mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: move sending of RPM message up
This commit is contained in:
parent
85d9dd6f64
commit
0edba9070f
@ -310,19 +310,6 @@ void Plane::send_wind(mavlink_channel_t chan)
|
||||
wind.z);
|
||||
}
|
||||
|
||||
/*
|
||||
send RPM packet
|
||||
*/
|
||||
void NOINLINE Plane::send_rpm(mavlink_channel_t chan)
|
||||
{
|
||||
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
|
||||
mavlink_msg_rpm_send(
|
||||
chan,
|
||||
rpm_sensor.get_rpm(0),
|
||||
rpm_sensor.get_rpm(1));
|
||||
}
|
||||
}
|
||||
|
||||
// sends a single pid info over the provided channel
|
||||
void GCS_MAVLINK_Plane::send_pid_info(const AP_Logger::PID_Info *pid_info,
|
||||
const uint8_t axis, const float achieved)
|
||||
@ -451,11 +438,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
plane.send_wind(chan);
|
||||
break;
|
||||
|
||||
case MSG_RPM:
|
||||
CHECK_PAYLOAD_SIZE(RPM);
|
||||
plane.send_rpm(chan);
|
||||
break;
|
||||
|
||||
case MSG_ADSB_VEHICLE:
|
||||
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||
plane.adsb.send_adsb_vehicle(chan);
|
||||
|
@ -792,7 +792,6 @@ private:
|
||||
void send_fence_status(mavlink_channel_t chan);
|
||||
void send_servo_out(mavlink_channel_t chan);
|
||||
void send_wind(mavlink_channel_t chan);
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
|
||||
void send_aoa_ssa(mavlink_channel_t chan);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user