Browse Source

rename barometer parameters to BARO prefix

zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
cd2f2f96eb
  1. 7
      AntennaTracker/Parameters.cpp
  2. 4
      ArduCopter/Parameters.cpp
  3. 6
      ArduPlane/Parameters.cpp
  4. 4
      ArduSub/Parameters.cpp
  5. 6
      Rover/Parameters.cpp
  6. 4
      Tools/AP_Periph/Parameters.cpp

7
AntennaTracker/Parameters.cpp

@ -213,11 +213,10 @@ const AP_Param::Info Tracker::var_info[] = { @@ -213,11 +213,10 @@ const AP_Param::Info Tracker::var_info[] = {
// @User: Standard
GSCALAR(pitch_max, "PITCH_MAX", PITCH_MAX_DEFAULT),
// barometer ground calibration. The GND_ prefix is chosen for
// compatibility with previous releases of ArduPlane
// @Group: GND_
// barometer library
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(barometer, "GND_", AP_Baro),
GOBJECT(barometer, "BARO", AP_Baro),
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/AP_Compass.cpp

4
ArduCopter/Parameters.cpp

@ -582,9 +582,9 @@ const AP_Param::Info Copter::var_info[] = { @@ -582,9 +582,9 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(sitl, "SIM_", SITL::SITL),
#endif
// @Group: GND_
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(barometer, "GND_", AP_Baro),
GOBJECT(barometer, "BARO", AP_Baro),
// GPS driver
// @Group: GPS_

6
ArduPlane/Parameters.cpp

@ -857,11 +857,9 @@ const AP_Param::Info Plane::var_info[] = { @@ -857,11 +857,9 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
ASCALAR(crash_detection_enable, "CRASH_DETECT", 0),
// barometer ground calibration. The GND_ prefix is chosen for
// compatibility with previous releases of ArduPlane
// @Group: GND_
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(barometer, "GND_", AP_Baro),
GOBJECT(barometer, "BARO", AP_Baro),
// GPS driver
// @Group: GPS_

4
ArduSub/Parameters.cpp

@ -500,9 +500,9 @@ const AP_Param::Info Sub::var_info[] = { @@ -500,9 +500,9 @@ const AP_Param::Info Sub::var_info[] = {
GOBJECT(sitl, "SIM_", SITL::SITL),
#endif
// @Group: GND_
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(barometer, "GND_", AP_Baro),
GOBJECT(barometer, "BARO", AP_Baro),
// GPS driver
// @Group: GPS_

6
Rover/Parameters.cpp

@ -236,11 +236,9 @@ const AP_Param::Info Rover::var_info[] = { @@ -236,11 +236,9 @@ const AP_Param::Info Rover::var_info[] = {
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
// barometer ground calibration. The GND_ prefix is chosen for
// compatibility with previous releases of ArduPlane
// @Group: GND_
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(barometer, "GND_", AP_Baro),
GOBJECT(barometer, "BARO", AP_Baro),
// @Group: RELAY_
// @Path: ../libraries/AP_Relay/AP_Relay.cpp

4
Tools/AP_Periph/Parameters.cpp

@ -66,9 +66,9 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { @@ -66,9 +66,9 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#ifdef HAL_PERIPH_ENABLE_BARO
// Baro driver
// @Group: BARO_
// @Group: BARO
// @Path: ../../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(baro, "BARO_", AP_Baro),
GOBJECT(baro, "BARO", AP_Baro),
GSCALAR(baro_enable, "BARO_ENABLE", 1),
#endif

Loading…
Cancel
Save