Browse Source

global: use static method to construct RangeFinder

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
9027a55696
  1. 2
      APMrover2/Rover.h
  2. 2
      AntennaTracker/Tracker.h
  3. 2
      ArduCopter/Copter.h
  4. 2
      ArduPlane/Plane.h
  5. 2
      ArduSub/Sub.h
  6. 2
      Tools/Replay/Replay.h
  7. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  8. 2
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp
  9. 2
      libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp

2
APMrover2/Rover.h

@ -155,7 +155,7 @@ private: @@ -155,7 +155,7 @@ private:
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_NONE);
AP_Button button;
// flight modes convenience array

2
AntennaTracker/Tracker.h

@ -112,7 +112,7 @@ private: @@ -112,7 +112,7 @@ private:
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rng {serial_manager, ROTATION_NONE};
RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_NONE);
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE

2
ArduCopter/Copter.h

@ -201,7 +201,7 @@ private: @@ -201,7 +201,7 @@ private:
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
struct {
bool enabled:1;
bool alt_healthy:1; // true if we can trust the altitude from the rangefinder

2
ArduPlane/Plane.h

@ -205,7 +205,7 @@ private: @@ -205,7 +205,7 @@ private:
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state;

2
ArduSub/Sub.h

@ -170,7 +170,7 @@ private: @@ -170,7 +170,7 @@ private:
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
struct {
bool enabled:1;
bool alt_healthy:1; // true if we can trust the altitude from the rangefinder

2
Tools/Replay/Replay.h

@ -63,7 +63,7 @@ public: @@ -63,7 +63,7 @@ public:
AP_GPS gps = AP_GPS::create();
Compass compass = Compass::create();
AP_SerialManager serial_manager;
RangeFinder rng {serial_manager, ROTATION_PITCH_270};
RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
NavEKF2 EKF2{&ahrs, barometer, rng};
NavEKF3 EKF3{&ahrs, barometer, rng};
AP_AHRS_NavEKF ahrs {ins, barometer, gps, rng, EKF2, EKF3};

2
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -23,7 +23,7 @@ AP_SerialManager serial_manager; @@ -23,7 +23,7 @@ AP_SerialManager serial_manager;
class DummyVehicle {
public:
RangeFinder sonar {serial_manager, ROTATION_PITCH_270};
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
NavEKF2 EKF2{&ahrs, barometer, sonar};

2
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

@ -26,7 +26,7 @@ public: @@ -26,7 +26,7 @@ public:
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
AP_SerialManager serial_manager;
RangeFinder sonar {serial_manager, ROTATION_PITCH_270};
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
NavEKF2 EKF2{&ahrs, barometer, sonar};

2
libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp

@ -11,7 +11,7 @@ void loop(); @@ -11,7 +11,7 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_SerialManager serial_manager;
static RangeFinder sonar {serial_manager, ROTATION_PITCH_270};
static RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
void setup()
{

Loading…
Cancel
Save