23 #define WHEELENCODER_MAX_INSTANCES 2 24 #define WHEELENCODER_CPR_DEFAULT 3200 // default encoder counts per full revolution of the wheel 25 #define WHEELENCODER_RADIUS_DEFAULT 0.05f // default wheel radius of 5cm (0.05m) 66 bool enabled(uint8_t instance)
const;
AP_Int8 _type[WHEELENCODER_MAX_INSTANCES]
WheelEncoder_State state[WHEELENCODER_MAX_INSTANCES]
float get_wheel_radius(uint8_t instance) const
AP_Int8 _pinb[WHEELENCODER_MAX_INSTANCES]
uint32_t get_total_count(uint8_t instance) const
AP_Int16 _counts_per_revolution[WHEELENCODER_MAX_INSTANCES]
uint32_t get_last_reading_ms(uint8_t instance) const
#define WHEELENCODER_MAX_INSTANCES
static const struct AP_Param::GroupInfo var_info[]
A system for managing and storing variables that are of general interest to the system.
uint32_t get_error_count(uint8_t instance) const
float get_distance(uint8_t instance) const
Vector3f get_position(uint8_t instance) const
bool healthy(uint8_t instance) const
bool enabled(uint8_t instance) const
AP_Float _wheel_radius[WHEELENCODER_MAX_INSTANCES]
float get_signal_quality(uint8_t instance) const
uint8_t num_sensors(void) const
Common definitions and utility routines for the ArduPilot libraries.
uint16_t get_counts_per_revolution(uint8_t instance) const
AP_Vector3f _pos_offset[WHEELENCODER_MAX_INSTANCES]
AP_WheelEncoder_Backend * drivers[WHEELENCODER_MAX_INSTANCES]
AP_Int8 _pina[WHEELENCODER_MAX_INSTANCES]
float get_delta_angle(uint8_t instance) const