mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: change rangefinder msg for common one
This commit is contained in:
parent
156863d10a
commit
261eb387eb
|
@ -703,7 +703,6 @@ private:
|
|||
void send_hwstatus(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);
|
||||
void send_proximity(mavlink_channel_t chan, uint16_t count_max);
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void rpm_update();
|
||||
|
|
|
@ -207,20 +207,6 @@ void NOINLINE Copter::send_current_waypoint(mavlink_channel_t chan)
|
|||
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
|
||||
}
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
void NOINLINE Copter::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
|
||||
|
||||
void NOINLINE Copter::send_proximity(mavlink_channel_t chan, uint16_t count_max)
|
||||
{
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
|
@ -472,7 +458,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
|||
case MSG_RANGEFINDER:
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||
copter.send_rangefinder(chan);
|
||||
send_rangefinder(copter.rangefinder);
|
||||
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
||||
send_distance_sensor_downward(copter.rangefinder);
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue