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

Allow compass mag cal command to come in as COMMAND_INT #24480

Merged
merged 2 commits into from Aug 8, 2023
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
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass.h
Expand Up @@ -196,7 +196,7 @@ friend class AP_Compass_Backend;
/*
handle an incoming MAG_CAL command
*/
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet);
MAV_RESULT handle_mag_cal_command(const mavlink_command_int_t &packet);

bool send_mag_cal_progress(const class GCS_MAVLINK& link);
bool send_mag_cal_report(const class GCS_MAVLINK& link);
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_Calibration.cpp
Expand Up @@ -371,7 +371,7 @@ uint8_t Compass::_get_cal_mask()
/*
handle an incoming MAG_CAL command
*/
MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)
{
MAV_RESULT result = MAV_RESULT_FAILED;

Expand All @@ -392,7 +392,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
bool retry = !is_zero(packet.param2);
bool autosave = !is_zero(packet.param3);
float delay = packet.param4;
bool autoreboot = !is_zero(packet.param5);
bool autoreboot = packet.x != 0;

if (mag_mask == 0) { // 0 means all
_reset_compass_id();
Expand Down
7 changes: 4 additions & 3 deletions libraries/GCS_MAVLink/GCS.h
Expand Up @@ -649,7 +649,10 @@ class GCS_MAVLINK
MAV_RESULT handle_command_do_set_roi_none();

virtual MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);

MAV_RESULT handle_command_mag_cal(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet);

MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet);
virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
Expand All @@ -674,8 +677,6 @@ class GCS_MAVLINK

void handle_optical_flow(const mavlink_message_t &msg);

MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet);

void handle_manual_control(const mavlink_message_t &msg);

// default empty handling of LANDING_TARGET
Expand Down
34 changes: 14 additions & 20 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Expand Up @@ -3712,22 +3712,25 @@ void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg)
#endif


#if COMPASS_CAL_ENABLED
/*
handle MAV_CMD_FIXED_MAG_CAL_YAW
*/
MAV_RESULT GCS_MAVLINK::handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet)
{
#if COMPASS_CAL_ENABLED
Compass &compass = AP::compass();
return compass.mag_cal_fixed_yaw(packet.param1,
uint8_t(packet.param2),
packet.param3,
packet.param4);
#else
return MAV_RESULT_UNSUPPORTED;
#endif
}

MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_int_t &packet)
{
return AP::compass().handle_mag_cal_command(packet);
}
#endif // COMPASS_CAL_ENABLED

/*
handle MAV_CMD_CAN_FORWARD
*/
Expand Down Expand Up @@ -4426,13 +4429,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_
return MAV_RESULT_FAILED;
}

#if COMPASS_CAL_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet)
{
return AP::compass().handle_mag_cal_command(packet);
}
#endif

#if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
{
Expand Down Expand Up @@ -4696,15 +4692,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
break;
#endif // HAL_HIGH_LATENCY2_ENABLED

#if COMPASS_CAL_ENABLED
case MAV_CMD_DO_START_MAG_CAL:
case MAV_CMD_DO_ACCEPT_MAG_CAL:
case MAV_CMD_DO_CANCEL_MAG_CAL: {
result = handle_command_mag_cal(packet);
break;
}
#endif

case MAV_CMD_START_RX_PAIR:
result = handle_rc_bind(packet);
break;
Expand Down Expand Up @@ -5146,8 +5133,15 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
#endif
case MAV_CMD_COMPONENT_ARM_DISARM:
return handle_command_component_arm_disarm(packet);

#if COMPASS_CAL_ENABLED
case MAV_CMD_FIXED_MAG_CAL_YAW:
return handle_command_fixed_mag_cal_yaw(packet);
case MAV_CMD_DO_START_MAG_CAL:
case MAV_CMD_DO_ACCEPT_MAG_CAL:
case MAV_CMD_DO_CANCEL_MAG_CAL:
return handle_command_mag_cal(packet);
#endif

#if AP_SCRIPTING_ENABLED
case MAV_CMD_SCRIPTING:
Expand Down