mirror of https://github.com/ArduPilot/ardupilot
GCS_Common: rename send_rangefinder to send_rangefinder_downward
This commit is contained in:
parent
57ef598c07
commit
d5cc1e64ed
|
@ -458,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);
|
||||
send_rangefinder(copter.rangefinder);
|
||||
send_rangefinder_downward(copter.rangefinder);
|
||||
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
||||
send_distance_sensor_downward(copter.rangefinder);
|
||||
#endif
|
||||
|
|
|
@ -585,7 +585,7 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
|||
|
||||
case MSG_RANGEFINDER:
|
||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||
send_rangefinder(plane.rangefinder);
|
||||
send_rangefinder_downward(plane.rangefinder);
|
||||
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
||||
send_distance_sensor_downward(plane.rangefinder);
|
||||
break;
|
||||
|
|
|
@ -546,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);
|
||||
send_rangefinder(sub.rangefinder);
|
||||
send_rangefinder_downward(sub.rangefinder);
|
||||
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
||||
send_distance_sensor_downward(sub.rangefinder);
|
||||
#endif
|
||||
|
|
|
@ -145,7 +145,7 @@ public:
|
|||
void send_distance_sensor(const RangeFinder &rangefinder, const uint8_t instance) const;
|
||||
bool send_distance_sensor(const RangeFinder &rangefinder) const;
|
||||
void send_distance_sensor_downward(const RangeFinder &rangefinder) const;
|
||||
void send_rangefinder(const RangeFinder &rangefinder) const;
|
||||
void send_rangefinder_downward(const RangeFinder &rangefinder) const;
|
||||
void send_ahrs2(AP_AHRS &ahrs);
|
||||
bool send_gps_raw(AP_GPS &gps);
|
||||
void send_system_time(AP_GPS &gps);
|
||||
|
|
|
@ -256,7 +256,7 @@ void GCS_MAVLINK::send_distance_sensor_downward(const RangeFinder &rangefinder)
|
|||
send_distance_sensor(rangefinder, instance);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_rangefinder(const RangeFinder &rangefinder) const
|
||||
void GCS_MAVLINK::send_rangefinder_downward(const RangeFinder &rangefinder) const
|
||||
{
|
||||
// exit immediately if rangefinder is disabled or not downward looking
|
||||
if (!rangefinder.has_data_orient(ROTATION_PITCH_270)) {
|
||||
|
|
Loading…
Reference in New Issue