ArduSub: change rangefinder msg for common one
This commit is contained in:
parent
e124cddeeb
commit
57ef598c07
@ -339,20 +339,6 @@ void NOINLINE Sub::send_current_waypoint(mavlink_channel_t chan)
|
||||
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
|
||||
}
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
void NOINLINE Sub::send_rangefinder(mavlink_channel_t chan)
|
||||
{
|
||||
// exit immediately if rangefinder is disabled
|
||||
if (!rangefinder.has_data_orient(ROTATION_PITCH_270)) {
|
||||
return;
|
||||
}
|
||||
mavlink_msg_rangefinder_send(
|
||||
chan,
|
||||
rangefinder.distance_cm_orient(ROTATION_PITCH_270) * 0.01f,
|
||||
rangefinder.voltage_mv_orient(ROTATION_PITCH_270) * 0.001f);
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
send RPM packet
|
||||
*/
|
||||
@ -560,7 +546,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||
case MSG_RANGEFINDER:
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||
sub.send_rangefinder(chan);
|
||||
send_rangefinder(sub.rangefinder);
|
||||
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
||||
send_distance_sensor_downward(sub.rangefinder);
|
||||
#endif
|
||||
|
@ -484,7 +484,6 @@ private:
|
||||
void send_radio_out(mavlink_channel_t chan);
|
||||
void send_vfr_hud(mavlink_channel_t chan);
|
||||
void send_current_waypoint(mavlink_channel_t chan);
|
||||
void send_rangefinder(mavlink_channel_t chan);
|
||||
#if RPM_ENABLED == ENABLED
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void rpm_update();
|
||||
|
Loading…
Reference in New Issue
Block a user