Copter: allow MAV_CMD_CONDITION_YAW to be run as COMMAND_INT

This commit is contained in:
Peter Barker 2023-09-20 16:09:23 +10:00 committed by Andrew Tridgell
parent ad126cc96e
commit ad9a36c157
2 changed files with 11 additions and 5 deletions

View File

@ -740,6 +740,9 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
{ {
switch(packet.command) { switch(packet.command) {
case MAV_CMD_CONDITION_YAW:
return handle_MAV_CMD_CONDITION_YAW(packet);
case MAV_CMD_DO_CHANGE_SPEED: case MAV_CMD_DO_CHANGE_SPEED:
return handle_MAV_CMD_DO_CHANGE_SPEED(packet); return handle_MAV_CMD_DO_CHANGE_SPEED(packet);
@ -860,7 +863,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
} }
return MAV_RESULT_ACCEPTED; return MAV_RESULT_ACCEPTED;
case MAV_CMD_CONDITION_YAW: default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)
{
// param1 : target angle [0-360] // param1 : target angle [0-360]
// param2 : speed during change [deg per second] // param2 : speed during change [deg per second]
// param3 : direction (-1:ccw, +1:cw) // param3 : direction (-1:ccw, +1:cw)
@ -876,10 +885,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_ACCEPTED; return MAV_RESULT_ACCEPTED;
} }
return MAV_RESULT_FAILED; return MAV_RESULT_FAILED;
default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
} }
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet) MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)

View File

@ -98,6 +98,7 @@ private:
#endif // HAL_HIGH_LATENCY2_ENABLED #endif // HAL_HIGH_LATENCY2_ENABLED
MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);
MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);