Rover: support running MAV_CMD_NAV_SET_YAW_SPEED as command_int

This commit is contained in:
Peter Barker 2023-08-25 10:15:32 +10:00 committed by Peter Barker
parent e3f0904616
commit 76c6d537ed
2 changed files with 5 additions and 11 deletions

View File

@ -680,17 +680,16 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
}
return MAV_RESULT_FAILED;
case MAV_CMD_NAV_SET_YAW_SPEED:
return handle_command_nav_set_yaw_speed(packet, msg);
default:
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
}
MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
case MAV_CMD_NAV_SET_YAW_SPEED:
{
// param1 : yaw angle to adjust direction by in centidegress
// param2 : Speed - normalized to 0 .. 1
// param3 : 0 = absolute, 1 = relative
@ -709,11 +708,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
rover.mode_guided.set_desired_heading_and_speed(packet.param1 * 100.0f, packet.param2);
}
return MAV_RESULT_ACCEPTED;
}
default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet)

View File

@ -17,8 +17,8 @@ protected:
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
void send_position_target_global_int() override;