APM:Libraries
|
Common definitions and utility routines for the ArduPilot libraries. More...
Go to the source code of this file.
Classes | |
struct | Location_Option_Flags |
struct | Location |
Macros | |
#define | PACKED __attribute__((__packed__)) |
#define | UNUSED_FUNCTION __attribute__((unused)) |
#define | OPTIMIZE(level) __attribute__((optimize(level))) |
#define | NOINLINE __attribute__((noinline)) |
#define | FMT_PRINTF(a, b) __attribute__((format(printf, a, b))) |
#define | FMT_SCANF(a, b) __attribute__((format(scanf, a, b))) |
#define | FALLTHROUGH |
#define | ToRad(x) radians(x) |
#define | ToDeg(x) degrees(x) |
#define | DEFINE_BYTE_ARRAY_METHODS |
#define | LOCATION_ALT_MAX_M 83000 |
#define | BIT_IS_SET(value, bitnumber) (((value) & (1U<<(bitnumber))) != 0) |
#define | LOWBYTE(i) ((uint8_t)(i)) |
#define | HIGHBYTE(i) ((uint8_t)(((uint16_t)(i))>>8)) |
#define | ARRAY_SIZE(_arr) sizeof(_ARRAY_SIZE_HELPER(_arr)) |
#define | ARRAY_SIZE_SIMPLE(_arr) (sizeof(_arr)/sizeof(_arr[0])) |
#define | _UNUSED_RESULT(uniq_, expr_) |
#define | UNUSED_RESULT(expr_) _UNUSED_RESULT(__unique_name_##__COUNTER__, expr_) |
Functions | |
template<typename T , size_t N> | |
char(& | _ARRAY_SIZE_HELPER (T(&_arr)[N]))[N] |
template<typename T > | |
char(& | _ARRAY_SIZE_HELPER (T(&_arr)[0]))[0] |
Conversions | |
#define | SITL_printf(fmt, args ...) do { ::printf("%s(%u): " fmt, __FILE__, __LINE__, ##args); } while(0) |
bool | is_bounded_int32 (int32_t value, int32_t lower_bound, int32_t upper_bound) |
Common definitions and utility routines for the ArduPilot libraries.
Definition in file AP_Common.h.
#define _UNUSED_RESULT | ( | uniq_, | |
expr_ | |||
) |
Definition at line 92 of file AP_Common.h.
#define ARRAY_SIZE | ( | _arr | ) | sizeof(_ARRAY_SIZE_HELPER(_arr)) |
Definition at line 80 of file AP_Common.h.
Referenced by SITL::Calibration::_calibration_poses(), AP_BattMonitor_Bebop::_compute_compensation(), HALSITL::SITL_State::_parse_command_line(), PX4::PX4AnalogSource::_pin_scaler(), VRBRAIN::VRBRAINAnalogSource::_pin_scaler(), HALSITL::SITL_State::_simulator_servos(), Linux::RCInput_Navio2::_timer_tick(), HALSITL::SITL_State::_update_gps_ubx(), accept_unsigned_callback(), AP_BoardConfig::board_setup_sbus(), AP_GPS_SBF::broadcast_configuration_failure_reason(), AP_GPS_UBLOX::broadcast_configuration_failure_reason(), AP_BattMonitor::convert_params(), AP_GPS::detect_instance(), Linux::RCOutput_Disco::disable_ch(), Linux::RCOutput_Disco::enable_ch(), SITL::Frame::find_frame(), SITL::FlightAxis::FlightAxis(), Linux::RCOutput_Disco::get_freq(), Linux::RCInput_Navio2::init(), AP_RAMTRON::init(), Linux::Scheduler::init(), AP_RangeFinder_VL53L0X::init(), AP_Airspeed_MS4525::init(), AP_Airspeed_SDP3X::init(), AP_Airspeed_MS5525::init(), AnalogSource_IIO::init_pins(), AP_GPS_SBF::is_configured(), F4Light::RCOutput::lateInit(), DataFlash_Class::Log_Write_Current_instance(), loop(), AP_GPS_SBF::parse(), Linux::RCOutput_PRU::push(), GCS_MAVLINK::push_deferred_messages(), AP_BoardConfig::px4_setup_pwm(), AP_BoardConfig::px4_start_driver(), AP_Arming::rc_checks_copter_sub(), AP_Compass_HIL::read(), Linux::RCOutput_Disco::read(), AP_GPS_SBF::read(), read_calibration_data(), GCS_MAVLINK::send_message(), Linux::RCOutput_Disco::set_freq(), SchedTest::setup(), DataFlashTest::setup(), setup(), DataFlashTest_AllTypes::setup(), AP_OpticalFlow_Pixart::setup_sensor(), AP_OpticalFlow_Pixart::srom_download(), AP_AutoTune::start(), test_conversions(), test_matrix_eulers(), test_offset(), test_passed_waypoint(), test_printf(), test_quaternion_eulers(), test_wrap_cd(), AP_OpticalFlow_SITL::update(), SRV_Channels::upgrade_motors_servo(), SRV_Channels::upgrade_parameters(), and Linux::RCOutput_Disco::write().
#define ARRAY_SIZE_SIMPLE | ( | _arr | ) | (sizeof(_arr)/sizeof(_arr[0])) |
Definition at line 83 of file AP_Common.h.
Referenced by ChibiOS::GPIO::_attach_interrupt(), ChibiOS::SPIDevice::derive_freq_flag(), AP_ROMFS::find_file(), ChibiOS::I2CDeviceManager::get_device(), ChibiOS::SPIDeviceManager::get_device(), gpio_by_pin_num(), ChibiOS::I2CDeviceManager::I2CDeviceManager(), and ChibiOS::GPIO::init().
Definition at line 68 of file AP_Common.h.
#define DEFINE_BYTE_ARRAY_METHODS |
Definition at line 58 of file AP_Common.h.
#define FALLTHROUGH |
Definition at line 50 of file AP_Common.h.
Referenced by AP_GPS_NMEA::_decode(), AP_GPS_MTK::_detect(), AP_GPS_SIRF::_detect(), AP_GPS_ERB::_detect(), AP_GPS_UBLOX::_detect(), AP_Baro_MS56XX::_init(), ChibiOS::UARTDriver::_timer_tick(), AP_RangeFinder_NMEA::decode(), AP_RangeFinder_LeddarOne::get_reading(), GCS_MAVLINK::handle_command_long_message(), GCS_MAVLINK::handle_common_message(), DataFlash_Class::handle_mavlink_msg(), print_vprintf(), DFMessageWriter_WriteSysInfo::process(), DFMessageWriter_WriteEntireMission::process(), DFMessageWriter_DFLogStart::process(), AP_GPS_ERB::read(), AP_GPS_SIRF::read(), AP_GPS_UBLOX::read(), VRBRAIN::VRBRAINRCOutput::set_output_mode(), PX4::PX4RCOutput::set_output_mode(), GCS_MAVLINK::try_send_message(), AP_TempCalibration::update(), and AP_Landing_Deepstall::verify_land().
#define FMT_PRINTF | ( | a, | |
b | |||
) | __attribute__((format(printf, a, b))) |
Definition at line 39 of file AP_Common.h.
Referenced by Linux::Util::set_custom_storage_directory().
#define FMT_SCANF | ( | a, | |
b | |||
) | __attribute__((format(scanf, a, b))) |
Definition at line 40 of file AP_Common.h.
Referenced by Linux::Util::set_custom_storage_directory().
#define HIGHBYTE | ( | i | ) | ((uint8_t)(((uint16_t)(i))>>8)) |
Definition at line 72 of file AP_Common.h.
Referenced by AP_RangeFinder_LeddarOne::CRC16(), AP_Mission::mission_cmd_to_mavlink_int(), AP_Volz_Protocol::send_command(), test_high_low_byte(), and AP_Volz_Protocol::update().
#define LOCATION_ALT_MAX_M 83000 |
Definition at line 62 of file AP_Common.h.
Referenced by AP_Mission::mavlink_int_to_mission_cmd().
#define LOWBYTE | ( | i | ) | ((uint8_t)(i)) |
Definition at line 71 of file AP_Common.h.
Referenced by AP_RangeFinder_LeddarOne::CRC16(), AP_Mission::mission_cmd_to_mavlink_int(), AP_Volz_Protocol::send_command(), test_high_low_byte(), and AP_Volz_Protocol::update().
#define NOINLINE __attribute__((noinline)) |
Definition at line 37 of file AP_Common.h.
#define OPTIMIZE | ( | level | ) | __attribute__((optimize(level))) |
Definition at line 34 of file AP_Common.h.
#define PACKED __attribute__((__packed__)) |
Definition at line 28 of file AP_Common.h.
Referenced by Linux::RCOutput_AeroIO::_hw_read(), Linux::RCOutput_AeroIO::_hw_write(), AP_Compass_BMM150::_load_trim_values(), AP_Compass_LSM303D::_read_sample(), Linux::OpticalFlow_Onboard::_run_optflow(), Linux::RCOutput_Bebop::_set_ref_speed(), AP_ADC_ADS1115::_start_conversion(), Display_SH1106_I2C::_timer(), Display_SSD1306_I2C::_timer(), HALSITL::SITL_State::_update_gps_mtk(), HALSITL::SITL_State::_update_gps_mtk16(), HALSITL::SITL_State::_update_gps_mtk19(), HALSITL::SITL_State::_update_gps_nova(), HALSITL::SITL_State::_update_gps_sbp(), HALSITL::SITL_State::_update_gps_sbp2(), HALSITL::SITL_State::_update_gps_ubx(), Display_SH1106_I2C::hw_init(), Display_SSD1306_I2C::hw_init(), RC_UART::loop(), Linux::RCOutput_Bebop::play_note(), Linux::RCOutput_PCA9685::push(), Linux::RCOutput_Bebop::read_obs_data(), SITL::XPlane::select_data(), SITL::XPlane::send_data(), SITL::XPlane::send_dref(), AP_Compass_IST8310::timer(), AP_Compass_QMC5883L::timer(), AP_Compass_LIS3MDL::timer(), and AP_Compass_AK09916::timer().
#define SITL_printf | ( | fmt, | |
args ... | |||
) | do { ::printf("%s(%u): " fmt, __FILE__, __LINE__, ##args); } while(0) |
Definition at line 167 of file AP_Common.h.
Definition at line 54 of file AP_Common.h.
Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), AP_InertialSensor::_init_gyro(), HALSITL::SITL_State::_update_gps_mtk(), HALSITL::SITL_State::_update_gps_mtk16(), HALSITL::SITL_State::_update_gps_mtk19(), HALSITL::SITL_State::_update_gps_nmea(), HALSITL::SITL_State::_update_gps_nova(), HALSITL::SITL_State::_update_gps_ubx(), check_result(), AC_AttitudeControl::get_althold_lean_angle_max(), AP_YawController::get_servo_out(), AP_SteerController::get_steering_out_lat_accel(), AP_SteerController::get_steering_out_rate(), AP_GPS_SBF::log_ExtEventPVTGeodetic(), loop(), AP_Mount_SToRM32::status_msg(), test_rotation_accuracy(), AP_Mount_SToRM32_serial::update(), and AP_Mount_SToRM32::update().
Definition at line 53 of file AP_Common.h.
Referenced by AP_InertialSensor::_init_gyro(), AP_AHRS_DCM::_P_gain(), Compass::_setup_earth_field(), AC_WPNav::AC_WPNav(), AP_AHRS::add_trim(), AP_Mount_Backend::calc_angle_to_location(), AC_Circle::calc_velocities(), check_result(), SITL::SITL::convert_body_frame(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::drift_correction_yaw(), AP_InertialSensor_SITL::generate_gyro(), AP_InertialSensor::get_gyro_drift_rate(), AP_SteerController::get_steering_out_rate(), AP_InertialSensor_SITL::gyro_drift(), missing_rotations(), AC_PosControl::run_xy_controller(), AC_Loiter::sanity_check_params(), AP_AHRS::set_trim(), setup(), SITL::SITL::simstate_send(), test_frame_transforms(), test_quaternion_eulers(), test_rotation_accuracy(), CompassLearn::update(), AP_Mount_SToRM32_serial::update(), AP_Mount_SToRM32::update(), and SITL::Aircraft::update_mag_field_bf().
#define UNUSED_FUNCTION __attribute__((unused)) |
Definition at line 31 of file AP_Common.h.
#define UNUSED_RESULT | ( | expr_ | ) | _UNUSED_RESULT(__unique_name_##__COUNTER__, expr_) |
Definition at line 104 of file AP_Common.h.
Referenced by AP_Follow::handle_msg().
char(& _ARRAY_SIZE_HELPER | ( | T(&) | _arr[N] | ) | )[N] |
char(& _ARRAY_SIZE_HELPER | ( | T(&) | _arr[0] | ) | )[0] |
bool is_bounded_int32 | ( | int32_t | value, |
int32_t | lower_bound, | ||
int32_t | upper_bound | ||
) |
Definition at line 29 of file AP_Common.cpp.
Referenced by RC_Channel::in_trim_dz().