mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: handle preflight calibrations
This commit is contained in:
parent
c3e70e477d
commit
09d4e36970
@ -297,6 +297,8 @@ protected:
|
||||
virtual uint32_t telem_delay() const = 0;
|
||||
|
||||
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
|
||||
virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet);
|
||||
|
||||
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
|
||||
@ -316,6 +318,8 @@ protected:
|
||||
void handle_data_packet(mavlink_message_t *msg);
|
||||
private:
|
||||
|
||||
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet);
|
||||
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
||||
|
||||
MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode);
|
||||
|
@ -2219,6 +2219,21 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlin
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
{
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
{
|
||||
if (hal.util->get_soft_armed()) {
|
||||
// *preflight*, remember?
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
// now call subclass methods:
|
||||
return _handle_command_preflight_calibration(packet);
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet)
|
||||
{
|
||||
Compass *compass = get_compass();
|
||||
@ -2306,6 +2321,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
result = handle_command_preflight_calibration(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
|
||||
result = handle_command_preflight_set_sensor_offsets(packet);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user