Skip to content

Commit

Permalink
Rover: minor comment fix to set-position-target handling
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Feb 8, 2019
1 parent 9707a73 commit d50a94a
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions APMrover2/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -938,13 +938,13 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
// consume velocity and turn rate
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
} else if (pos_ignore && !vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
// consume velocity
// consume velocity and heading
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
} else if (pos_ignore && vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
// consume just target heading (probably only skid steering vehicles can do this)
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
} else if (pos_ignore && vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
// consume just turn rate(probably only skid steering vehicles can do this)
// consume just turn rate (probably only skid steering vehicles can do this)
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
}
break;
Expand Down

0 comments on commit d50a94a

Please sign in to comment.