From 5f54daecee13c31101bd80c1812b8acd37d2ae93 Mon Sep 17 00:00:00 2001 From: Joshua Henderson Date: Sun, 9 Jan 2022 20:37:11 -0500 Subject: [PATCH] Rover: move Airspeed to AP_Vehicle --- Rover/Parameters.cpp | 18 ++++++++++++++---- Rover/Parameters.h | 3 --- Rover/Rover.cpp | 1 - Rover/Rover.h | 2 -- Rover/sensors.cpp | 8 -------- Rover/system.cpp | 6 ++++-- 6 files changed, 18 insertions(+), 20 deletions(-) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index e06ef57e9f..8df3cc7fda 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -574,9 +574,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // 32 to 36 were old sailboat params - // @Group: ARSPD - // @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp - AP_SUBGROUPINFO(airspeed, "ARSPD", 37, ParametersG2, AP_Airspeed), + // 37 was airspeed // @Param: MIS_DONE_BEHAVE // @DisplayName: Mission done behave @@ -711,7 +709,6 @@ ParametersG2::ParametersG2(void) avoid(), follow(), windvane(), - airspeed(), wp_nav(attitude_control, rover.L1_controller), sailboat() { @@ -843,4 +840,17 @@ void Rover::load_parameters(void) AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON| AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED); #endif + +// PARAMETER_CONVERSION - Added: JAN-2022 +#if AP_AIRSPEED_ENABLED + // Find G2's Top Level Key + AP_Param::ConversionInfo info; + if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { + return; + } + + const uint16_t old_index = 37; // Old parameter index in the tree + const uint16_t old_top_element = 4069; // Old group element in the tree for the first subgroup element + AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false); +#endif } diff --git a/Rover/Parameters.h b/Rover/Parameters.h index efbd3254d3..653dc5a5d0 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -371,9 +371,6 @@ public: // windvane AP_WindVane windvane; - // Airspeed - AP_Airspeed airspeed; - // mission behave AP_Int8 mis_done_behave; diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 94b4862a64..b90d94405e 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -130,7 +130,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #if ADVANCED_FAILSAFE == ENABLED SCHED_TASK(afs_fs_check, 10, 200, 129), #endif - SCHED_TASK(read_airspeed, 10, 100, 132), #if HAL_AIS_ENABLED SCHED_TASK_CLASS(AP_AIS, &rover.g2.ais, update, 5, 100, 135), #endif diff --git a/Rover/Rover.h b/Rover/Rover.h index 1d25cdb380..19cb2b6753 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -27,7 +27,6 @@ #include #include // interface and maths for accelerometer calibration #include // ArduPilot Mega DCM Library -#include // needed for AHRS build #include #include // Battery monitor library #include @@ -352,7 +351,6 @@ private: void compass_save(void); void update_wheel_encoder(); void read_rangefinders(void); - void read_airspeed(); // Steering.cpp void set_servos(void); diff --git a/Rover/sensors.cpp b/Rover/sensors.cpp index 795512a360..9153fd7e34 100644 --- a/Rover/sensors.cpp +++ b/Rover/sensors.cpp @@ -93,11 +93,3 @@ void Rover::read_rangefinders(void) rangefinder.update(); Log_Write_Depth(); } - -/* - ask airspeed sensor for a new value, duplicated from plane - */ -void Rover::read_airspeed(void) -{ - g2.airspeed.update(should_log(MASK_LOG_IMU)); -} diff --git a/Rover/system.cpp b/Rover/system.cpp index 0a97d88e9a..4d08c33797 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -42,8 +42,6 @@ void Rover::init_ardupilot() rssi.init(); - g2.airspeed.init(); - g2.windvane.init(serial_manager); // init baro before we start the GCS, so that the CLI baro test works @@ -68,6 +66,10 @@ void Rover::init_ardupilot() AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init(); +#if AP_AIRSPEED_ENABLED + airspeed.set_log_bit(MASK_LOG_IMU); +#endif + // initialise rangefinder rangefinder.set_log_rfnd_bit(MASK_LOG_RANGEFINDER); rangefinder.init(ROTATION_NONE);