Skip to content

Commit e708a5b

Browse files
committed
move AP_Baro calls up to AP_Vehicle
1 parent 3a48a76 commit e708a5b

39 files changed

+137
-125
lines changed

AntennaTracker/Parameters.cpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -208,11 +208,6 @@ const AP_Param::Info Tracker::var_info[] = {
208208
// @User: Standard
209209
GSCALAR(pitch_max, "PITCH_MAX", PITCH_MAX_DEFAULT),
210210

211-
// barometer library
212-
// @Group: BARO
213-
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
214-
GOBJECT(barometer, "BARO", AP_Baro),
215-
216211
// @Group: COMPASS_
217212
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
218213
GOBJECT(compass, "COMPASS_", Compass),
@@ -608,6 +603,10 @@ void Tracker::load_parameters(void)
608603

609604
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
610605

606+
#if AP_BARO_ENABLED
607+
AP::baro().convert_parameters_for_move_to_ap_vehicle(Parameters::k_param_barometer_old);
608+
#endif
609+
611610
#if HAL_HAVE_SAFETY_SWITCH
612611
// configure safety switch to allow stopping the motors while armed
613612
AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|

AntennaTracker/Parameters.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ class Parameters {
5454
k_param_compass_enabled_deprecated,
5555
k_param_compass,
5656
k_param_ahrs, // AHRS group
57-
k_param_barometer,
57+
k_param_barometer_old,
5858
k_param_scheduler,
5959
k_param_ins,
6060
k_param_sitl,

AntennaTracker/Tracker.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
5555
SCHED_TASK(update_compass, 10, 1500, 25),
5656
SCHED_TASK(compass_save, 0.02, 200, 30),
5757
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500, 35),
58-
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40),
5958
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45),
6059
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50),
6160
#if HAL_LOGGING_ENABLED

AntennaTracker/Tracker.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -195,6 +195,7 @@ class Tracker : public AP_Vehicle {
195195

196196
// system.cpp
197197
void init_ardupilot() override;
198+
uint32_t baro_log_bit() const override { return MASK_LOG_IMU; }
198199
bool get_home_eeprom(Location &loc) const;
199200
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
200201
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;

AntennaTracker/system.cpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,10 +13,6 @@ void Tracker::init_ardupilot()
1313
// initialise battery
1414
battery.init();
1515

16-
// init baro before we start the GCS, so that the CLI baro test works
17-
barometer.set_log_baro_bit(MASK_LOG_IMU);
18-
barometer.init();
19-
2016
// setup telem slots with serial ports
2117
gcs().setup_uarts();
2218
// update_send so that if the first packet we receive happens to
@@ -38,8 +34,6 @@ void Tracker::init_ardupilot()
3834
ins.init(scheduler.get_loop_rate_hz());
3935
ahrs.reset();
4036

41-
barometer.calibrate();
42-
4337
#if HAL_LOGGING_ENABLED
4438
// initialise AP_Logger library
4539
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void));

ArduCopter/Copter.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
173173
#if AP_BEACON_ENABLED
174174
SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39),
175175
#endif
176-
SCHED_TASK(update_altitude, 10, 100, 42),
177176
SCHED_TASK(run_nav_updates, 50, 100, 45),
178177
SCHED_TASK(update_throttle_hover,100, 90, 48),
179178
#if MODE_SMARTRTL_ENABLED == ENABLED
@@ -756,10 +755,12 @@ void Copter::read_AHRS(void)
756755
}
757756

