mirror of https://github.com/ArduPilot/ardupilot
Rover: allow WATER_DEPTH mavlink message rate to be specified
... and reduce the default rate this is currently unconditionally streamed at 50Hz, chewing up all available bandwidth on some telemetry radios.
This commit is contained in:
parent
6e49333a40
commit
c5284c6fdf
|
@ -589,6 +589,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||||
MSG_WIND,
|
MSG_WIND,
|
||||||
#if AP_RANGEFINDER_ENABLED
|
#if AP_RANGEFINDER_ENABLED
|
||||||
MSG_RANGEFINDER,
|
MSG_RANGEFINDER,
|
||||||
|
MSG_WATER_DEPTH,
|
||||||
#endif
|
#endif
|
||||||
MSG_DISTANCE_SENSOR,
|
MSG_DISTANCE_SENSOR,
|
||||||
MSG_SYSTEM_TIME,
|
MSG_SYSTEM_TIME,
|
||||||
|
|
|
@ -79,10 +79,6 @@ void Rover::Log_Write_Depth()
|
||||||
(double)(s->distance()),
|
(double)(s->distance()),
|
||||||
temp_C);
|
temp_C);
|
||||||
}
|
}
|
||||||
#if AP_RANGEFINDER_ENABLED
|
|
||||||
// send water depth and temp to ground station
|
|
||||||
gcs().send_message(MSG_WATER_DEPTH);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue