GCS_MAVLink: allow Plane to override method so it can set calib. flag
This commit is contained in:
parent
c80714b820
commit
f6b7ca75e9
@ -297,6 +297,11 @@ protected:
|
||||
virtual uint32_t telem_delay() const = 0;
|
||||
|
||||
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
|
||||
|
||||
// generally this should not be overridden; Plane overrides it to ensure
|
||||
// failsafe isn't triggered during calibation
|
||||
virtual MAV_RESULT handle_command_preflight_calibration(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);
|
||||
@ -318,8 +323,6 @@ 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);
|
||||
|
Loading…
Reference in New Issue
Block a user