41 ModuleParams(nullptr),
42 _sensor_accel_pub{
ORB_ID(sensor_accel), priority},
125 uint32_t integral_dt = 0;
127 if (
_integrator.
put(timestamp, val_calibrated, integrated_value, integral_dt)) {
134 report.
x = val_filtered(0);
135 report.
y = val_filtered(1);
136 report.
z = val_filtered(2);
PX4Accelerometer(uint32_t device_id, uint8_t priority=ORB_PRIO_DEFAULT, enum Rotation rotation=ROTATION_NONE)
~PX4Accelerometer() override
void set_sample_rate(unsigned rate)
virtual int register_class_devname(const char *class_devname)
Register a class device name, automatically adding device class instance suffix if need be...
void update(hrt_abstime timestamp, float x, float y, float z)
__EXPORT void rotate_3f(enum Rotation rot, float &x, float &y, float &z)
rotate a 3 element float vector in-place
float get_cutoff_freq() const
matrix::Vector3f _calibration_offset
static int32_t device_id[max_accel_sens]
math::LowPassFilter2pVector3f _filter
accel scaling factors; Vout = Vscale * (Vin + Voffset)
bool put(const uint64_t ×tamp, const matrix::Vector3f &val, matrix::Vector3f &integral, uint32_t &integral_dt)
Put an item into the integral.
struct DeviceStructure devid_s
virtual void poll_notify(pollevent_t events)
Report new poll events.
#define ACCEL_BASE_DEVICE_PATH
Definitions for the generic base classes in the device framework.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
void set_cutoff_frequency(float sample_freq, float cutoff_freq)
matrix::Vector3f _calibration_scale
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance)
Register a class device name, automatically adding device class instance suffix if need be...
void configure_filter(float cutoff_freq)
Rotation
Enum for board and external compass rotations.
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override
Perform an ioctl operation on the device.
int _class_device_instance
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
#define ACCELIOCSSCALE
set the accel scaling constants to the structure pointed to by (arg)
matrix::Vector3f apply(const matrix::Vector3f &sample)
Add a new raw value to the filter.
uORB::PublicationMultiData< sensor_accel_s > _sensor_accel_pub
void set_device_type(uint8_t devtype)