mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: convert to COMMAND_INT to handle MAV_CMD_DO_SET_HOME
This commit is contained in:
parent
49226b6dcf
commit
ae8d3724cd
|
@ -518,7 +518,7 @@ protected:
|
|||
void handle_set_mode(const mavlink_message_t &msg);
|
||||
void handle_command_int(const mavlink_message_t &msg);
|
||||
|
||||
MAV_RESULT handle_command_int_do_set_home(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet);
|
||||
virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet);
|
||||
|
||||
|
@ -526,7 +526,6 @@ protected:
|
|||
virtual bool set_home(const Location& loc, bool lock) = 0;
|
||||
|
||||
virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_set_home(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_aux_function(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_storage_format(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||
void handle_mission_request_list(const mavlink_message_t &msg);
|
||||
|
|
|
@ -4601,32 +4601,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_long_t &packe
|
|||
#endif
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_long_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param1, 1.0f) || (is_zero(packet.param5) && is_zero(packet.param6))) {
|
||||
// param1 is 1 (or both lat and lon are zero); use current location
|
||||
if (!set_home_to_current_location(true)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
// ensure param1 is zero
|
||||
if (!is_zero(packet.param1)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
Location new_home_loc;
|
||||
if (!location_from_command_t(packet, MAV_FRAME_GLOBAL, new_home_loc)) {
|
||||
return MAV_RESULT_DENIED;
|
||||
}
|
||||
|
||||
if (!set_home(new_home_loc, true)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
|
@ -4667,6 +4641,7 @@ MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_lo
|
|||
{ MAV_CMD_FIXED_MAG_CAL_YAW, MAV_FRAME_GLOBAL_RELATIVE_ALT },
|
||||
{ MAV_CMD_DO_SET_ROI, MAV_FRAME_GLOBAL_RELATIVE_ALT },
|
||||
{ MAV_CMD_DO_SET_ROI_LOCATION, MAV_FRAME_GLOBAL_RELATIVE_ALT },
|
||||
{ MAV_CMD_DO_SET_HOME, MAV_FRAME_GLOBAL },
|
||||
};
|
||||
|
||||
// map from command to frame:
|
||||
|
@ -4711,10 +4686,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||
result = handle_command_do_send_banner(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_HOME:
|
||||
result = handle_command_do_set_home(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
result = handle_command_do_fence_enable(packet);
|
||||
break;
|
||||
|
@ -5039,7 +5010,7 @@ void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg)
|
|||
}
|
||||
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_int_do_set_home(const mavlink_command_int_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) {
|
||||
// param1 is 1 (or both lat and lon are zero); use current location
|
||||
|
@ -5182,7 +5153,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|||
case MAV_CMD_DO_SET_ROI_NONE:
|
||||
return handle_command_do_set_roi_none();
|
||||
case MAV_CMD_DO_SET_HOME:
|
||||
return handle_command_int_do_set_home(packet);
|
||||
return handle_command_do_set_home(packet);
|
||||
#if AP_AHRS_POSITION_RESET_ENABLED
|
||||
case MAV_CMD_EXTERNAL_POSITION_ESTIMATE:
|
||||
return handle_command_int_external_position_estimate(packet);
|
||||
|
|
Loading…
Reference in New Issue