mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move sending of WATER_DEPTH into Rover code
only compiled in on Rover at the moment. need to add an additional Rover-specific check for frame type, so move this code into Rover for now.
This commit is contained in:
parent
c5284c6fdf
commit
33a788ebb5
|
@ -403,7 +403,6 @@ public:
|
||||||
#if AP_WINCH_ENABLED
|
#if AP_WINCH_ENABLED
|
||||||
virtual void send_winch_status() const {};
|
virtual void send_winch_status() const {};
|
||||||
#endif
|
#endif
|
||||||
void send_water_depth() const;
|
|
||||||
int8_t battery_remaining_pct(const uint8_t instance) const;
|
int8_t battery_remaining_pct(const uint8_t instance) const;
|
||||||
|
|
||||||
#if HAL_HIGH_LATENCY2_ENABLED
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
|
|
@ -5966,57 +5966,6 @@ void GCS_MAVLINK::send_generator_status() const
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
||||||
void GCS_MAVLINK::send_water_depth() const
|
|
||||||
{
|
|
||||||
if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
RangeFinder *rangefinder = RangeFinder::get_singleton();
|
|
||||||
|
|
||||||
if (rangefinder == nullptr || !rangefinder->has_orientation(ROTATION_PITCH_270)){
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// get position
|
|
||||||
const AP_AHRS &ahrs = AP::ahrs();
|
|
||||||
Location loc;
|
|
||||||
IGNORE_RETURN(ahrs.get_location(loc));
|
|
||||||
|
|
||||||
for (uint8_t i=0; i<rangefinder->num_sensors(); i++) {
|
|
||||||
const AP_RangeFinder_Backend *s = rangefinder->get_backend(i);
|
|
||||||
|
|
||||||
if (s == nullptr || s->orientation() != ROTATION_PITCH_270 || !s->has_data()) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
// get temperature
|
|
||||||
float temp_C;
|
|
||||||
if (!s->get_temp(temp_C)) {
|
|
||||||
temp_C = 0.0f;
|
|
||||||
}
|
|
||||||
|
|
||||||
const bool sensor_healthy = (s->status() == RangeFinder::Status::Good);
|
|
||||||
|
|
||||||
mavlink_msg_water_depth_send(
|
|
||||||
chan,
|
|
||||||
AP_HAL::millis(), // time since system boot TODO: take time of measurement
|
|
||||||
i, // rangefinder instance
|
|
||||||
sensor_healthy, // sensor healthy
|
|
||||||
loc.lat, // latitude of vehicle
|
|
||||||
loc.lng, // longitude of vehicle
|
|
||||||
loc.alt * 0.01f, // altitude of vehicle (MSL)
|
|
||||||
ahrs.get_roll(), // roll in radians
|
|
||||||
ahrs.get_pitch(), // pitch in radians
|
|
||||||
ahrs.get_yaw(), // yaw in radians
|
|
||||||
s->distance(), // distance in meters
|
|
||||||
temp_C); // temperature in degC
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
#endif // AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
||||||
|
|
||||||
#if HAL_ADSB_ENABLED
|
#if HAL_ADSB_ENABLED
|
||||||
void GCS_MAVLINK::send_uavionix_adsb_out_status() const
|
void GCS_MAVLINK::send_uavionix_adsb_out_status() const
|
||||||
{
|
{
|
||||||
|
@ -6547,13 +6496,6 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
||||||
case MSG_WATER_DEPTH:
|
|
||||||
CHECK_PAYLOAD_SIZE(WATER_DEPTH);
|
|
||||||
send_water_depth();
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAL_HIGH_LATENCY2_ENABLED
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
case MSG_HIGH_LATENCY2:
|
case MSG_HIGH_LATENCY2:
|
||||||
CHECK_PAYLOAD_SIZE(HIGH_LATENCY2);
|
CHECK_PAYLOAD_SIZE(HIGH_LATENCY2);
|
||||||
|
|
Loading…
Reference in New Issue