PX4 Firmware
PX4 Autopilot Software http://px4.io
Sih Class Reference

#include <sih.hpp>

Inheritance diagram for Sih:
Collaboration diagram for Sih:

Public Member Functions

 Sih ()
 
virtual ~Sih ()=default
 
void run () override
 
int print_status () override
 

Static Public Member Functions

static int task_spawn (int argc, char *argv[])
 
static Sihinstantiate (int argc, char *argv[])
 
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 
static float generate_wgn ()
 
static matrix::Vector3f noiseGauss3f (float stdx, float stdy, float stdz)
 
static void timer_callback (void *sem)
 

Private Member Functions

void parameters_update_poll ()
 Check for parameter changes and update them if needed. More...
 
void parameters_updated ()
 
void init_variables ()
 
void init_sensors ()
 
void read_motors ()
 
void generate_force_and_torques ()
 
void equations_of_motion ()
 
void reconstruct_sensors_signals ()
 
void send_IMU ()
 
void send_gps ()
 
void publish_sih ()
 
void inner_loop ()
 

Private Attributes

PX4Accelerometer _px4_accel { 1311244, ORB_PRIO_DEFAULT, ROTATION_NONE }
 
PX4Gyroscope _px4_gyro { 2294028, ORB_PRIO_DEFAULT, ROTATION_NONE }
 
PX4Magnetometer _px4_mag { 197388, ORB_PRIO_DEFAULT, ROTATION_NONE }
 
PX4Barometer _px4_baro { 6620172, ORB_PRIO_DEFAULT }
 
vehicle_gps_position_s _vehicle_gps_pos {}
 
orb_advert_t _vehicle_gps_pos_pub {nullptr}
 
vehicle_angular_velocity_s _vehicle_angular_velocity_gt {}
 
orb_advert_t _vehicle_angular_velocity_gt_pub {nullptr}
 
vehicle_attitude_s _att_gt {}
 
orb_advert_t _att_gt_pub {nullptr}
 
vehicle_global_position_s _gpos_gt {}
 
orb_advert_t _gpos_gt_pub {nullptr}
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 
int _actuator_out_sub {-1}
 
perf_counter_t _loop_perf
 
perf_counter_t _sampling_perf
 
px4_sem_t _data_semaphore
 
hrt_call _timer_call
 
hrt_abstime _last_run
 
hrt_abstime _gps_time
 
hrt_abstime _serial_time
 
hrt_abstime _now
 
float _dt
 
bool _grounded {true}
 
matrix::Vector3f _T_B
 
matrix::Vector3f _Fa_I
 
matrix::Vector3f _Mt_B
 
matrix::Vector3f _Ma_B
 
matrix::Vector3f _p_I
 
matrix::Vector3f _v_I
 
matrix::Vector3f _v_B
 
matrix::Vector3f _p_I_dot
 
matrix::Vector3f _v_I_dot
 
matrix::Quatf _q
 
matrix::Dcmf _C_IB
 
matrix::Vector3f _w_B
 
matrix::Quatf _q_dot
 
matrix::Vector3f _w_B_dot
 
float _u [NB_MOTORS]
 
matrix::Vector3f _acc
 
matrix::Vector3f _mag
 
matrix::Vector3f _gyro
 
matrix::Vector3f _gps_vel
 
double _gps_lat
 
double _gps_lat_noiseless
 
double _gps_lon
 
double _gps_lon_noiseless
 
float _gps_alt
 
float _gps_alt_noiseless
 
float _baro_p_mBar
 
float _baro_temp_c
 
float _MASS
 
float _T_MAX
 
float _Q_MAX
 
float _L_ROLL
 
float _L_PITCH
 
float _KDV
 
float _KDW
 
float _H0
 
double _LAT0
 
double _LON0
 
double _COS_LAT0
 
matrix::Vector3f _W_I
 
matrix::Matrix3f _I
 
matrix::Matrix3f _Im1
 
matrix::Vector3f _mu_I
 

Static Private Attributes

static constexpr uint16_t NB_MOTORS = 4
 
static constexpr float T1_C = 15.0f
 
