42 #include <px4_platform_common/module_params.h> 88 (ParamFloat<px4::params::IMU_GYRO_CUTOFF>) _param_imu_gyro_cutoff,
89 (ParamInt<px4::params::IMU_GYRO_RATEMAX>) _param_imu_gyro_rate_max
matrix::Vector3f _calibration_scale
Gyroscope driver interface.
A class to implement a second order low pass filter on a Vector3f Based on LowPassFilter2p.hpp by Leonard Hall LeonardTHall@gmail.com
API for the uORB lightweight object broker.
int _class_device_instance
void configure_filter(float cutoff_freq)
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override
Perform an ioctl operation on the device.
static int32_t device_id[max_accel_sens]
High-resolution timer with callouts and timekeeping.
void set_device_type(uint8_t devtype)
void update(hrt_abstime timestamp, float x, float y, float z)
void set_cutoff_frequency(float sample_freq, float cutoff_freq)
Abstract class for any character device.
void set_sample_rate(unsigned rate)
Rotation
Enum for board and external compass rotations.
uORB::PublicationMultiData< sensor_gyro_control_s > _sensor_gyro_control_pub
void set_error_count(uint64_t error_count)
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
PX4Gyroscope(uint32_t device_id, uint8_t priority=ORB_PRIO_DEFAULT, enum Rotation rotation=ROTATION_NONE)
void set_temperature(float temperature)
math::LowPassFilter2pVector3f _filter
matrix::Vector3f _calibration_offset
void set_scale(float scale)
uORB::PublicationMultiData< sensor_gyro_s > _sensor_gyro_pub