mirror of https://github.com/ArduPilot/ardupilot
Sub: accept NAV_LOITER_UNLIM and NAV_LAND as command_int too
This commit is contained in:
parent
0f6bf8994f
commit
30101c1e0f
|
@ -459,21 +459,40 @@ bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) {
|
|||
return sub.set_home(loc, _lock);
|
||||
}
|
||||
|
||||
|
||||
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_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
||||
{
|
||||
switch (packet.command) {
|
||||
switch(packet.command) {
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
return handle_MAV_CMD_NAV_LOITER_UNLIM(packet);
|
||||
|
||||
case MAV_CMD_NAV_LAND:
|
||||
return handle_MAV_CMD_NAV_LAND(packet);
|
||||
|
||||
}
|
||||
|
||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (!sub.set_mode(Mode::Number::POSHOLD, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
case MAV_CMD_NAV_LAND:
|
||||
MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (!sub.set_mode(Mode::Number::SURFACE, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
||||
{
|
||||
switch (packet.command) {
|
||||
|
||||
case MAV_CMD_CONDITION_YAW:
|
||||
// param1 : target angle [0-360]
|
||||
|
|
|
@ -22,6 +22,8 @@ protected:
|
|||
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;
|
||||
|
||||
// override sending of scaled_pressure3 to send on-board temperature:
|
||||
void send_scaled_pressure3() override;
|
||||
|
||||
|
@ -51,6 +53,9 @@ private:
|
|||
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
|
||||
MAV_RESULT handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet);
|
||||
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
int16_t high_latency_target_altitude() const override;
|
||||
uint8_t high_latency_tgt_heading() const override;
|
||||
|
|
Loading…
Reference in New Issue