mirror of https://github.com/ArduPilot/ardupilot
Rover: add Airspeed to raw sensor stream rates
This commit is contained in:
parent
34aad934d1
commit
c3393d8d16
|
@ -421,7 +421,7 @@ void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mav
|
|||
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
||||
// @Param: RAW_SENS
|
||||
// @DisplayName: Raw sensor stream rate
|
||||
// @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3
|
||||
// @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED
|
||||
// @Units: Hz
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
|
@ -529,6 +529,7 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
|||
MSG_SCALED_PRESSURE,
|
||||
MSG_SCALED_PRESSURE2,
|
||||
MSG_SCALED_PRESSURE3,
|
||||
MSG_AIRSPEED,
|
||||
};
|
||||
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
MSG_SYS_STATUS,
|
||||
|
|
Loading…
Reference in New Issue