static constexpr float T1_K = T1_C - CONSTANTS_ABSOLUTE_NULL_CELSIUS
 
static constexpr float TEMP_GRADIENT = -6.5f / 1000.0f
 
static constexpr hrt_abstime LOOP_INTERVAL = 4000
 

Detailed Description

Definition at line 58 of file sih.hpp.

Constructor & Destructor Documentation

◆ Sih()

Sih::Sih ( )

Definition at line 100 of file sih.cpp.

◆ ~Sih()

virtual Sih::~Sih ( )
virtualdefault

Member Function Documentation

◆ custom_command()

int Sih::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 66 of file sih.cpp.

References print_usage().

Here is the call graph for this function:

◆ equations_of_motion()

void Sih::equations_of_motion ( )
private

Definition at line 286 of file sih.cpp.

References _C_IB, _dt, _Fa_I, _grounded, _I, _Im1, _Ma_B, _MASS, _Mt_B, _p_I, _p_I_dot, _q, _q_dot, _T_B, _v_I, _v_I_dot, _w_B, _w_B_dot, _W_I, matrix::Vector3< Type >::cross(), matrix::Quaternion< Type >::derivative1(), matrix::Vector< Type, M >::normalize(), matrix::Matrix< Type, M, N >::setZero(), and matrix::Quaternion< Type >::to_dcm().

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generate_force_and_torques()

void Sih::generate_force_and_torques ( )
private

Definition at line 274 of file sih.cpp.

References _Fa_I, _KDV, _KDW, _L_PITCH, _L_ROLL, _Ma_B, _Mt_B, _Q_MAX, _T_B, _T_MAX, _u, _v_I, _w_B, and f().

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generate_wgn()

float Sih::generate_wgn ( )
static

Definition at line 454 of file sih.cpp.

References f().

Referenced by noiseGauss3f(), and reconstruct_sensors_signals().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_sensors()

void Sih::init_sensors ( )
private

◆ init_variables()

void Sih::init_variables ( )
private

Definition at line 229 of file sih.cpp.

References _p_I, _q, _u, _v_I, _w_B, and f().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inner_loop()

void Sih::inner_loop ( )
private

Definition at line 154 of file sih.cpp.

References _dt, _gps_time, _last_run, _now, _serial_time, equations_of_motion(), f(), generate_force_and_torques(), hrt_absolute_time(), parameters_update_poll(), publish_sih(), read_motors(), reconstruct_sensors_signals(), send_gps(), and send_IMU().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ instantiate()

Sih * Sih::instantiate ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 89 of file sih.cpp.

References ll40ls::instance.

◆ noiseGauss3f()

Vector3f Sih::noiseGauss3f ( float  stdx,
float  stdy,
float  stdz 
)
static

Definition at line 484 of file sih.cpp.

References generate_wgn().

Referenced by reconstruct_sensors_signals().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ parameters_update_poll()

void Sih::parameters_update_poll ( )
private

Check for parameter changes and update them if needed.

Parameters
parameter_update_subuorb subscription to parameter_update
forcefor a parameter update

Definition at line 185 of file sih.cpp.

References _parameter_update_sub, uORB::Subscription::copy(), parameters_updated(), and uORB::Subscription::updated().

Referenced by inner_loop(), and run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ parameters_updated()

void Sih::parameters_updated ( )
private

Definition at line 200 of file sih.cpp.

References _COS_LAT0, _H0, _I, _Im1, _KDV, _KDW, _L_PITCH, _L_ROLL, _LAT0, _LON0, _MASS, _mu_I, _Q_MAX, _T_MAX, _W_I, CONSTANTS_ONE_G, matrix::diag(), f(), matrix::inv(), and math::radians().

Referenced by parameters_update_poll().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_status()

int Sih::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 60 of file sih.cpp.

◆ print_usage()

int Sih::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 494 of file sih.cpp.

◆ publish_sih()

void Sih::publish_sih ( )
private

Definition at line 407 of file sih.cpp.