758757
// read baro and log control tuning
759-
void Copter::update_altitude()
758+
void Copter::update_barometer()
760759
{
761760
// read in baro altitude
762-
read_barometer();
761+
AP_Vehicle::update_barometer();
762+
763+
baro_alt = barometer.get_altitude() * 100.0f;
763764

764765
#if HAL_LOGGING_ENABLED
765766
if (should_log(MASK_LOG_CTUN)) {

ArduCopter/Copter.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -705,7 +705,6 @@ class Copter : public AP_Vehicle {
705705
void update_simple_mode(void);
706706
void update_super_simple_bearing(bool force_update);
707707
void read_AHRS(void);
708-
void update_altitude();
709708
bool get_wp_distance_m(float &distance) const override;
710709
bool get_wp_bearing_deg(float &bearing) const override;
711710
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
@@ -923,7 +922,7 @@ class Copter : public AP_Vehicle {
923922
int16_t get_throttle_mid(void);
924923

925924
// sensors.cpp
926-
void read_barometer(void);
925+
void update_barometer(void) override;
927926
void init_rangefinder(void);
928927
void read_rangefinder(void);
929928
bool rangefinder_alt_ok() const;
@@ -941,6 +940,8 @@ class Copter : public AP_Vehicle {
941940

942941
// system.cpp
943942
void init_ardupilot() override;
943+
uint32_t baro_log_bit() const override { return MASK_LOG_IMU; }
944+
944945
void startup_INS_ground();
945946
bool position_ok() const;
946947
bool ekf_has_absolute_position() const;

ArduCopter/Parameters.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -579,9 +579,7 @@ const AP_Param::Info Copter::var_info[] = {
579579
GOBJECT(sitl, "SIM_", SITL::SIM),
580580
#endif
581581

582-
// @Group: BARO
583-
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
584-
GOBJECT(barometer, "BARO", AP_Baro),
582+
// BARO was here
585583

586584
// GPS driver
587585
// @Group: GPS
@@ -1385,6 +1383,9 @@ void Copter::load_parameters(void)
13851383

13861384
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
13871385

1386+
#if AP_BARO_ENABLED
1387+
AP::baro().convert_parameters_for_move_to_ap_vehicle(Parameters::k_param_barometer_old);
1388+
#endif
13881389

13891390
// setup AP_Param frame type flags
13901391
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);

ArduCopter/Parameters.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ class Parameters {
6464
k_param_sitl = 10,
6565

6666
// barometer object (needed for SITL)
67-
k_param_barometer,
67+
k_param_barometer_old,
6868

6969
// scheduler object (for debugging)
7070
k_param_scheduler,

ArduCopter/sensors.cpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,5 @@
11
#include "Copter.h"
22

3-
// return barometric altitude in centimeters
4-
void Copter::read_barometer(void)
5-
{
6-
barometer.update();
7-
8-
baro_alt = barometer.get_altitude() * 100.0f;
9-
}
10-
113
void Copter::init_rangefinder(void)
124
{
135
#if RANGEFINDER_ENABLED == ENABLED

ArduCopter/system.cpp

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -29,8 +29,6 @@ void Copter::init_ardupilot()
2929

3030
// Init RSSI
3131
rssi.init();
32-
33-
barometer.init();
3432

3533
// setup telem slots with serial ports
3634
gcs().setup_uarts();
@@ -128,11 +126,6 @@ void Copter::init_ardupilot()
128126
USERHOOK_INIT
129127
#endif
130128

131-
// read Baro pressure at ground
132-
//-----------------------------
133-
barometer.set_log_baro_bit(MASK_LOG_IMU);
134-
barometer.calibrate();
135-
136129
#if RANGEFINDER_ENABLED == ENABLED
137130
// initialise rangefinder
138131
init_rangefinder();

ArduPlane/ArduPlane.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
6969
SCHED_TASK(navigate, 10, 150, 36),
7070
SCHED_TASK(update_compass, 10, 200, 39),
7171
SCHED_TASK(calc_airspeed_errors, 10, 100, 42),
72-
SCHED_TASK(update_alt, 10, 200, 45),
7372
SCHED_TASK(adjust_altitude_target, 10, 200, 48),
7473
#if AP_ADVANCEDFAILSAFE_ENABLED
7574
SCHED_TASK(afs_fs_check, 10, 100, 51),
@@ -540,9 +539,9 @@ void Plane::set_flight_stage(AP_FixedWing::FlightStage fs)
540539
#endif
541540
}
542541

543-
void Plane::update_alt()
542+
void Plane::update_barometer()
544543
{
545-
barometer.update();
544+
AP_Vehicle::update_barometer();
546545

547546
// calculate the sink rate.
548547
float sink_rate;

ArduPlane/Parameters.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -736,9 +736,7 @@ const AP_Param::Info Plane::var_info[] = {
736736
// @User: Advanced
737737
ASCALAR(crash_detection_enable, "CRASH_DETECT", 0),
738738

739-
// @Group: BARO
740-
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
741-
GOBJECT(barometer, "BARO", AP_Baro),
739+
// BARO was here
742740

743741
// GPS driver
744742
// @Group: GPS
@@ -1550,4 +1548,8 @@ void Plane::load_parameters(void)
15501548
};
15511549

15521550
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
1551+
1552+
#if AP_BARO_ENABLED
1553+
AP::baro().convert_parameters_for_move_to_ap_vehicle(Parameters::k_param_barometer_old);
1554+
#endif
15531555
}

ArduPlane/Parameters.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -197,7 +197,7 @@ class Parameters {
197197
k_param_pack_capacity, // unused
198198
k_param_sonar_enabled_old, // unused
199199
k_param_ahrs, // AHRS group
200-
k_param_barometer, // barometer ground calibration
200+
k_param_barometer_old, // barometer ground calibration
201201
k_param_airspeed, // only used for parameter conversion; AP_Airspeed parameters moved to AP_Vehicle
202202
k_param_curr_amp_offset,
203203
k_param_NavEKF, // deprecated - remove

ArduPlane/Plane.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1034,7 +1034,7 @@ class Plane : public AP_Vehicle {
10341034
void update_GPS_50Hz(void);
10351035
void update_GPS_10Hz(void);
10361036
void update_compass(void);
1037-
void update_alt(void);
1037+
void update_barometer(void) override;
10381038
#if AP_ADVANCEDFAILSAFE_ENABLED
10391039
void afs_fs_check(void);
10401040
#endif
@@ -1085,6 +1085,7 @@ class Plane : public AP_Vehicle {
10851085

10861086
// system.cpp
10871087
void init_ardupilot() override;
1088+
uint32_t baro_log_bit() const override { return MASK_LOG_IMU; }
10881089
bool set_mode(Mode& new_mode, const ModeReason reason);
10891090
bool set_mode(const uint8_t mode, const ModeReason reason) override;
10901091
bool set_mode_by_number(const Mode::Number new_mode_number, const ModeReason reason);

ArduPlane/system.cpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,6 @@ void Plane::init_ardupilot()
3333

3434
init_rc_out_main();
3535

36-
// init baro
37-
barometer.init();
38-
3936
// initialise rangefinder
4037
rangefinder.set_log_rfnd_bit(MASK_LOG_SONAR);
4138
rangefinder.init(ROTATION_PITCH_270);
@@ -417,11 +414,6 @@ void Plane::startup_INS(void)
417414

418415
ins.init(scheduler.get_loop_rate_hz());
419416
ahrs.reset();
420-
421-
// read Baro pressure at ground
422-
//-----------------------------
423-
barometer.set_log_baro_bit(MASK_LOG_IMU);
424-
barometer.calibrate();
425417
}
426418

427419
// sets notify object flight mode information

ArduSub/ArduSub.cpp

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
7676
#endif
7777
SCHED_TASK(update_batt_compass, 10, 120, 12),
7878
SCHED_TASK(read_rangefinder, 20, 100, 15),
79-
SCHED_TASK(update_altitude, 10, 100, 18),
8079
SCHED_TASK(three_hz_loop, 3, 75, 21),
8180
SCHED_TASK(update_turn_counter, 10, 50, 24),
8281
SCHED_TASK(one_hz_loop, 1, 100, 33),
@@ -312,11 +311,20 @@ void Sub::read_AHRS()
312311
ahrs_view.update();
313312
}
314313

315-
// read baro and rangefinder altitude at 10hz
316-
void Sub::update_altitude()
314+
// override barometer update method to do a few extra things
315+
void Sub::update_barometer()
317316
{
318-
// read in baro altitude
319-
read_barometer();
317+
AP_Vehicle::update_barometer();
318+
319+
// If we are reading a positive altitude, the sensor needs calibration
320+
// Even a few meters above the water we should have no significant depth reading
321+
if(barometer.get_altitude() > 0) {
322+
barometer.update_calibration();
323+
}
324+
325+
if (ap.depth_sensor_present) {
326+
sensor_health.depth = barometer.healthy(depth_sensor_idx);
327+
}
320328

321329
#if HAL_LOGGING_ENABLED
322330
if (should_log(MASK_LOG_CTUN)) {

ArduSub/Parameters.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -574,9 +574,7 @@ const AP_Param::Info Sub::var_info[] = {
574574
GOBJECT(sitl, "SIM_", SITL::SIM),
575575
#endif
576576

577-
// @Group: BARO
578-
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
579-
GOBJECT(barometer, "BARO", AP_Baro),
577+
// BARO was here
580578

581579
// GPS driver
582580
// @Group: GPS
@@ -781,6 +779,10 @@ void Sub::load_parameters()
781779
};
782780

783781
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
782+
783+
#if AP_BARO_ENABLED
784+
AP::baro().convert_parameters_for_move_to_ap_vehicle(Parameters::k_param_barometer_old);
785+
#endif
784786
}
785787

786788
void Sub::convert_old_parameters()

ArduSub/Parameters.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ class Parameters {
6969
// Sensor objects
7070
k_param_ins = 30, // AP_InertialSensor
7171
k_param_compass, // Compass
72-
k_param_barometer, // Barometer/Depth Sensor
72+
k_param_barometer_old, // Barometer/Depth Sensor
7373
k_param_battery, // AP_BattMonitor
7474
k_param_leak_detector, // Leak Detector
7575
k_param_rangefinder, // Rangefinder

ArduSub/Sub.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -387,7 +387,6 @@ class Sub : public AP_Vehicle {
387387
void one_hz_loop();
388388
void update_turn_counter();
389389
void read_AHRS(void);
390-
void update_altitude();
391390
float get_smoothing_gain();
392391
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);
393392
float get_pilot_desired_yaw_rate(int16_t stick_angle) const;
@@ -476,12 +475,13 @@ class Sub : public AP_Vehicle {
476475
JSButton* get_button(uint8_t index);
477476
void default_js_buttons(void);
478477
void clear_input_hold();
479-
void read_barometer(void);
478+
void update_barometer(void) override;
480479
void init_rangefinder(void);
481480
void read_rangefinder(void);
482481
void terrain_update();
483482
void terrain_logging();
484483
void init_ardupilot() override;
484+
uint32_t baro_log_bit() const override { return MASK_LOG_IMU; }
485485
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
486486
uint8_t &task_count,
487487
uint32_t &log_bit) override;

ArduSub/sensors.cpp

Lines changed: 0 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,20 +1,5 @@
11
#include "Sub.h"
22

3-
// return barometric altitude in centimeters
4-
void Sub::read_barometer()
5-
{
6-
barometer.update();
7-
// If we are reading a positive altitude, the sensor needs calibration
8-
// Even a few meters above the water we should have no significant depth reading
9-
if(barometer.get_altitude() > 0) {
10-
barometer.update_calibration();
11-
}
12-
13-
if (ap.depth_sensor_present) {
14-
sensor_health.depth = barometer.healthy(depth_sensor_idx);
15-
}
16-
}
17-
183
void Sub::init_rangefinder()
194
{
205
#if RANGEFINDER_ENABLED == ENABLED

ArduSub/system.cpp

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,6 @@ void Sub::init_ardupilot()
2020
// initialise battery monitor
2121
battery.init();
2222

23-
barometer.init();
24-
2523
#if AP_FEATURE_BOARD_DETECT
2624
// Detection won't work until after BoardConfig.init()
2725
switch (AP_BoardConfig::get_board_type()) {
@@ -100,11 +98,8 @@ void Sub::init_ardupilot()
10098
USERHOOK_INIT
10199
#endif
102100

103-
// Init baro and determine if we have external (depth) pressure sensor
104-
barometer.set_log_baro_bit(MASK_LOG_IMU);
105-
barometer.calibrate(false);
101+
// determine if we have external (depth) pressure sensor
106102
barometer.update();
107-
108103
for (uint8_t i = 0; i < barometer.num_instances(); i++) {
109104
if (barometer.get_type(i) == AP_Baro::BARO_TYPE_WATER) {
110105
barometer.set_primary_baro(i);

0 commit comments

Comments
 (0)