Copter: handle DO_CHANGE_SPEED as both COMMAND_LONG and COMMAND_INT

This commit is contained in:
Peter Barker 2023-09-20 10:09:44 +10:00 committed by Peter Barker
parent c352de2dd8
commit c61022f596
2 changed files with 12 additions and 5 deletions

View File

@ -739,6 +739,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_co
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch(packet.command) {
case MAV_CMD_DO_CHANGE_SPEED:
return handle_MAV_CMD_DO_CHANGE_SPEED(packet);
#if MODE_FOLLOW_ENABLED == ENABLED
case MAV_CMD_DO_FOLLOW:
// param1: sysid of target to follow
@ -873,7 +877,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_CHANGE_SPEED:
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)
{
// param1 : Speed type (0 or 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)
// param2 : new speed in m/s
// param3 : unused
@ -897,10 +907,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
}
}
return MAV_RESULT_FAILED;
default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}
#if MODE_AUTO_ENABLED == ENABLED

View File

@ -98,6 +98,7 @@ private:
#endif // HAL_HIGH_LATENCY2_ENABLED
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_PARACHUTE(const mavlink_command_int_t &packet);