mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: move Airspeed to AP_Vehicle
This commit is contained in:
parent
a765bb048d
commit
5f54daecee
@ -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
|
||||
}
|
||||
|
@ -371,9 +371,6 @@ public:
|
||||
// windvane
|
||||
AP_WindVane windvane;
|
||||
|
||||
// Airspeed
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
// mission behave
|
||||
AP_Int8 mis_done_behave;
|
||||
|
||||
|
@ -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
|
||||
|
@ -27,7 +27,6 @@
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
|
||||
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
@ -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);
|
||||
|
@ -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));
|
||||
}
|
||||
|
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user