mirror of https://github.com/ArduPilot/ardupilot
Blimp: support preflight calibration via command_int
This commit is contained in:
parent
2d5452d540
commit
0f48bf7552
|
@ -417,7 +417,7 @@ void GCS_MAVLINK_Blimp::send_banner()
|
|||
send_text(MAV_SEVERITY_INFO, "Frame: %s", blimp.get_frame_string());
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Blimp::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
||||
MAV_RESULT GCS_MAVLINK_Blimp::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
||||
{
|
||||
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
|
||||
}
|
||||
|
|
|
@ -21,7 +21,7 @@ protected:
|
|||
bool params_ready() const override;
|
||||
void send_banner() override;
|
||||
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
||||
|
||||
void send_position_target_global_int() override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue