mirror of https://github.com/ArduPilot/ardupilot
Rover: remove pointless library init wrappers
The vast majority of calls in init_ardupilot already follow this convention
This commit is contained in:
parent
d70e252bf4
commit
a798c87d91
|
@ -384,12 +384,9 @@ private:
|
||||||
// sensors.cpp
|
// sensors.cpp
|
||||||
void update_compass(void);
|
void update_compass(void);
|
||||||
void compass_save(void);
|
void compass_save(void);
|
||||||
void init_beacon();
|
|
||||||
void init_visual_odom();
|
|
||||||
void update_wheel_encoder();
|
void update_wheel_encoder();
|
||||||
void accel_cal_update(void);
|
void accel_cal_update(void);
|
||||||
void read_rangefinders(void);
|
void read_rangefinders(void);
|
||||||
void init_proximity();
|
|
||||||
void read_airspeed();
|
void read_airspeed();
|
||||||
void rpm_update(void);
|
void rpm_update(void);
|
||||||
|
|
||||||
|
|
|
@ -20,18 +20,6 @@ void Rover::compass_save() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// init beacons used for non-gps position estimates
|
|
||||||
void Rover::init_beacon()
|
|
||||||
{
|
|
||||||
g2.beacon.init();
|
|
||||||
}
|
|
||||||
|
|
||||||
// init visual odometry sensor
|
|
||||||
void Rover::init_visual_odom()
|
|
||||||
{
|
|
||||||
g2.visual_odom.init();
|
|
||||||
}
|
|
||||||
|
|
||||||
// update wheel encoders
|
// update wheel encoders
|
||||||
void Rover::update_wheel_encoder()
|
void Rover::update_wheel_encoder()
|
||||||
{
|
{
|
||||||
|
@ -119,12 +107,6 @@ void Rover::read_rangefinders(void)
|
||||||
Log_Write_Depth();
|
Log_Write_Depth();
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise proximity sensor
|
|
||||||
void Rover::init_proximity(void)
|
|
||||||
{
|
|
||||||
g2.proximity.init();
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
ask airspeed sensor for a new value, duplicated from plane
|
ask airspeed sensor for a new value, duplicated from plane
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -99,13 +99,13 @@ void Rover::init_ardupilot()
|
||||||
rangefinder.init(ROTATION_NONE);
|
rangefinder.init(ROTATION_NONE);
|
||||||
|
|
||||||
// init proximity sensor
|
// init proximity sensor
|
||||||
init_proximity();
|
g2.proximity.init();
|
||||||
|
|
||||||
// init beacons used for non-gps position estimation
|
// init beacons used for non-gps position estimation
|
||||||
init_beacon();
|
g2.beacon.init();
|
||||||
|
|
||||||
// init visual odometry
|
// init library used for visual position estimation
|
||||||
init_visual_odom();
|
g2.visual_odom.init();
|
||||||
|
|
||||||
// and baro for EKF
|
// and baro for EKF
|
||||||
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||||
|
|
Loading…
Reference in New Issue