References _att_gt, _att_gt_pub, _gpos_gt, _gpos_gt_pub, _gps_alt_noiseless, _gps_lat_noiseless, _gps_lon_noiseless, _q, _v_I, _vehicle_angular_velocity_gt, _vehicle_angular_velocity_gt_pub, _w_B, vehicle_global_position_s::alt, hrt_absolute_time(), vehicle_global_position_s::lat, vehicle_global_position_s::lon, orb_advertise(), ORB_ID, orb_publish(), vehicle_attitude_s::q, vehicle_attitude_s::timestamp, vehicle_global_position_s::timestamp, vehicle_angular_velocity_s::timestamp, vehicle_global_position_s::vel_d, vehicle_global_position_s::vel_e, vehicle_global_position_s::vel_n, and vehicle_angular_velocity_s::xyz.

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_motors()

void Sih::read_motors ( )
private

Definition at line 256 of file sih.cpp.

References _actuator_out_sub, _u, math::constrain(), NB_MOTORS, orb_check(), orb_copy(), ORB_ID, PWM_DEFAULT_MAX, and PWM_DEFAULT_MIN.

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reconstruct_sensors_signals()

void Sih::reconstruct_sensors_signals ( )
private

Definition at line 322 of file sih.cpp.

References _acc, _baro_p_mBar, _baro_temp_c, _C_IB, _COS_LAT0, _gps_alt, _gps_alt_noiseless, _gps_lat, _gps_lat_noiseless, _gps_lon, _gps_lon_noiseless, _gps_vel, _gyro, _H0, _LAT0, _LON0, _mag, _mu_I, _p_I, _v_I, _v_I_dot, _w_B, CONSTANTS_ABSOLUTE_NULL_CELSIUS, CONSTANTS_AIR_GAS_CONST, CONSTANTS_ONE_G, CONSTANTS_RADIUS_OF_EARTH, CONSTANTS_STD_PRESSURE_MBAR, math::degrees(), f(), generate_wgn(), noiseGauss3f(), T1_K, TEMP_GRADIENT, and matrix::Matrix< Type, M, N >::transpose().

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ run()

void Sih::run ( )
override
See also
ModuleBase::run()

Definition at line 107 of file sih.cpp.

References _actuator_out_sub, _data_semaphore, _gps_time, _last_run, _loop_perf, _sampling_perf, _serial_time, _timer_call, hrt_absolute_time(), hrt_abstime, hrt_call_every(), hrt_cancel(), init_sensors(), init_variables(), inner_loop(), LOOP_INTERVAL, ORB_ID, orb_subscribe(), orb_unsubscribe(), parameters_update_poll(), perf_begin(), perf_end(), and timer_callback().

Here is the call graph for this function:

◆ send_gps()

void Sih::send_gps ( )
private

Definition at line 383 of file sih.cpp.

References _gps_alt, _gps_lat, _gps_lon, _gps_vel, _now, _vehicle_gps_pos, _vehicle_gps_pos_pub, vehicle_gps_position_s::alt, vehicle_gps_position_s::alt_ellipsoid, matrix::atan2(), vehicle_gps_position_s::cog_rad, f(), vehicle_gps_position_s::lat, vehicle_gps_position_s::lon, orb_advertise(), ORB_ID, orb_publish(), vehicle_gps_position_s::timestamp, vehicle_gps_position_s::vel_d_m_s, vehicle_gps_position_s::vel_e_m_s, vehicle_gps_position_s::vel_m_s, vehicle_gps_position_s::vel_n_m_s, and vehicle_gps_position_s::vel_ned_valid.

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_IMU()

void Sih::send_IMU ( )
private

Definition at line 350 of file sih.cpp.

References _acc, _baro_p_mBar, _baro_temp_c, _gyro, _mag, _now, _px4_accel, _px4_baro, _px4_gyro, _px4_mag, PX4Magnetometer::set_scale(), PX4Accelerometer::set_scale(), PX4Gyroscope::set_scale(), PX4Barometer::set_temperature(), PX4Magnetometer::set_temperature(), PX4Accelerometer::set_temperature(), PX4Gyroscope::set_temperature(), T1_C, PX4Barometer::update(), PX4Magnetometer::update(), PX4Accelerometer::update(), and PX4Gyroscope::update().

