mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
ArduSub: accept MAV_CMD_CONDITION_YAW as both long and int in Sub
This commit is contained in:
parent
805901dc18
commit
4843fa4c4b
@ -467,6 +467,9 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_
|
|||||||
{
|
{
|
||||||
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);
|
||||||
|
|
||||||
@ -503,11 +506,8 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t
|
|||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
switch (packet.command) {
|
|
||||||
|
|
||||||
case MAV_CMD_CONDITION_YAW:
|
|
||||||
// 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)
|
||||||
@ -518,11 +518,7 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon
|
|||||||
sub.mode_auto.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
|
sub.mode_auto.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_DENIED;
|
||||||
|
|
||||||
default:
|
|
||||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet)
|
||||||
|
@ -20,7 +20,6 @@ protected:
|
|||||||
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
||||||
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
|
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
|
||||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
MAV_RESULT _handle_command_preflight_calibration(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_packet(const mavlink_command_int_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;
|
||||||
|
|
||||||
@ -53,6 +52,7 @@ private:
|
|||||||
|
|
||||||
int16_t vfr_hud_throttle() const override;
|
int16_t vfr_hud_throttle() const override;
|
||||||
|
|
||||||
|
MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_MAV_CMD_MISSION_START(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);
|
||||||
|
Loading…
Reference in New Issue
Block a user