#include <stdio.h>
#include <stdint.h>
#include <stdbool.h>
#include <math.h>
#include <AP_Module_Structures.h>
Go to the source code of this file.
◆ degrees
#define degrees |
( |
|
x | ) |
(x * 180.0 / M_PI) |
Definition at line 23 of file moduletest.c.
Referenced by AP_GPS_SBP::_attempt_state_update(), AP_GPS_SBP2::_attempt_state_update(), AP_InertialSensor::_calculate_trim(), AP_GPS_UBLOX::_parse_gps(), HALSITL::SITL_State::_update_gps(), AP_TECS::_update_pitch(), ap_hook_AHRS_update(), ap_hook_gyro_sample(), AP_Landing_Deepstall::build_approach_path(), AP_GPS::calc_blended_state(), SITL::JSBSim::create_templates(), SITL::Aircraft::fill_fdm(), AC_AttitudeControl::get_att_error_angle_deg(), AC_AttitudeControl::get_att_target_euler_cd(), AP_GPS_MAV::handle_msg(), DataFlash_Class::Log_Write_AHRS2(), DataFlash_Class::Log_Write_POS(), DataFlash_Class::Log_Write_Rate(), AP_L1_Control::nav_roll_cd(), AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(), AP_GPS_GSOF::process_message(), AP_GPS_SBF::process_message(), CompassLearn::process_sample(), SITL::JSBSim::recv_fdm(), SITL::ADSB::send_report(), AC_AttitudeControl::set_yaw_target_to_current_heading(), AP_GPS::setHIL(), SITL::Aircraft::smooth_sensors(), AP_Mount_Servo::stabilize(), AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(), AP_Landing::type_slope_setup_landing_glide_slope(), SITL::Tracker::update(), AP_AHRS_View::update(), AP_AHRS::update_AOA_SSA(), AP_AHRS::update_cd_values(), AP_Landing_Deepstall::update_steering(), AP_Landing_Deepstall::verify_breakout(), and AP_Landing_Deepstall::verify_land().
◆ ap_hook_accel_sample()
void ap_hook_accel_sample |
( |
const struct accel_sample * |
state | ) |
|
◆ ap_hook_AHRS_update()
void ap_hook_AHRS_update |
( |
const struct AHRS_state * |
state | ) |
|
◆ ap_hook_gyro_sample()
void ap_hook_gyro_sample |
( |
const struct gyro_sample * |
state | ) |
|
◆ ap_hook_setup_complete()
void ap_hook_setup_complete |
( |
uint64_t |
time_us | ) |
|
◆ ap_hook_setup_start()
void ap_hook_setup_start |
( |
uint64_t |
time_us | ) |
|