Skip to content

Commit

Permalink
Fix bug: rotateToYaw not working
Browse files Browse the repository at this point in the history
- `isYawWithinMargin` should receive the target yaw degree as the first argument
- the original stop criterion does not stop rotation due to inertia, so the resulted yaw is not guaranteed.
  • Loading branch information
songxiaocheng committed Apr 2, 2020
1 parent b709ce8 commit 258e5e4
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -339,6 +339,7 @@ class MultirotorApiBase : public VehicleApiBase {
//TODO: make this configurable?
float landing_vel_ = 0.2f; //velocity to use for landing
float approx_zero_vel_ = 0.05f;
float approx_zero_angular_vel_ = 0.01f;
};

}} //namespace
Expand Down
34 changes: 19 additions & 15 deletions AirLib/src/vehicles/multirotor/api/MultirotorApiBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -446,25 +446,29 @@ bool MultirotorApiBase::rotateToYaw(float yaw, float timeout_sec, float margin)
{
SingleTaskCall lock(this);

const YawMode yaw_mode(false, VectorMath::normalizeAngle(yaw));
Waiter waiter(getCommandPeriod(), timeout_sec, getCancelToken());

float estimated_pitch, estimated_roll, estimated_yaw;
if (timeout_sec <= 0)
return true;

auto start_pos = getPosition();
do {
auto kinematics = getKinematicsEstimated();
VectorMath::toEulerianAngle(kinematics.pose.orientation,
estimated_pitch, estimated_roll, estimated_yaw);

if (isYawWithinMargin(estimated_yaw, margin))
return true;
float yaw_target = VectorMath::normalizeAngle(yaw);
YawMode move_yaw_mode(false, yaw_target);
YawMode stop_yaw_mode(true, 0);

//change yaw by moving to same position but constant yaw mode
moveToPositionInternal(start_pos, yaw_mode);
} while (waiter.sleep());
return waitForFunction([&]() {
if (isYawWithinMargin(yaw_target, margin)) { // yaw is within margin, then trying to stop rotation
moveToPositionInternal(start_pos, stop_yaw_mode); // let yaw rate be zero
auto yaw_rate = getKinematicsEstimated().twist.angular.z();
if (abs(yaw_rate) <= approx_zero_angular_vel_) { // already sopped
return true; //stop all for stably achieving the goal
}
}
else { // yaw is not within margin, go on rotation
moveToPositionInternal(start_pos, move_yaw_mode);
}

return false; //we are not exiting because we reached yaw
// yaw is not within margin
return false; //keep moving until timeout
}, timeout_sec).isComplete();
}

bool MultirotorApiBase::rotateByYawRate(float yaw_rate, float duration)
Expand Down

0 comments on commit 258e5e4

Please sign in to comment.