mirror of https://github.com/ArduPilot/ardupilot
Plane: break out a method for set-position-target-global-int
This commit is contained in:
parent
1bfd9f3763
commit
5bc2b1a09b
|
@ -1329,6 +1329,16 @@ void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)
|
||||||
}
|
}
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
|
||||||
|
handle_set_position_target_global_int(msg);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
GCS_MAVLINK::handle_message(msg);
|
||||||
|
break;
|
||||||
|
} // end switch
|
||||||
|
} // end handle mavlink
|
||||||
|
|
||||||
|
void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
// Only want to allow companion computer position control when
|
// Only want to allow companion computer position control when
|
||||||
// in a certain mode to avoid inadvertently sending these
|
// in a certain mode to avoid inadvertently sending these
|
||||||
|
@ -1338,7 +1348,7 @@ void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)
|
||||||
// one uses the FENCE_ACTION = 4 (RTL) for geofence failures).
|
// one uses the FENCE_ACTION = 4 (RTL) for geofence failures).
|
||||||
if (plane.control_mode != &plane.mode_guided) {
|
if (plane.control_mode != &plane.mode_guided) {
|
||||||
//don't screw up failsafes
|
//don't screw up failsafes
|
||||||
break;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_set_position_target_global_int_t pos_target;
|
mavlink_set_position_target_global_int_t pos_target;
|
||||||
|
@ -1378,16 +1388,8 @@ void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)
|
||||||
handle_change_alt_request(cmd);
|
handle_change_alt_request(cmd);
|
||||||
}
|
}
|
||||||
} // end if alt_mask
|
} // end if alt_mask
|
||||||
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
default:
|
|
||||||
GCS_MAVLINK::handle_message(msg);
|
|
||||||
break;
|
|
||||||
} // end switch
|
|
||||||
} // end handle mavlink
|
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet);
|
const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet);
|
||||||
|
|
|
@ -66,6 +66,8 @@ private:
|
||||||
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet);
|
||||||
|
|
||||||
|
void handle_set_position_target_global_int(const mavlink_message_t &msg);
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
||||||
void convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);
|
void convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);
|
||||||
|
|
Loading…
Reference in New Issue