Browse Source

AP_RangeFinder: format fixes

master
Randy Mackay 6 years ago
parent
commit
a72477590f
  1. 2
      libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp
  2. 2
      libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h
  3. 2
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h
  4. 2
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp
  5. 2
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h
  6. 2
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp
  7. 2
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h
  8. 2
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp
  9. 2
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h
  10. 20
      libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp
  11. 10
      libraries/AP_RangeFinder/AP_RangeFinder_Params.h
  12. 2
      libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp
  13. 2
      libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h
  14. 2
      libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp
  15. 2
      libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h
  16. 2
      libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp
  17. 2
      libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h
  18. 1
      libraries/AP_RangeFinder/RangeFinder.cpp
  19. 1
      libraries/AP_RangeFinder/RangeFinder_Backend.h

2
libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp

@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal; @@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state, _params)

2
libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h

@ -43,7 +43,7 @@ class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend @@ -43,7 +43,7 @@ class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

2
libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h

@ -10,7 +10,7 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend @@ -10,7 +10,7 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// update state

2
libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp

@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state, _params)

2
libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h

@ -9,7 +9,7 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend @@ -9,7 +9,7 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

2
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp

@ -37,7 +37,7 @@ extern const AP_HAL::HAL& hal; @@ -37,7 +37,7 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_RangeFinder_Backend(_state, _params)
, _dev(std::move(dev))

2
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h

@ -12,7 +12,7 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend @@ -12,7 +12,7 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// update state

2
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp

@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal; @@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state, _params)

2
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h

@ -9,7 +9,7 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend @@ -9,7 +9,7 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

20
libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp

@ -45,7 +45,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { @@ -45,7 +45,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
// @Param: MIN_CM
// @DisplayName: Rangefinder minimum distance
// @Description: Minimum distance in centimeters that rangefinder can reliably read
// @Units: cm
// @Units: cm
// @Increment: 1
// @User: Standard
AP_GROUPINFO("MIN_CM", 6, AP_RangeFinder_Params, min_distance_cm, 20),
@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { @@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
// @Param: MAX_CM
// @DisplayName: Rangefinder maximum distance
// @Description: Maximum distance in centimeters that rangefinder can reliably read
// @Units: cm
// @Units: cm
// @Increment: 1
// @User: Standard
AP_GROUPINFO("MAX_CM", 7, AP_RangeFinder_Params, max_distance_cm, 700),
@ -80,13 +80,13 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { @@ -80,13 +80,13 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
// @User: Standard
AP_GROUPINFO("RMETRIC", 10, AP_RangeFinder_Params, ratiometric, 1),
// @Param: PWRRNG
// @DisplayName: Powersave range
// @Description: This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
// @Units: m
// @Range: 0 32767
// @User: Standard
AP_GROUPINFO("PWRRNG", 11, AP_RangeFinder_Params, powersave_range, 0),
// @Param: PWRRNG
// @DisplayName: Powersave range
// @Description: This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
// @Units: m
// @Range: 0 32767
// @User: Standard
AP_GROUPINFO("PWRRNG", 11, AP_RangeFinder_Params, powersave_range, 0),
// @Param: GNDCLEAR
// @DisplayName: Distance (in cm) from the range finder to the ground
@ -130,7 +130,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { @@ -130,7 +130,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
// @Values: 0:Forward, 1:Forward-Right, 2:Right, 3:Back-Right, 4:Back, 5:Back-Left, 6:Left, 7:Forward-Left, 24:Up, 25:Down
// @User: Advanced
AP_GROUPINFO("ORIENT", 53, AP_RangeFinder_Params, orientation, ROTATION_PITCH_270),
AP_GROUPEND
};

10
libraries/AP_RangeFinder/AP_RangeFinder_Params.h

@ -5,14 +5,14 @@ @@ -5,14 +5,14 @@
class AP_RangeFinder_Params {
public:
static const struct AP_Param::GroupInfo var_info[];
AP_RangeFinder_Params(void);
static const struct AP_Param::GroupInfo var_info[];
AP_RangeFinder_Params(void);
/* Do not allow copies */
AP_RangeFinder_Params(const AP_RangeFinder_Params &other) = delete;
AP_RangeFinder_Params &operator=(const AP_RangeFinder_Params&) = delete;
AP_Int8 type;
AP_Int8 pin;
AP_Int8 ratiometric;

2
libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp

@ -47,7 +47,7 @@ extern const AP_HAL::HAL& hal; @@ -47,7 +47,7 @@ extern const AP_HAL::HAL& hal;
*/
AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus,
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
RangeFinder::RangeFinder_Type _rftype)
: AP_RangeFinder_Backend(_state, _params)
, _dev(hal.i2c_mgr->get_device(bus, LL40LS_ADDR))

2
libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h

@ -21,7 +21,7 @@ public: @@ -21,7 +21,7 @@ public:
// static detection function
static AP_RangeFinder_Backend *detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
RangeFinder::RangeFinder_Type rftype);
// update state

2
libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp

@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev)
: AP_RangeFinder_Backend(_state, _params)
, dev(std::move(i2c_dev))

2
libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h

@ -9,7 +9,7 @@ class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend @@ -9,7 +9,7 @@ class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev);
// update state

2
libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp

@ -33,7 +33,7 @@ extern const AP_HAL::HAL& hal; @@ -33,7 +33,7 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state, _params)

2
libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h

@ -9,7 +9,7 @@ class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend @@ -9,7 +9,7 @@ class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

1
libraries/AP_RangeFinder/RangeFinder.cpp

@ -38,7 +38,6 @@ @@ -38,7 +38,6 @@
#include "AP_RangeFinder_PWM.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <stdio.h>
extern const AP_HAL::HAL &hal;

1
libraries/AP_RangeFinder/RangeFinder_Backend.h

@ -22,7 +22,6 @@ class AP_RangeFinder_Backend @@ -22,7 +22,6 @@ class AP_RangeFinder_Backend
{
public:
// constructor. This incorporates initialisation as well.
//AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
// we declare a virtual destructor so that RangeFinder drivers can

Loading…
Cancel
Save