Referenced by inner_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ task_spawn()

int Sih::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 72 of file sih.cpp.

◆ timer_callback()

void Sih::timer_callback ( void *  sem)
static

Definition at line 148 of file sih.cpp.

Referenced by run().

Here is the caller graph for this function:

Member Data Documentation

◆ _acc

matrix::Vector3f Sih::_acc
private

Definition at line 175 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_IMU().

◆ _actuator_out_sub

int Sih::_actuator_out_sub {-1}
private

Definition at line 124 of file sih.hpp.

Referenced by read_motors(), and run().

◆ _att_gt

vehicle_attitude_s Sih::_att_gt {}
private

Definition at line 116 of file sih.hpp.

Referenced by publish_sih().

◆ _att_gt_pub

orb_advert_t Sih::_att_gt_pub {nullptr}
private

Definition at line 117 of file sih.hpp.

Referenced by publish_sih().

◆ _baro_p_mBar

float Sih::_baro_p_mBar
private

Definition at line 182 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_IMU().

◆ _baro_temp_c

float Sih::_baro_temp_c
private

Definition at line 183 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_IMU().

◆ _C_IB

matrix::Dcmf Sih::_C_IB
private

Definition at line 167 of file sih.hpp.

Referenced by equations_of_motion(), and reconstruct_sensors_signals().

◆ _COS_LAT0

double Sih::_COS_LAT0
private

Definition at line 187 of file sih.hpp.

Referenced by parameters_updated(), and reconstruct_sensors_signals().

◆ _data_semaphore

px4_sem_t Sih::_data_semaphore
private

Definition at line 147 of file sih.hpp.

Referenced by run().

◆ _dt

float Sih::_dt
private

Definition at line 154 of file sih.hpp.

Referenced by equations_of_motion(), and inner_loop().

◆ _Fa_I

matrix::Vector3f Sih::_Fa_I
private

Definition at line 158 of file sih.hpp.

Referenced by equations_of_motion(), and generate_force_and_torques().

◆ _gpos_gt

vehicle_global_position_s Sih::_gpos_gt {}
private

Definition at line 120 of file sih.hpp.

Referenced by publish_sih().

◆ _gpos_gt_pub

orb_advert_t Sih::_gpos_gt_pub {nullptr}
private

Definition at line 121 of file sih.hpp.

Referenced by publish_sih().

◆ _gps_alt

float Sih::_gps_alt
private

Definition at line 181 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_gps().

◆ _gps_alt_noiseless

float Sih::_gps_alt_noiseless
private

Definition at line 181 of file sih.hpp.

Referenced by publish_sih(), and reconstruct_sensors_signals().

◆ _gps_lat

double Sih::_gps_lat
private

Definition at line 179 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_gps().

◆ _gps_lat_noiseless

double Sih::_gps_lat_noiseless
private

Definition at line 179 of file sih.hpp.

Referenced by publish_sih(), and reconstruct_sensors_signals().

◆ _gps_lon

double Sih::_gps_lon
private

Definition at line 180 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_gps().

◆ _gps_lon_noiseless

double Sih::_gps_lon_noiseless
private

Definition at line 180 of file sih.hpp.

Referenced by publish_sih(), and reconstruct_sensors_signals().

◆ _gps_time

hrt_abstime Sih::_gps_time
private

Definition at line 151 of file sih.hpp.

Referenced by inner_loop(), and run().

◆ _gps_vel

matrix::Vector3f Sih::_gps_vel
private

Definition at line 178 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_gps().

◆ _grounded

bool Sih::_grounded {true}
private

Definition at line 155 of file sih.hpp.

Referenced by equations_of_motion().

◆ _gyro

matrix::Vector3f Sih::_gyro
private

Definition at line 177 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_IMU().

◆ _H0

float Sih::_H0
private

Definition at line 186 of file sih.hpp.

Referenced by parameters_updated(), and reconstruct_sensors_signals().

◆ _I

matrix::Matrix3f Sih::_I
private

Definition at line 189 of file sih.hpp.

