PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Classes | |
struct | accel_calibration_s |
struct | gyro_calibration_s |
struct | mag_calibration_s |
Public Member Functions | |
DfMpu9250Wrapper (bool mag_enabled, enum Rotation rotation) | |
~DfMpu9250Wrapper () | |
int | start () |
Start automatic measurement. More... | |
int | stop () |
Stop automatic measurement. More... | |
void | info () |
Print some debug info. More... | |
Public Member Functions inherited from MPU9250 | |
MPU9250 (device::Device *interface, device::Device *mag_interface, enum Rotation rotation) | |
virtual | ~MPU9250 () |
virtual int | init () |
uint8_t | get_whoami () |
void | print_info () |
Diagnostics - print some basic information about the driver. More... | |
Private Member Functions | |
int | _publish (struct imu_sensor_data &data) |
void | _update_accel_calibration () |
void | _update_gyro_calibration () |
void | _update_mag_calibration () |
Additional Inherited Members | |
Protected Member Functions inherited from MPU9250 | |
virtual int | probe () |
whoami result More... | |
void | Run () override |
Protected Attributes inherited from MPU9250 | |
device::Device * | _interface |
uint8_t | _whoami {0} |
Definition at line 86 of file df_mpu9250_wrapper.cpp.
DfMpu9250Wrapper::DfMpu9250Wrapper | ( | bool | mag_enabled, |
enum Rotation | rotation | ||
) |
Definition at line 185 of file df_mpu9250_wrapper.cpp.
References _accel_calibration, _accel_filter_x, _accel_filter_y, _accel_filter_z, _accel_int, _accel_orb_class_instance, _accel_range_hit_counter, _error_counter, _fifo_corruption_counter, _fifo_overflow_counter, _gyro_calibration, _gyro_filter_x, _gyro_filter_y, _gyro_filter_z, _gyro_int, _gyro_orb_class_instance, _gyro_range_hit_counter, _last_accel_range_hit_count, _last_accel_range_hit_time, _mag_calibration, _mag_enabled, _mag_fifo_overflow_counter, _mag_orb_class_instance, _publish_perf, _read_counter, _rotation, MPU9250_ACCEL_DEFAULT_DRIVER_FILTER_FREQ, MPU9250_ACCEL_DEFAULT_RATE, MPU9250_GYRO_DEFAULT_DRIVER_FILTER_FREQ, MPU9250_GYRO_DEFAULT_RATE, MPU9250_PUB_RATE, param_find(), param_get(), PARAM_INVALID, PC_COUNT, PC_ELAPSED, perf_alloc, math::LowPassFilter2p::set_cutoff_frequency(), DfMpu9250Wrapper::accel_calibration_s::x_offset, DfMpu9250Wrapper::gyro_calibration_s::x_offset, DfMpu9250Wrapper::mag_calibration_s::x_offset, DfMpu9250Wrapper::accel_calibration_s::x_scale, DfMpu9250Wrapper::gyro_calibration_s::x_scale, DfMpu9250Wrapper::mag_calibration_s::x_scale, DfMpu9250Wrapper::accel_calibration_s::y_offset, DfMpu9250Wrapper::gyro_calibration_s::y_offset, DfMpu9250Wrapper::mag_calibration_s::y_offset, DfMpu9250Wrapper::accel_calibration_s::y_scale, DfMpu9250Wrapper::gyro_calibration_s::y_scale, DfMpu9250Wrapper::mag_calibration_s::y_scale, DfMpu9250Wrapper::accel_calibration_s::z_offset, DfMpu9250Wrapper::gyro_calibration_s::z_offset, DfMpu9250Wrapper::mag_calibration_s::z_offset, DfMpu9250Wrapper::accel_calibration_s::z_scale, DfMpu9250Wrapper::gyro_calibration_s::z_scale, and DfMpu9250Wrapper::mag_calibration_s::z_scale.
Referenced by df_mpu9250_wrapper::start().
DfMpu9250Wrapper::~DfMpu9250Wrapper | ( | ) |
Definition at line 269 of file df_mpu9250_wrapper.cpp.
References _accel_range_hit_counter, _error_counter, _fifo_corruption_counter, _fifo_overflow_counter, _gyro_range_hit_counter, _mag_enabled, _mag_fifo_overflow_counter, _publish_perf, _read_counter, and perf_free().
|
private |
Definition at line 600 of file df_mpu9250_wrapper.cpp.
References _accel_calibration, _accel_filter_x, _accel_filter_y, _accel_filter_z, _accel_int, _accel_range_hit_counter, _accel_topic, _error_counter, _fifo_corruption_counter, _fifo_overflow_counter, _gyro_calibration, _gyro_filter_x, _gyro_filter_y, _gyro_filter_z, _gyro_int, _gyro_range_hit_counter, _gyro_topic, _last_accel_range_hit_count, _last_accel_range_hit_time, _mag_calibration, _mag_enabled, _mag_fifo_overflow_counter, _mag_orb_class_instance, _mag_topic, _mavlink_log_pub, _param_update_sub, _publish_perf, _read_counter, _rotation, _update_accel_calibration(), _update_gyro_calibration(), _update_mag_calibration(), math::LowPassFilter2p::apply(), sensor_gyro_s::device_id, sensor_accel_s::device_id, sensor_accel_s::error_count, sensor_gyro_s::error_count, hrt_absolute_time(), hrt_elapsed_time(), sensor_accel_s::integral_dt, sensor_gyro_s::integral_dt, mag_report, mavlink_log_critical, orb_advertise_multi(), orb_check(), orb_copy(), ORB_ID, ORB_PRIO_LOW, orb_publish(), perf_begin(), perf_end(), perf_set_count(), Integrator::put(), rotate_3f(), sensor_gyro_s::scaling, sensor_accel_s::scaling, sensor_accel_s::timestamp, sensor_gyro_s::timestamp, sensor_gyro_s::x, sensor_accel_s::x, sensor_accel_s::x_integral, sensor_gyro_s::x_integral, DfMpu9250Wrapper::accel_calibration_s::x_offset, DfMpu9250Wrapper::gyro_calibration_s::x_offset, DfMpu9250Wrapper::mag_calibration_s::x_offset, sensor_accel_s::x_raw, sensor_gyro_s::x_raw, DfMpu9250Wrapper::accel_calibration_s::x_scale, DfMpu9250Wrapper::gyro_calibration_s::x_scale, DfMpu9250Wrapper::mag_calibration_s::x_scale, sensor_gyro_s::y, sensor_accel_s::y, sensor_accel_s::y_integral, sensor_gyro_s::y_integral, DfMpu9250Wrapper::accel_calibration_s::y_offset, DfMpu9250Wrapper::gyro_calibration_s::y_offset, DfMpu9250Wrapper::mag_calibration_s::y_offset, sensor_gyro_s::y_raw, sensor_accel_s::y_raw, DfMpu9250Wrapper::accel_calibration_s::y_scale, DfMpu9250Wrapper::gyro_calibration_s::y_scale, DfMpu9250Wrapper::mag_calibration_s::y_scale, sensor_gyro_s::z, sensor_accel_s::z, sensor_gyro_s::z_integral, sensor_accel_s::z_integral, DfMpu9250Wrapper::accel_calibration_s::z_offset, DfMpu9250Wrapper::gyro_calibration_s::z_offset, DfMpu9250Wrapper::mag_calibration_s::z_offset, sensor_gyro_s::z_raw, sensor_accel_s::z_raw, DfMpu9250Wrapper::accel_calibration_s::z_scale, DfMpu9250Wrapper::gyro_calibration_s::z_scale, and DfMpu9250Wrapper::mag_calibration_s::z_scale.
|
private |
Definition at line 444 of file df_mpu9250_wrapper.cpp.
References _accel_calibration, device_id, OK, param_find(), param_get(), DfMpu9250Wrapper::accel_calibration_s::x_offset, DfMpu9250Wrapper::accel_calibration_s::x_scale, DfMpu9250Wrapper::accel_calibration_s::y_offset, DfMpu9250Wrapper::accel_calibration_s::y_scale, DfMpu9250Wrapper::accel_calibration_s::z_offset, and DfMpu9250Wrapper::accel_calibration_s::z_scale.
Referenced by _publish(), and start().
|
private |
Definition at line 369 of file df_mpu9250_wrapper.cpp.
References _gyro_calibration, device_id, OK, param_find(), param_get(), DfMpu9250Wrapper::gyro_calibration_s::x_offset, DfMpu9250Wrapper::gyro_calibration_s::x_scale, DfMpu9250Wrapper::gyro_calibration_s::y_offset, DfMpu9250Wrapper::gyro_calibration_s::y_scale, DfMpu9250Wrapper::gyro_calibration_s::z_offset, and DfMpu9250Wrapper::gyro_calibration_s::z_scale.
Referenced by _publish(), and start().
|
private |
Definition at line 520 of file df_mpu9250_wrapper.cpp.
References _mag_calibration, _mag_enabled, device_id, OK, param_find(), param_get(), DfMpu9250Wrapper::mag_calibration_s::x_offset, DfMpu9250Wrapper::mag_calibration_s::x_scale, DfMpu9250Wrapper::mag_calibration_s::y_offset, DfMpu9250Wrapper::mag_calibration_s::y_scale, DfMpu9250Wrapper::mag_calibration_s::z_offset, and DfMpu9250Wrapper::mag_calibration_s::z_scale.
Referenced by _publish(), and start().
void DfMpu9250Wrapper::info | ( | ) |
Print some debug info.
Definition at line 353 of file df_mpu9250_wrapper.cpp.
References _accel_range_hit_counter, _error_counter, _fifo_corruption_counter, _fifo_overflow_counter, _gyro_range_hit_counter, _mag_enabled, _mag_fifo_overflow_counter, _publish_perf, _read_counter, and perf_print_counter().
Referenced by df_mpu9250_wrapper::info().
int DfMpu9250Wrapper::start | ( | ) |
Start automatic measurement.
Definition at line 285 of file df_mpu9250_wrapper.cpp.
References _accel_orb_class_instance, _accel_topic, _gyro_orb_class_instance, _gyro_topic, _mag_enabled, _param_update_sub, _update_accel_calibration(), _update_gyro_calibration(), _update_mag_calibration(), MPU9250::init(), orb_advertise_multi(), ORB_ID, ORB_PRIO_DEFAULT, orb_subscribe(), and MPU9250::start().
Referenced by df_mpu9250_wrapper::start().
int DfMpu9250Wrapper::stop | ( | ) |
Stop automatic measurement.
Definition at line 340 of file df_mpu9250_wrapper.cpp.
References MPU9250::stop().
Referenced by df_mpu9250_wrapper::stop().
|
private |
Referenced by _publish(), _update_accel_calibration(), and DfMpu9250Wrapper().
|
private |
Definition at line 161 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 162 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 163 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 158 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 154 of file df_mpu9250_wrapper.cpp.
Referenced by DfMpu9250Wrapper(), and start().
|
private |
Definition at line 173 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 119 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and start().
|
private |
Definition at line 169 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 171 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 170 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Referenced by _publish(), _update_gyro_calibration(), and DfMpu9250Wrapper().
|
private |
Definition at line 164 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 165 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 166 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 159 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 155 of file df_mpu9250_wrapper.cpp.
Referenced by DfMpu9250Wrapper(), and start().
|
private |
Definition at line 172 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 120 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and start().
|
private |
Definition at line 178 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 177 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Referenced by _publish(), _update_mag_calibration(), and DfMpu9250Wrapper().
|
private |
Definition at line 180 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), _update_mag_calibration(), DfMpu9250Wrapper(), info(), start(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 174 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 156 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().
|
private |
Definition at line 121 of file df_mpu9250_wrapper.cpp.
Referenced by _publish().
|
private |
Definition at line 123 of file df_mpu9250_wrapper.cpp.
Referenced by _publish().
|
private |
Definition at line 125 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and start().
|
private |
Definition at line 175 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 168 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), DfMpu9250Wrapper(), info(), and ~DfMpu9250Wrapper().
|
private |
Definition at line 182 of file df_mpu9250_wrapper.cpp.
Referenced by _publish(), and DfMpu9250Wrapper().