ArduCopter: support preflight calibration via command_int

This commit is contained in:
Peter Barker 2023-09-07 20:13:30 +10:00 committed by Peter Barker
parent 4f0b328674
commit 619b1ecd47
2 changed files with 3 additions and 3 deletions

View File

@ -653,9 +653,9 @@ void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &p
#endif
}
MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
if (is_equal(packet.param6,1.0f)) {
if (packet.y == 1) {
// compassmot calibration
return copter.mavlink_compassmot(*this);
}

View File

@ -26,7 +26,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_attitude_target() override;
void send_position_target_global_int() override;