Referenced by equations_of_motion(), and parameters_updated().

◆ _Im1

matrix::Matrix3f Sih::_Im1
private

Definition at line 190 of file sih.hpp.

Referenced by equations_of_motion(), and parameters_updated().

◆ _KDV

float Sih::_KDV
private

Definition at line 186 of file sih.hpp.

Referenced by generate_force_and_torques(), and parameters_updated().

◆ _KDW

float Sih::_KDW
private

Definition at line 186 of file sih.hpp.

Referenced by generate_force_and_torques(), and parameters_updated().

◆ _L_PITCH

float Sih::_L_PITCH
private

Definition at line 186 of file sih.hpp.

Referenced by generate_force_and_torques(), and parameters_updated().

◆ _L_ROLL

float Sih::_L_ROLL
private

Definition at line 186 of file sih.hpp.

Referenced by generate_force_and_torques(), and parameters_updated().

◆ _last_run

hrt_abstime Sih::_last_run
private

Definition at line 150 of file sih.hpp.

Referenced by inner_loop(), and run().

◆ _LAT0

double Sih::_LAT0
private

Definition at line 187 of file sih.hpp.

Referenced by parameters_updated(), and reconstruct_sensors_signals().

◆ _LON0

double Sih::_LON0
private

Definition at line 187 of file sih.hpp.

Referenced by parameters_updated(), and reconstruct_sensors_signals().

◆ _loop_perf

perf_counter_t Sih::_loop_perf
private

Definition at line 144 of file sih.hpp.

Referenced by run().

◆ _Ma_B

matrix::Vector3f Sih::_Ma_B
private

Definition at line 160 of file sih.hpp.

Referenced by equations_of_motion(), and generate_force_and_torques().

◆ _mag

matrix::Vector3f Sih::_mag
private

Definition at line 176 of file sih.hpp.

Referenced by reconstruct_sensors_signals(), and send_IMU().

◆ _MASS

float Sih::_MASS
private

Definition at line 186 of file sih.hpp.

Referenced by equations_of_motion(), and parameters_updated().

◆ _Mt_B

matrix::Vector3f Sih::_Mt_B
private

Definition at line 159 of file sih.hpp.

Referenced by equations_of_motion(), and generate_force_and_torques().

◆ _mu_I

matrix::Vector3f Sih::_mu_I
private

Definition at line 191 of file sih.hpp.

Referenced by parameters_updated(), and reconstruct_sensors_signals().

◆ _now

hrt_abstime Sih::_now
private

Definition at line 153 of file sih.hpp.

Referenced by inner_loop(), send_gps(), and send_IMU().

◆ _p_I

matrix::Vector3f Sih::_p_I
private

Definition at line 161 of file sih.hpp.

Referenced by equations_of_motion(), init_variables(), and reconstruct_sensors_signals().

◆ _p_I_dot

matrix::Vector3f Sih::_p_I_dot
private

Definition at line 164 of file sih.hpp.

Referenced by equations_of_motion().

◆ _parameter_update_sub

uORB::Subscription Sih::_parameter_update_sub {ORB_ID(parameter_update)}
private

Definition at line 123 of file sih.hpp.

Referenced by parameters_update_poll().

◆ _px4_accel

PX4Accelerometer Sih::_px4_accel { 1311244, ORB_PRIO_DEFAULT, ROTATION_NONE }
private

Definition at line 102 of file sih.hpp.

Referenced by send_IMU().

◆ _px4_baro

PX4Barometer Sih::_px4_baro { 6620172, ORB_PRIO_DEFAULT }
private

Definition at line 105 of file sih.hpp.

Referenced by send_IMU().

◆ _px4_gyro

PX4Gyroscope Sih::_px4_gyro { 2294028, ORB_PRIO_DEFAULT, ROTATION_NONE }
private

Definition at line 103 of file sih.hpp.

Referenced by send_IMU().

◆ _px4_mag

PX4Magnetometer Sih::_px4_mag { 197388, ORB_PRIO_DEFAULT, ROTATION_NONE }
private

Definition at line 104 of file sih.hpp.

Referenced by send_IMU().

