mirror of https://github.com/ArduPilot/ardupilot
Blimp: add Airspeed to raw sensor stream rates
This commit is contained in:
parent
29646299ef
commit
34aad934d1
|
@ -218,7 +218,7 @@ bool GCS_MAVLINK_Blimp::try_send_message(enum ap_message id)
|
||||||
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
||||||
// @Param: RAW_SENS
|
// @Param: RAW_SENS
|
||||||
// @DisplayName: Raw sensor stream rate
|
// @DisplayName: Raw sensor stream rate
|
||||||
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
|
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3, AIRSPEED and SENSOR_OFFSETS to ground station
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
@ -315,6 +315,7 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
||||||
MSG_SCALED_PRESSURE,
|
MSG_SCALED_PRESSURE,
|
||||||
MSG_SCALED_PRESSURE2,
|
MSG_SCALED_PRESSURE2,
|
||||||
MSG_SCALED_PRESSURE3,
|
MSG_SCALED_PRESSURE3,
|
||||||
|
MSG_AIRSPEED,
|
||||||
};
|
};
|
||||||
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||||
MSG_SYS_STATUS,
|
MSG_SYS_STATUS,
|
||||||
|
|
Loading…
Reference in New Issue