mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move sending of RPM message up
This commit is contained in:
parent
8d6748dc4f
commit
bb1ae30594
|
@ -233,6 +233,7 @@ public:
|
|||
void send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag));
|
||||
void send_sys_status();
|
||||
void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc);
|
||||
void send_rpm() const;
|
||||
|
||||
// return a bitmap of active channels. Used by libraries to loop
|
||||
// over active channels to send to all active channels
|
||||
|
|
|
@ -3817,6 +3817,22 @@ void GCS_MAVLINK::send_hwstatus()
|
|||
0);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_rpm() const
|
||||
{
|
||||
AP_RPM *rpm = AP::rpm();
|
||||
if (rpm == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!rpm->enabled(0) && !rpm->enabled(1)) {
|
||||
return;
|
||||
}
|
||||
|
||||
mavlink_msg_rpm_send(
|
||||
chan,
|
||||
rpm->get_rpm(0),
|
||||
rpm->get_rpm(1));
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_sys_status()
|
||||
{
|
||||
|
@ -4000,6 +4016,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||
send_gps_global_origin();
|
||||
break;
|
||||
|
||||
case MSG_RPM:
|
||||
CHECK_PAYLOAD_SIZE(RPM);
|
||||
send_rpm();
|
||||
break;
|
||||
|
||||
case MSG_CURRENT_WAYPOINT:
|
||||
case MSG_MISSION_ITEM_REACHED:
|
||||
case MSG_NEXT_MISSION_REQUEST:
|
||||
|
|
Loading…
Reference in New Issue