GCS_MAVLink: add send_distance_sensor_downward function

This commit is contained in:
Pierre Kancir 2017-05-30 12:33:03 +02:00 committed by Francisco Ferreira
parent f0369bc507
commit 0848d96354
2 changed files with 12 additions and 0 deletions

View File

@ -144,6 +144,7 @@ public:
bool send_battery_status(const AP_BattMonitor &battery) const;
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_ahrs2(AP_AHRS &ahrs);
bool send_gps_raw(AP_GPS &gps);
void send_system_time(AP_GPS &gps);

View File

@ -245,6 +245,17 @@ bool GCS_MAVLINK::send_distance_sensor(const RangeFinder &rangefinder) const
return true;
}
void GCS_MAVLINK::send_distance_sensor_downward(const RangeFinder &rangefinder) const
{
// exit immediately if rangefinder is disabled or not downward looking
if (!rangefinder.has_data_orient(ROTATION_PITCH_270)) {
return;
}
uint8_t instance;
rangefinder.find_instance(ROTATION_PITCH_270, instance);
send_distance_sensor(rangefinder, instance);
}
// report AHRS2 state
void GCS_MAVLINK::send_ahrs2(AP_AHRS &ahrs)
{