mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: stop sending BATTERY2 by default
This commit is contained in:
parent
72c6977ea5
commit
76cb127067
|
@ -447,7 +447,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
|
||||
// @Param: EXTRA3
|
||||
// @DisplayName: Extra data type 3 stream rate to ground station
|
||||
// @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
|
||||
// @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
|
@ -526,7 +526,6 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||
#if AP_TERRAIN_AVAILABLE
|
||||
MSG_TERRAIN,
|
||||
#endif
|
||||
MSG_BATTERY2,
|
||||
MSG_BATTERY_STATUS,
|
||||
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
|
||||
MSG_OPTICAL_FLOW,
|
||||
|
|
Loading…
Reference in New Issue