PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <VehicleAngularVelocity.hpp>
Public Member Functions | |
VehicleAngularVelocity () | |
virtual | ~VehicleAngularVelocity () |
void | Run () override |
bool | Start () |
void | Stop () |
void | PrintStatus () |
Private Member Functions | |
void | ParametersUpdate (bool force=false) |
void | SensorBiasUpdate (bool force=false) |
bool | SensorCorrectionsUpdate (bool force=false) |
Private Attributes | |
DEFINE_PARAMETERS((ParamInt< px4::params::SENS_BOARD_ROT >) _param_sens_board_rot,(ParamFloat< px4::params::SENS_BOARD_X_OFF >) _param_sens_board_x_off,(ParamFloat< px4::params::SENS_BOARD_Y_OFF >) _param_sens_board_y_off,(ParamFloat< px4::params::SENS_BOARD_Z_OFF >) _param_sens_board_z_off) uORB uORB::Subscription | _params_sub {ORB_ID(parameter_update)} |
parameter updates subscription More... | |
uORB::Subscription | _sensor_bias_sub {ORB_ID(sensor_bias)} |
sensor in-run bias correction subscription More... | |
uORB::Subscription | _sensor_correction_sub {ORB_ID(sensor_correction)} |
sensor thermal correction subscription More... | |
uORB::SubscriptionCallbackWorkItem | _sensor_selection_sub {this, ORB_ID(sensor_selection)} |
selected primary sensor subscription More... | |
uORB::SubscriptionCallbackWorkItem | _sensor_sub [MAX_SENSOR_COUNT] |
sensor data subscription More... | |
uORB::SubscriptionCallbackWorkItem | _sensor_control_sub [MAX_SENSOR_COUNT] |
sensor control data subscription More... | |
matrix::Dcmf | _board_rotation |
rotation matrix for the orientation that the board is mounted More... | |
matrix::Vector3f | _offset |
matrix::Vector3f | _scale |
matrix::Vector3f | _bias |
uint32_t | _selected_sensor_device_id {0} |
uint8_t | _selected_sensor {0} |
uint8_t | _selected_sensor_control {0} |
bool | _sensor_control_available {false} |
Static Private Attributes | |
static constexpr int | MAX_SENSOR_COUNT = 3 |
Definition at line 55 of file VehicleAngularVelocity.hpp.
VehicleAngularVelocity::VehicleAngularVelocity | ( | ) |
Definition at line 41 of file VehicleAngularVelocity.cpp.
|
virtual |
Definition at line 47 of file VehicleAngularVelocity.cpp.
References Stop().
|
private |
Definition at line 186 of file VehicleAngularVelocity.cpp.
References _board_rotation, _params_sub, uORB::Subscription::copy(), get_rot_matrix(), math::radians(), and uORB::Subscription::updated().
Referenced by Run(), and Start().
void VehicleAngularVelocity::PrintStatus | ( | ) |
Definition at line 273 of file VehicleAngularVelocity.cpp.
References _selected_sensor, _selected_sensor_control, and _selected_sensor_device_id.
Referenced by Sensors::print_status().
|
override |
Definition at line 210 of file VehicleAngularVelocity.cpp.
References _bias, _board_rotation, _offset, _scale, _selected_sensor, _sensor_control_available, _sensor_control_sub, _sensor_sub, uORB::SubscriptionInterval::copy(), hrt_absolute_time(), ParametersUpdate(), SensorBiasUpdate(), SensorCorrectionsUpdate(), vehicle_angular_velocity_s::timestamp, sensor_gyro_s::timestamp, sensor_gyro_control_s::timestamp_sample, vehicle_angular_velocity_s::timestamp_sample, sensor_gyro_s::x, vehicle_angular_velocity_s::xyz, sensor_gyro_control_s::xyz, sensor_gyro_s::y, and sensor_gyro_s::z.
|
private |
Definition at line 84 of file VehicleAngularVelocity.cpp.
References _bias, _sensor_bias_sub, uORB::Subscription::copy(), sensor_bias_s::gyro_bias, and uORB::Subscription::updated().
Referenced by Run(), and Start().
|
private |
Definition at line 97 of file VehicleAngularVelocity.cpp.
References _offset, _scale, _selected_sensor, _selected_sensor_control, _selected_sensor_device_id, _sensor_control_available, _sensor_control_sub, _sensor_correction_sub, _sensor_selection_sub, _sensor_sub, uORB::SubscriptionInterval::copy(), uORB::Subscription::copy(), sensor_selection_s::gyro_device_id, MAX_SENSOR_COUNT, uORB::SubscriptionInterval::updated(), and uORB::Subscription::updated().
Referenced by Run(), and Start().
bool VehicleAngularVelocity::Start | ( | ) |
Definition at line 53 of file VehicleAngularVelocity.cpp.
References _bias, _offset, _scale, _sensor_selection_sub, ParametersUpdate(), uORB::SubscriptionCallback::registerCallback(), SensorBiasUpdate(), SensorCorrectionsUpdate(), and matrix::Matrix< Type, M, N >::zero().
Referenced by Sensors::Sensors().
void VehicleAngularVelocity::Stop | ( | ) |
Definition at line 71 of file VehicleAngularVelocity.cpp.
References _sensor_selection_sub, _sensor_sub, and uORB::SubscriptionCallback::unregisterCallback().
Referenced by Sensors::~Sensors(), and ~VehicleAngularVelocity().
|
private |
Definition at line 109 of file VehicleAngularVelocity.hpp.
Referenced by Run(), SensorBiasUpdate(), and Start().
|
private |
rotation matrix for the orientation that the board is mounted
Definition at line 105 of file VehicleAngularVelocity.hpp.
Referenced by ParametersUpdate(), and Run().
|
private |
Definition at line 107 of file VehicleAngularVelocity.hpp.
Referenced by Run(), SensorCorrectionsUpdate(), and Start().
|
private |
parameter updates subscription
Definition at line 87 of file VehicleAngularVelocity.hpp.
Referenced by ParametersUpdate().
|
private |
Definition at line 108 of file VehicleAngularVelocity.hpp.
Referenced by Run(), SensorCorrectionsUpdate(), and Start().
|
private |
Definition at line 112 of file VehicleAngularVelocity.hpp.
Referenced by PrintStatus(), Run(), and SensorCorrectionsUpdate().
|
private |
Definition at line 113 of file VehicleAngularVelocity.hpp.
Referenced by PrintStatus(), and SensorCorrectionsUpdate().
|
private |
Definition at line 111 of file VehicleAngularVelocity.hpp.
Referenced by PrintStatus(), and SensorCorrectionsUpdate().
|
private |
sensor in-run bias correction subscription
Definition at line 88 of file VehicleAngularVelocity.hpp.
Referenced by SensorBiasUpdate().
|
private |
Definition at line 114 of file VehicleAngularVelocity.hpp.
Referenced by Run(), and SensorCorrectionsUpdate().
|
private |
sensor control data subscription
Definition at line 99 of file VehicleAngularVelocity.hpp.
Referenced by Run(), and SensorCorrectionsUpdate().
|
private |
sensor thermal correction subscription
Definition at line 89 of file VehicleAngularVelocity.hpp.
Referenced by SensorCorrectionsUpdate().
|
private |
selected primary sensor subscription
Definition at line 91 of file VehicleAngularVelocity.hpp.
Referenced by SensorCorrectionsUpdate(), Start(), and Stop().
|
private |
sensor data subscription
Definition at line 93 of file VehicleAngularVelocity.hpp.
Referenced by Run(), SensorCorrectionsUpdate(), and Stop().
|
staticprivate |
Definition at line 75 of file VehicleAngularVelocity.hpp.
Referenced by SensorCorrectionsUpdate().