PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <sih.hpp>
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 Sih * | instantiate (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 () |
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 |
|
virtualdefault |
|
static |
Definition at line 66 of file sih.cpp.
References print_usage().
|
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().
|
private |
|
static |
Definition at line 454 of file sih.cpp.
References f().
Referenced by noiseGauss3f(), and reconstruct_sensors_signals().
|
private |
Definition at line 241 of file sih.cpp.
References _vehicle_gps_pos, vehicle_gps_position_s::c_variance_rad, vehicle_gps_position_s::eph, vehicle_gps_position_s::epv, vehicle_gps_position_s::fix_type, vehicle_gps_position_s::hdop, vehicle_gps_position_s::heading, vehicle_gps_position_s::heading_offset, vehicle_gps_position_s::s_variance_m_s, vehicle_gps_position_s::satellites_used, and vehicle_gps_position_s::vdop.
Referenced by run().
|
private |
|
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().
|
static |
|
static |
Definition at line 484 of file sih.cpp.
References generate_wgn().
Referenced by reconstruct_sensors_signals().
|
private |
Check for parameter changes and update them if needed.
parameter_update_sub | uorb subscription to parameter_update |
force | for 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().
|
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().
|
override |
|
static |
|
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().
|
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().
|
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().
|
override |
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().
|
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().
|
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().
|
static |
|
static |
|
private |
Definition at line 175 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_IMU().
|
private |
Definition at line 124 of file sih.hpp.
Referenced by read_motors(), and run().
|
private |
Definition at line 116 of file sih.hpp.
Referenced by publish_sih().
|
private |
Definition at line 117 of file sih.hpp.
Referenced by publish_sih().
|
private |
Definition at line 182 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_IMU().
|
private |
Definition at line 183 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_IMU().
|
private |
Definition at line 167 of file sih.hpp.
Referenced by equations_of_motion(), and reconstruct_sensors_signals().
|
private |
Definition at line 187 of file sih.hpp.
Referenced by parameters_updated(), and reconstruct_sensors_signals().
|
private |
Definition at line 154 of file sih.hpp.
Referenced by equations_of_motion(), and inner_loop().
|
private |
Definition at line 158 of file sih.hpp.
Referenced by equations_of_motion(), and generate_force_and_torques().
|
private |
Definition at line 120 of file sih.hpp.
Referenced by publish_sih().
|
private |
Definition at line 121 of file sih.hpp.
Referenced by publish_sih().
|
private |
Definition at line 181 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_gps().
|
private |
Definition at line 181 of file sih.hpp.
Referenced by publish_sih(), and reconstruct_sensors_signals().
|
private |
Definition at line 179 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_gps().
|
private |
Definition at line 179 of file sih.hpp.
Referenced by publish_sih(), and reconstruct_sensors_signals().
|
private |
Definition at line 180 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_gps().
|
private |
Definition at line 180 of file sih.hpp.
Referenced by publish_sih(), and reconstruct_sensors_signals().
|
private |
Definition at line 151 of file sih.hpp.
Referenced by inner_loop(), and run().
|
private |
Definition at line 178 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_gps().
|
private |
Definition at line 155 of file sih.hpp.
Referenced by equations_of_motion().
|
private |
Definition at line 177 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_IMU().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by parameters_updated(), and reconstruct_sensors_signals().
|
private |
Definition at line 189 of file sih.hpp.
Referenced by equations_of_motion(), and parameters_updated().
|
private |
Definition at line 190 of file sih.hpp.
Referenced by equations_of_motion(), and parameters_updated().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by generate_force_and_torques(), and parameters_updated().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by generate_force_and_torques(), and parameters_updated().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by generate_force_and_torques(), and parameters_updated().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by generate_force_and_torques(), and parameters_updated().
|
private |
Definition at line 150 of file sih.hpp.
Referenced by inner_loop(), and run().
|
private |
Definition at line 187 of file sih.hpp.
Referenced by parameters_updated(), and reconstruct_sensors_signals().
|
private |
Definition at line 187 of file sih.hpp.
Referenced by parameters_updated(), and reconstruct_sensors_signals().
|
private |
|
private |
Definition at line 160 of file sih.hpp.
Referenced by equations_of_motion(), and generate_force_and_torques().
|
private |
Definition at line 176 of file sih.hpp.
Referenced by reconstruct_sensors_signals(), and send_IMU().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by equations_of_motion(), and parameters_updated().
|
private |
Definition at line 159 of file sih.hpp.
Referenced by equations_of_motion(), and generate_force_and_torques().
|
private |
Definition at line 191 of file sih.hpp.
Referenced by parameters_updated(), and reconstruct_sensors_signals().
|
private |
Definition at line 153 of file sih.hpp.
Referenced by inner_loop(), send_gps(), and send_IMU().
|
private |
Definition at line 161 of file sih.hpp.
Referenced by equations_of_motion(), init_variables(), and reconstruct_sensors_signals().
|
private |
Definition at line 164 of file sih.hpp.
Referenced by equations_of_motion().
|
private |
Definition at line 123 of file sih.hpp.
Referenced by parameters_update_poll().
|
private |
Definition at line 102 of file sih.hpp.
Referenced by send_IMU().
|
private |
Definition at line 105 of file sih.hpp.
Referenced by send_IMU().
|
private |
Definition at line 103 of file sih.hpp.
Referenced by send_IMU().
|
private |
Definition at line 104 of file sih.hpp.
Referenced by send_IMU().
|
private |
Definition at line 166 of file sih.hpp.
Referenced by equations_of_motion(), init_variables(), and publish_sih().
|
private |
Definition at line 169 of file sih.hpp.
Referenced by equations_of_motion().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by generate_force_and_torques(), and parameters_updated().
|
private |
|
private |
Definition at line 152 of file sih.hpp.
Referenced by inner_loop(), and run().
|
private |
Definition at line 157 of file sih.hpp.
Referenced by equations_of_motion(), and generate_force_and_torques().
|
private |
Definition at line 186 of file sih.hpp.
Referenced by generate_force_and_torques(), and parameters_updated().
|
private |
Definition at line 171 of file sih.hpp.
Referenced by generate_force_and_torques(), init_variables(), and read_motors().
|
private |
|
private |
Definition at line 162 of file sih.hpp.
Referenced by equations_of_motion(), generate_force_and_torques(), init_variables(), publish_sih(), and reconstruct_sensors_signals().
|
private |
Definition at line 165 of file sih.hpp.
Referenced by equations_of_motion(), and reconstruct_sensors_signals().
|
private |
Definition at line 112 of file sih.hpp.
Referenced by publish_sih().
|
private |
Definition at line 113 of file sih.hpp.
Referenced by publish_sih().
|
private |
Definition at line 108 of file sih.hpp.
Referenced by init_sensors(), and send_gps().
|
private |
Definition at line 109 of file sih.hpp.
Referenced by send_gps().
|
private |
Definition at line 168 of file sih.hpp.
Referenced by equations_of_motion(), generate_force_and_torques(), init_variables(), publish_sih(), and reconstruct_sensors_signals().
|
private |
Definition at line 170 of file sih.hpp.
Referenced by equations_of_motion().
|
private |
Definition at line 188 of file sih.hpp.
Referenced by equations_of_motion(), and parameters_updated().
|
staticprivate |
|
staticprivate |
Definition at line 127 of file sih.hpp.
Referenced by read_motors().
|
staticprivate |
Definition at line 128 of file sih.hpp.
Referenced by send_IMU().
|
staticprivate |
Definition at line 129 of file sih.hpp.
Referenced by reconstruct_sensors_signals().
|
staticprivate |
Definition at line 130 of file sih.hpp.
Referenced by reconstruct_sensors_signals().