◆ _q

matrix::Quatf Sih::_q
private

Definition at line 166 of file sih.hpp.

Referenced by equations_of_motion(), init_variables(), and publish_sih().

◆ _q_dot

matrix::Quatf Sih::_q_dot
private

Definition at line 169 of file sih.hpp.

Referenced by equations_of_motion().

◆ _Q_MAX

float Sih::_Q_MAX
private

Definition at line 186 of file sih.hpp.

Referenced by generate_force_and_torques(), and parameters_updated().

◆ _sampling_perf

perf_counter_t Sih::_sampling_perf
private

Definition at line 145 of file sih.hpp.

Referenced by run().

◆ _serial_time

hrt_abstime Sih::_serial_time
private

Definition at line 152 of file sih.hpp.

Referenced by inner_loop(), and run().

◆ _T_B

matrix::Vector3f Sih::_T_B
private

Definition at line 157 of file sih.hpp.

Referenced by equations_of_motion(), and generate_force_and_torques().

◆ _T_MAX

float Sih::_T_MAX
private

Definition at line 186 of file sih.hpp.

Referenced by generate_force_and_torques(), and parameters_updated().

◆ _timer_call

hrt_call Sih::_timer_call
private

Definition at line 149 of file sih.hpp.

Referenced by run().

◆ _u

float Sih::_u[NB_MOTORS]
private

Definition at line 171 of file sih.hpp.

Referenced by generate_force_and_torques(), init_variables(), and read_motors().

◆ _v_B

matrix::Vector3f Sih::_v_B
private

Definition at line 163 of file sih.hpp.

◆ _v_I

◆ _v_I_dot

matrix::Vector3f Sih::_v_I_dot
private

Definition at line 165 of file sih.hpp.

Referenced by equations_of_motion(), and reconstruct_sensors_signals().

◆ _vehicle_angular_velocity_gt

vehicle_angular_velocity_s Sih::_vehicle_angular_velocity_gt {}
private

Definition at line 112 of file sih.hpp.

Referenced by publish_sih().

◆ _vehicle_angular_velocity_gt_pub

orb_advert_t Sih::_vehicle_angular_velocity_gt_pub {nullptr}
private

Definition at line 113 of file sih.hpp.

Referenced by publish_sih().

◆ _vehicle_gps_pos

vehicle_gps_position_s Sih::_vehicle_gps_pos {}
private

Definition at line 108 of file sih.hpp.

Referenced by init_sensors(), and send_gps().

◆ _vehicle_gps_pos_pub

orb_advert_t Sih::_vehicle_gps_pos_pub {nullptr}
private

Definition at line 109 of file sih.hpp.

Referenced by send_gps().

◆ _w_B

◆ _w_B_dot

matrix::Vector3f Sih::_w_B_dot
private

Definition at line 170 of file sih.hpp.

Referenced by equations_of_motion().

◆ _W_I

matrix::Vector3f Sih::_W_I
private

Definition at line 188 of file sih.hpp.

Referenced by equations_of_motion(), and parameters_updated().

◆ LOOP_INTERVAL

constexpr hrt_abstime Sih::LOOP_INTERVAL = 4000
staticprivate

Definition at line 131 of file sih.hpp.

Referenced by run().

◆ NB_MOTORS

constexpr uint16_t Sih::NB_MOTORS = 4
staticprivate

Definition at line 127 of file sih.hpp.

Referenced by read_motors().

◆ T1_C

constexpr float Sih::T1_C = 15.0f
staticprivate

Definition at line 128 of file sih.hpp.

Referenced by send_IMU().

◆ T1_K

constexpr float Sih::T1_K = T1_C - CONSTANTS_ABSOLUTE_NULL_CELSIUS
staticprivate

Definition at line 129 of file sih.hpp.

Referenced by reconstruct_sensors_signals().

◆ TEMP_GRADIENT

constexpr float Sih::TEMP_GRADIENT = -6.5f / 1000.0f
staticprivate

Definition at line 130 of file sih.hpp.

Referenced by reconstruct_sensors_signals().


The documentation for this class was generated from the following files: