Blimp: add and use AP_MAVLINK_COMMAND_LONG_ENABLED
This commit is contained in:
parent
4b285fa579
commit
7a5ee38b9f
@ -488,6 +488,7 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_in
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
||||||
bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const
|
bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const
|
||||||
{
|
{
|
||||||
if (packet_command == MAV_CMD_NAV_TAKEOFF) {
|
if (packet_command == MAV_CMD_NAV_TAKEOFF) {
|
||||||
@ -496,6 +497,7 @@ bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD pac
|
|||||||
}
|
}
|
||||||
return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);
|
return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg)
|
void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
|
@ -29,7 +29,9 @@ protected:
|
|||||||
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;
|
||||||
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
||||||
|
|
||||||
|
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
||||||
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
|
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
|
||||||
|
#endif
|
||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||||
|
Loading…
Reference in New Issue
Block a user