GCS_MAVLink: handle MAV_CMD_NAV_TAKEOFF via command_long and command_in

This commit is contained in:
Peter Barker 2023-10-18 17:30:31 +11:00 committed by Peter Barker
parent f9165c786d
commit 21eaa08333
2 changed files with 4 additions and 3 deletions

View File

@ -651,7 +651,7 @@ protected:
virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const;
MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet);
virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
@ -728,7 +728,7 @@ protected:
// If location is not present in the command then just omit frame.
// this method ensures the passed-in structure is entirely
// initialised.
static void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT);
virtual void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT);
// methods to extract a Location object from a command_long or command_int
bool location_from_command_t(const mavlink_command_long_t &in, MAV_FRAME in_frame, Location &out);

View File

@ -4858,7 +4858,8 @@ bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command)
case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_SET_ROI:
case MAV_CMD_DO_SET_ROI_LOCATION:
case MAV_CMD_NAV_TAKEOFF:
// case MAV_CMD_NAV_TAKEOFF: // technically yes, but we don't do lat/lng
// case MAV_CMD_NAV_VTOL_TAKEOFF:
case MAV_CMD_DO_REPOSITION:
case MAV_CMD_EXTERNAL_POSITION_ESTIMATE:
return true;