AP_WheelEncoder: remove empty constructors

This commit is contained in:
divyateja04 2021-10-24 16:45:49 +05:30 committed by Peter Barker
parent 58b2154e77
commit d82ad94b7e
4 changed files with 4 additions and 16 deletions

View File

@ -21,12 +21,6 @@
extern const AP_HAL::HAL& hal; 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 // check if pin has changed and initialise gpio event callback
void AP_WheelEncoder_Quadrature::update_pin(uint8_t &pin, void AP_WheelEncoder_Quadrature::update_pin(uint8_t &pin,
uint8_t new_pin, uint8_t new_pin,

View File

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

View File

@ -22,14 +22,10 @@
extern const AP_HAL::HAL& hal; 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) void AP_WheelEncoder_SITL_Qaudrature::update(void)
{ {
const auto *_sitl = AP::sitl();
// earth frame velocity of vehicle in vector form // earth frame velocity of vehicle in vector form
const Vector2f ef_velocity(_sitl->state.speedN, _sitl->state.speedE); const Vector2f ef_velocity(_sitl->state.speedN, _sitl->state.speedE);
// store current heading // store current heading

View File

@ -24,14 +24,12 @@ class AP_WheelEncoder_SITL_Qaudrature : public AP_WheelEncoder_Backend
{ {
public: public:
// constructor // 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 // update state
void update(void) override; void update(void) override;
private: private:
SITL::SIM *_sitl; // pointer to SITL singleton
int32_t _distance_count; // distance count as number of encoder ticks int32_t _distance_count; // distance count as number of encoder ticks
uint32_t _total_count; // total number of encoder ticks uint32_t _total_count; // total number of encoder ticks
}; };