Browse Source

AP_WheelEncoder: remove empty constructors

gps-1.3.1
divyateja04 3 years ago committed by Peter Barker
parent
commit
d82ad94b7e
  1. 6
      libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp
  2. 2
      libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h
  3. 8
      libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp
  4. 4
      libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h

6
libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp

@ -21,12 +21,6 @@ @@ -21,12 +21,6 @@
extern const AP_HAL::HAL& hal;
// constructor
AP_WheelEncoder_Quadrature::AP_WheelEncoder_Quadrature(AP_WheelEncoder &frontend, uint8_t instance, AP_WheelEncoder::WheelEncoder_State &state) :
AP_WheelEncoder_Backend(frontend, instance, state)
{
}
// check if pin has changed and initialise gpio event callback
void AP_WheelEncoder_Quadrature::update_pin(uint8_t &pin,
uint8_t new_pin,

2
libraries/AP_WheelEncoder/WheelEncoder_Quadrature.h

@ -23,7 +23,7 @@ class AP_WheelEncoder_Quadrature : public AP_WheelEncoder_Backend @@ -23,7 +23,7 @@ class AP_WheelEncoder_Quadrature : public AP_WheelEncoder_Backend
{
public:
// constructor
AP_WheelEncoder_Quadrature(AP_WheelEncoder &frontend, uint8_t instance, AP_WheelEncoder::WheelEncoder_State &state);
using AP_WheelEncoder_Backend::AP_WheelEncoder_Backend;
// update state
void update(void) override;

8
libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.cpp

@ -22,14 +22,10 @@ @@ -22,14 +22,10 @@
extern const AP_HAL::HAL& hal;
AP_WheelEncoder_SITL_Qaudrature::AP_WheelEncoder_SITL_Qaudrature(AP_WheelEncoder &frontend, uint8_t instance, AP_WheelEncoder::WheelEncoder_State &state) :
AP_WheelEncoder_Backend(frontend, instance, state),
_sitl(AP::sitl())
{
}
void AP_WheelEncoder_SITL_Qaudrature::update(void)
{
const auto *_sitl = AP::sitl();
// earth frame velocity of vehicle in vector form
const Vector2f ef_velocity(_sitl->state.speedN, _sitl->state.speedE);
// store current heading

4
libraries/AP_WheelEncoder/WheelEncoder_SITL_Quadrature.h

@ -24,14 +24,12 @@ class AP_WheelEncoder_SITL_Qaudrature : public AP_WheelEncoder_Backend @@ -24,14 +24,12 @@ class AP_WheelEncoder_SITL_Qaudrature : public AP_WheelEncoder_Backend
{
public:
// constructor
AP_WheelEncoder_SITL_Qaudrature(AP_WheelEncoder &frontend, uint8_t instance, AP_WheelEncoder::WheelEncoder_State &state);
using AP_WheelEncoder_Backend::AP_WheelEncoder_Backend;
// update state
void update(void) override;
private:
SITL::SIM *_sitl; // pointer to SITL singleton
int32_t _distance_count; // distance count as number of encoder ticks
uint32_t _total_count; // total number of encoder ticks
};

Loading…
Cancel
Save