Skip to content

Commit

Permalink
Rover: rely on magic long-to-int conversion to handle MAV_CMD_DO_CHAN…
Browse files Browse the repository at this point in the history
…GE_SPEED
  • Loading branch information
peterbarker authored and rmackay9 committed Aug 24, 2023
1 parent 2b9b3c0 commit 8decb9d
Showing 1 changed file with 0 additions and 8 deletions.
8 changes: 0 additions & 8 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -678,14 +678,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
}
return MAV_RESULT_FAILED;

case MAV_CMD_DO_CHANGE_SPEED:
// param1 : unused
// param2 : new speed in m/s
if (!rover.control_mode->set_desired_speed(packet.param2)) {
return MAV_RESULT_FAILED;
}
return MAV_RESULT_ACCEPTED;

case MAV_CMD_NAV_SET_YAW_SPEED:
{
// param1 : yaw angle to adjust direction by in centidegress
Expand Down

0 comments on commit 8decb9d

Please sign in to comment.