PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <sensor_gyro.h>
Public Attributes | |
uint64_t | timestamp |
uint64_t | error_count |
uint32_t | device_id |
float | x |
float | y |
float | z |
uint32_t | integral_dt |
float | x_integral |
float | y_integral |
float | z_integral |
float | temperature |
float | scaling |
int16_t | x_raw |
int16_t | y_raw |
int16_t | z_raw |
uint8_t | _padding0 [2] |
Definition at line 51 of file sensor_gyro.h.
uint8_t sensor_gyro_s::_padding0[2] |
Definition at line 68 of file sensor_gyro.h.
uint32_t sensor_gyro_s::device_id |
Definition at line 55 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), PX4Gyroscope::ioctl(), PX4Gyroscope::PX4Gyroscope(), PX4Gyroscope::set_device_type(), and TemperatureCalibrationGyro::update_sensor_instance().
uint64_t sensor_gyro_s::error_count |
Definition at line 54 of file sensor_gyro.h.
Referenced by DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), and PX4Gyroscope::set_error_count().
uint32_t sensor_gyro_s::integral_dt |
Definition at line 59 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), and PX4Gyroscope::update().
float sensor_gyro_s::scaling |
Definition at line 64 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), PX4Gyroscope::PX4Gyroscope(), PX4Gyroscope::set_scale(), PX4Gyroscope::update(), and mpu9x50::update_reports().
float sensor_gyro_s::temperature |
Definition at line 63 of file sensor_gyro.h.
Referenced by sensors::VotedSensorsUpdate::gyroPoll(), PX4Gyroscope::set_temperature(), mpu9x50::update_reports(), and TemperatureCalibrationGyro::update_sensor_instance().
uint64_t sensor_gyro_s::timestamp |
Definition at line 53 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), MavlinkReceiver::handle_message_hil_sensor(), MavlinkReceiver::handle_message_hil_state_quaternion(), VehicleAngularVelocity::Run(), PX4Gyroscope::update(), and mpu9x50::update_reports().
float sensor_gyro_s::x |
Definition at line 56 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), do_gyro_calibration(), gyro_calibration_worker(), sensors::VotedSensorsUpdate::gyroPoll(), VehicleAngularVelocity::Run(), PX4Gyroscope::update(), mpu9x50::update_reports(), and TemperatureCalibrationGyro::update_sensor_instance().
float sensor_gyro_s::x_integral |
Definition at line 60 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), and PX4Gyroscope::update().
int16_t sensor_gyro_s::x_raw |
Definition at line 65 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), MavlinkStreamScaledIMU::send(), MavlinkStreamScaledIMU2::send(), MavlinkStreamScaledIMU3::send(), PX4Gyroscope::update(), and mpu9x50::update_reports().
float sensor_gyro_s::y |
Definition at line 57 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), do_gyro_calibration(), gyro_calibration_worker(), sensors::VotedSensorsUpdate::gyroPoll(), VehicleAngularVelocity::Run(), PX4Gyroscope::update(), mpu9x50::update_reports(), and TemperatureCalibrationGyro::update_sensor_instance().
float sensor_gyro_s::y_integral |
Definition at line 61 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), and PX4Gyroscope::update().
int16_t sensor_gyro_s::y_raw |
Definition at line 66 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), MavlinkStreamScaledIMU::send(), MavlinkStreamScaledIMU2::send(), MavlinkStreamScaledIMU3::send(), PX4Gyroscope::update(), and mpu9x50::update_reports().
float sensor_gyro_s::z |
Definition at line 58 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), do_gyro_calibration(), gyro_calibration_worker(), sensors::VotedSensorsUpdate::gyroPoll(), VehicleAngularVelocity::Run(), PX4Gyroscope::update(), mpu9x50::update_reports(), and TemperatureCalibrationGyro::update_sensor_instance().
float sensor_gyro_s::z_integral |
Definition at line 62 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), sensors::VotedSensorsUpdate::gyroPoll(), and PX4Gyroscope::update().
int16_t sensor_gyro_s::z_raw |
Definition at line 67 of file sensor_gyro.h.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), MavlinkStreamScaledIMU::send(), MavlinkStreamScaledIMU2::send(), MavlinkStreamScaledIMU3::send(), PX4Gyroscope::update(), and mpu9x50::update_reports().