Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLink: convert to COMMAND_INT to handle MAV_CMD_DO_SET_HOME #24316

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 1 addition & 2 deletions libraries/GCS_MAVLink/GCS.h
Expand Up @@ -518,15 +518,14 @@ class GCS_MAVLINK
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);

virtual bool set_home_to_current_location(bool lock) = 0;
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);
Expand Down
35 changes: 3 additions & 32 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Expand Up @@ -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)) {
Expand Down Expand Up @@ -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:
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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);
Expand Down