APM:Libraries
|
Classes | |
class | AnalogIn |
class | AnalogSource |
class | BetterStream |
class | Device |
class | DigitalSource |
class | GPIO |
class | HAL |
class | I2CDevice |
class | I2CDeviceManager |
class | OpticalFlow |
class | OwnPtr |
class | RCInput |
class | RCOutput |
class | Scheduler |
class | Semaphore |
class | SPIDevice |
class | SPIDeviceManager |
class | Storage |
class | UARTDriver |
class | Util |
Typedefs | |
typedef void(* | Proc) (void) |
Enumerations | |
enum | SPIDeviceType { SPIDevice_Type = -1 } |
Functions | |
FUNCTOR_TYPEDEF (MemberProc, void) | |
const HAL & | get_HAL () |
void | init () |
Generic board initialization function. More... | |
void | panic (const char *errormsg,...) FMT_PRINTF(1 |
uint32_t | micros () |
uint32_t | millis () |
uint64_t | micros64 () |
uint64_t | millis64 () |
template<typename T > | |
bool | operator== (T *a, const OwnPtr< T > &b) |
template<typename T > | |
bool | operator== (const OwnPtr< T > &a, T *b) |
template<typename T > | |
bool | operator!= (T *a, const OwnPtr< T > &b) |
template<typename T > | |
bool | operator!= (const OwnPtr< T > &a, T *b) |
void | cond_yield () |
void | delay (uint32_t ms) |
void | delay_microseconds (uint16_t us) |
void | yield (uint32_t us) |
Variables | |
void | NORETURN |
struct { | |
struct timespec AP_HAL::start_time | |
} | state |
struct { | |
struct timeval AP_HAL::start_time | |
} | state |
typedef void(* AP_HAL::Proc) (void) |
Definition at line 47 of file AP_HAL_Namespace.h.
Global names for all of the existing SPI devices on all platforms.
Enumerator | |
---|---|
SPIDevice_Type |
Definition at line 54 of file AP_HAL_Namespace.h.
void AP_HAL::cond_yield | ( | ) |
void AP_HAL::delay | ( | uint32_t | ms | ) |
Definition at line 91 of file system.cpp.
Referenced by Linux::RCInput_SoloLink::_check_hdr(), Linux::CameraSensor_Mt9v117::_init_sensor(), Linux::RCInput_UDP::_timer_tick(), VRBRAIN::DeviceBus::bus_thread(), PX4::DeviceBus::bus_thread(), ChibiOS::DeviceBus::bus_thread(), cond_yield(), Compass::handle_mag_cal_command(), and CompassCalibrator::start().
void AP_HAL::delay_microseconds | ( | uint16_t | us | ) |
Definition at line 95 of file system.cpp.
Referenced by cond_yield().
AP_HAL::FUNCTOR_TYPEDEF | ( | MemberProc | , |
void | |||
) |
const AP_HAL::HAL & AP_HAL::get_HAL | ( | ) |
Definition at line 234 of file HAL_ChibiOS_Class.cpp.
Referenced by HAL_Linux::exit_signal_handler(), loop(), main(), HAL_Empty::run(), HAL_SITL::run(), HAL_VRBRAIN::run(), HAL_PX4::run(), and sdcard_init().
void AP_HAL::init | ( | void | ) |
Generic board initialization function.
This function is called before main(). It ensures that the clocks and peripherals are configured properly for use with wirish, then calls boardInit().
Definition at line 136 of file system.cpp.
Referenced by HALSITL::AnalogIn::AnalogIn(), PX4::PX4_I2C::do_transfer(), VRBRAIN::VRBRAIN_I2C::do_transfer(), Linux::GPIO_Sysfs::from(), Linux::RCOutput_Bebop::from(), F4Light::I2CDevice::get_device(), Linux::CANManager::getNumIfaces(), AP_HAL::GPIO::GPIO(), AP_HAL::HAL::HAL(), PX4::PX4CAN::PX4CAN(), HAL_Linux::run(), and VRBRAIN::VRBRAINCAN::VRBRAINCAN().
uint32_t AP_HAL::micros | ( | ) |
Definition at line 152 of file system.cpp.
Referenced by AP_InertialSensor_PX4::_new_accel_sample(), AP_InertialSensor_PX4::_new_gyro_sample(), VRBRAIN::VRBRAINRCOutput::_send_outputs(), PX4::PX4RCOutput::_send_outputs(), HALSITL::SITL_State::_simulator_servos(), Linux::RCInput_Navio2::_timer_tick(), Linux::SPIUARTDriver::_timer_tick(), PX4::PX4AnalogIn::_timer_tick(), ChibiOS::RCInput::_timer_tick(), VRBRAIN::VRBRAINAnalogIn::_timer_tick(), ChibiOS::AnalogIn::_timer_tick(), AnalogIn_ADS1115::_update(), AP_InertialSensor_Backend::_update_sensor_rate(), ChibiOS::UARTDriver::check_dma_tx_completion(), AP::PerfInfo::check_loop_time(), cond_yield(), AP_SmartRTL::detect_loops(), AP_SmartRTL::detect_simplifications(), ChibiOS::SPIDeviceManager::get_device(), hrt_micros(), AP_Airspeed_MS5525::init(), AP_RPM_Pin::irq_handler(), loop(), AP_Scheduler::loop(), AP_Compass_Backend::publish_filtered_field(), GCS_MAVLINK::queued_param_send(), AP_BattMonitor_Bebop::read(), AP_Compass_LIS3MDL::read(), AP_BattMonitor_Analog::read(), ChibiOS::Scheduler::reboot(), F4Light::UARTDriver::receive_time_constraint_us(), AP_Scheduler::run(), GCS_MAVLINK::send_raw_imu(), SITL::ADSB::send_report(), SITL::Gimbal::send_report(), GCS_MAVLINK::send_servo_output_raw(), setup(), DataFlashTest::setup(), AP_OpticalFlow_Pixart::setup_sensor(), test_one_offset(), AP_Scheduler::time_available_usec(), AP_BattMonitor_SMBus_Maxell::timer(), AP_BattMonitor_SMBus_Solo::timer(), AP_Baro_ICM20789::timer(), AP_Airspeed_MS5525::timer(), AP_OpticalFlow_Pixart::timer(), ChibiOS::UARTDriver::tx_complete(), ChibiOS::UARTDriver::uart_thread(), AP_SBusOut::update(), SITL::Gimbal::update(), SITL::ADSB::update(), AP_Volz_Protocol::update(), GCS_MAVLINK::update(), AP_InertialSensor::update(), F4Light::UARTDriver::update_timestamp(), AP_L1_Control::update_waypoint(), NavEKF3::UpdateFilter(), NavEKF2::UpdateFilter(), AP_InertialSensor::wait_for_sample(), ChibiOS::UARTDriver::write_pending_bytes(), and ChibiOS::UARTDriver::write_pending_bytes_NODMA().
uint64_t AP_HAL::micros64 | ( | ) |
Definition at line 162 of file system.cpp.
Referenced by Linux::RCInput_SoloLink::_check_hdr(), HALSITL::UARTDriver::_check_reconnect(), HALSITL::SITL_State::_fdm_input_local(), AP_InertialSensor_Backend::_notify_new_accel_sensor_rate_sample(), AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(), F4Light::PPM_parser::_process_dsm_pulse(), Linux::RCInput::_process_dsm_pulse(), AP_InertialSensor_LSM9DS0::_read_data_transaction_a(), AP_InertialSensor_LSM9DS0::_read_data_transaction_g(), Linux::PeriodicThread::_run(), PX4::PX4UARTDriver::_timer_tick(), HALSITL::UARTDriver::_timer_tick(), AP_TECS::_update_speed(), VRBRAIN::VRBRAINUARTDriver::_write_fd(), PX4::PX4UARTDriver::_write_fd(), AP_Compass_MMC3416::accumulate_field(), Linux::RCInput::add_dsm_input(), Linux::RCInput::add_srxl_input(), PX4::DeviceBus::adjust_timer(), VRBRAIN::DeviceBus::adjust_timer(), ChibiOS::DeviceBus::adjust_timer(), PX4::DeviceBus::bus_thread(), VRBRAIN::DeviceBus::bus_thread(), ChibiOS::DeviceBus::bus_thread(), SITL::Motor::calculate_forces(), SoaringController::check_cruise_criteria(), SoaringController::check_init_thermal_criteria(), SoaringController::check_thermal_criteria(), cond_yield(), AC_AttitudeControl::control_monitor_log(), GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(), PX4::PX4Scheduler::delay(), VRBRAIN::VRBRAINScheduler::delay(), ChibiOS::Scheduler::delay(), ChibiOS::RCOutput::dshot_send(), dsm_decode(), AP_InertialSensor_SITL::generate_accel(), AP_InertialSensor_SITL::generate_gyro(), SoaringController::get_wind_corrected_drift(), AP_UAVCAN::SystemClock::getMonotonic(), AP_UAVCAN::SystemClock::getUtc(), AP_InertialSensor_SITL::gyro_drift(), AP_Follow::handle_msg(), GCS_MAVLINK::handle_timesync(), F4Light::DSM_parser::init(), SoaringController::init_cruising(), SoaringController::init_thermalling(), NavEKF3::InitialiseFilter(), NavEKF2::InitialiseFilter(), AP_Landing_Deepstall::Log(), AP_InertialSensor_Backend::log_accel_raw(), AP_GPS_SBF::log_ExtEventPVTGeodetic(), DataFlash_Backend::Log_Fill_Format_Units(), AP_InertialSensor_Backend::log_gyro_raw(), AP_GPS_UBLOX::log_mon_hw(), AP_GPS_UBLOX::log_mon_hw2(), AP_GPS_UBLOX::log_rxm_raw(), AP_GPS_UBLOX::log_rxm_rawx(), GCS_MAVLINK::log_vision_position_estimate_data(), DataFlash_Class::Log_Write_AHRS2(), DataFlash_Class::Log_Write_Airspeed(), DataFlash_Class::Log_Write_AOA_SSA(), DataFlash_Class::Log_Write_Attitude(), DataFlash_Class::Log_Write_AttitudeView(), DataFlash_Class::Log_Write_Baro(), DataFlash_Class::Log_Write_Beacon(), DataFlash_Class::Log_Write_CameraInfo(), DataFlash_Class::Log_Write_Compass(), DataFlash_Class::Log_Write_Current(), DataFlash_Class::Log_Write_ESC(), DataFlash_Class::Log_Write_GPS(), DataFlash_Class::Log_Write_IMU(), DataFlash_Class::Log_Write_ISBD(), DataFlash_Class::Log_Write_ISBH(), DataFlash_Backend::Log_Write_MavCmd(), DataFlash_Backend::Log_Write_Message(), DataFlash_Backend::Log_Write_Mode(), DataFlash_Backend::Log_Write_Multiplier(), DataFlash_Class::Log_Write_Origin(), DataFlash_Backend::Log_Write_Parameter(), AP_Tuning::Log_Write_Parameter_Tuning(), AP_Scheduler::Log_Write_Performance(), DataFlash_Class::Log_Write_PID(), DataFlash_Class::Log_Write_POS(), DataFlash_Class::Log_Write_Power(), DataFlash_Class::Log_Write_Proximity(), DataFlash_Class::Log_Write_Radio(), DataFlash_Class::Log_Write_Rally(), DataFlash_Class::Log_Write_Rate(), DataFlash_Class::Log_Write_RCIN(), DataFlash_Class::Log_Write_RCOUT(), DataFlash_Class::Log_Write_RFND(), DataFlash_Class::Log_Write_RPM(), DataFlash_Class::Log_Write_RSSI(), SITL::SITL::Log_Write_SIMSTATE(), DataFlash_Class::Log_Write_SRTL(), DataFlashTest_AllTypes::Log_Write_TypeMessages(), DataFlashTest_AllTypes::Log_Write_TypeMessages_Log_Write(), DataFlash_Backend::Log_Write_Unit(), DataFlash_Class::Log_Write_Vibration(), DataFlash_Class::Log_Write_VisualOdom(), AP_GPS_SBP2::logging_ext_event(), AP_GPS_SBP::logging_log_full_update(), AP_GPS_SBP2::logging_log_full_update(), AP_GPS_SBP::logging_log_raw_sbp(), AP_GPS_SBP2::logging_log_raw_sbp(), loop(), micros(), millis64(), AP_MotorsHeli_RSC::output(), AP_RCProtocol_DSM::process_pulse(), F4Light::UARTDriver::receive_time_constraint_us(), ChibiOS::UARTDriver::receive_timestamp_update(), PX4::DeviceBus::register_periodic_callback(), VRBRAIN::DeviceBus::register_periodic_callback(), ChibiOS::DeviceBus::register_periodic_callback(), HALSITL::Scheduler::Scheduler(), GCS_MAVLINK::send_ekf_origin(), GCS_MAVLINK::send_home(), GCS_MAVLINK::send_vibration(), SITL::Gripper_EPM::should_report(), SITL::Gripper_Servo::should_report(), SITL::Sprayer::should_report(), simulation_timeval(), SITL::Aircraft::smooth_sensors(), srxl_decode(), SoaringController::suppress_throttle(), PX4::Semaphore::take(), VRBRAIN::Semaphore::take(), Linux::Semaphore::take(), ChibiOS::Semaphore::take(), AP_Compass_MMC3416::timer(), ChibiOS::RCOutput::timer_tick(), AP_InertialSensor_SITL::timer_update(), GCS_MAVLINK::timesync_receive_timestamp_ns(), GCS_MAVLINK::timesync_timestamp_ns(), ChibiOS::RCOutput::trigger_groups(), AP_Landing::type_slope_log(), CompassLearn::update(), AP_Baro_ICM20789::update(), AP_RangeFinder_PX4_PWM::update(), SITL::Gripper_Servo::update(), SITL::Sprayer::update(), Variometer::update(), SITL::ICEngine::update(), AP_TECS::update_50hz(), SITL::Gripper_EPM::update_from_demand(), AP_TECS::update_pitch_throttle(), SITL::Aircraft::update_position(), SoaringController::update_thermalling(), SITL::Vicon::update_vicon_position_estimate(), NavEKF3::UpdateFilter(), NavEKF2::UpdateFilter(), HALSITL::SITL_State::wait_clock(), AP_AutoTune::write_log(), and AC_PosControl::write_log().
uint32_t AP_HAL::millis | ( | ) |
Definition at line 157 of file system.cpp.
Referenced by AP_GPS_SBP::_attempt_state_update(), AP_GPS_SBP2::_attempt_state_update(), SITL::Calibration::_calibration_poses(), AP_Baro_BMP085::_cmd_read_pressure(), AP_Baro_BMP085::_cmd_read_temp(), AP_Airspeed_MS4525::_collect(), AP_Baro_Backend::_copy_to_frontend(), AP_Baro_BMP085::_data_ready(), AP_TECS::_detect_underspeed(), HALSITL::SITL_State::_fdm_input_step(), ChibiOS::Storage::_flash_write_data(), AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), AP_GPS_NMEA::_have_new_message(), AP_Airspeed_MS4525::_measure(), PX4::PX4Storage::_mtd_load(), VRBRAIN::VRBRAINStorage::_mtd_load(), AP_GPS_ERB::_parse_gps(), AP_GPS_UBLOX::_parse_gps(), AP_Baro_BMP085::_read_pressure(), AP_GPS_UBLOX::_save_cfg(), AP_GPS_SBP::_sbp_process_message(), AP_GPS_SBP2::_sbp_process_message(), GCS_MAVLINK::_set_mode_common(), AP_GPS_NMEA::_term_complete(), AP_Compass_SITL::_timer(), AP_Baro_SITL::_timer(), AP_Airspeed_MS4525::_timer(), AP_Airspeed_SDP3X::_timer(), VRBRAIN::VRBRAINScheduler::_timer_thread(), PX4::PX4Scheduler::_timer_thread(), Linux::RCInput_SBUS::_timer_tick(), Linux::RCInput_115200::_timer_tick(), PX4::PX4AnalogIn::_timer_tick(), VRBRAIN::VRBRAINAnalogIn::_timer_tick(), ChibiOS::AnalogIn::_timer_tick(), AP_Compass_BMM150::_update(), HALSITL::SITL_State::_update_airspeed(), OpticalFlow_backend::_update_frontend(), HALSITL::SITL_State::_update_gps(), HALSITL::SITL_State::_update_gps_ubx(), AP_InertialSensor_Backend::_update_sensor_rate(), AP_Compass_MMC3416::accumulate_field(), Linux::RCInput::add_dsm_input(), Linux::RCInput::add_sbus_input(), AP_GPS_GSOF::AP_GPS_GSOF(), AP_GPS_SBF::AP_GPS_SBF(), AP_GPS_SBP::AP_GPS_SBP(), AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(), AC_Loiter::calc_desired_velocity(), AP_Airspeed_MS5525::calculate(), AP_Airspeed::calibrate(), AP_Baro::calibrate(), Compass_PerMotor::calibration_update(), AC_Fence::check(), AP_AdvancedFailsafe::check(), AP_AdvancedFailsafe::check_altlimit(), ToneAlarm_PX4::check_cont_tone(), AP_Tuning::check_controller_error(), AP_Frsky_Telem::check_ekf_status(), AP_BattMonitor::check_failsafe(), AP_Avoidance::check_for_threats(), CompassCalibrator::check_for_timeout(), AccelCalibrator::check_for_timeout(), AP_Tuning::check_input(), AP_AutoTune::check_save(), AP_Tuning::check_selector_switch(), AP_Frsky_Telem::check_sensor_status_flags(), cond_yield(), AP_GPS::detect_instance(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::estimate_wind(), AP_Mount_SToRM32::find_gimbal(), SchedTest::five_second_call(), VRBRAIN::VRBRAINRCOutput::force_safety_pending_requests(), PX4::PX4RCOutput::force_safety_pending_requests(), AR_AttitudeControl::get_desired_lat_accel(), AR_AttitudeControl::get_desired_turn_rate(), AP_Airspeed_MS4525::get_differential_pressure(), AP_Airspeed_SDP3X::get_differential_pressure(), AP_Airspeed_MS5525::get_differential_pressure(), AP_Baro::get_external_temperature(), AC_PrecLand_SITL::get_los_body(), AP_Follow::get_offsets_ned(), PID::get_pid(), AP_RangeFinder_VL53L0X::get_reading(), AP_RangeFinder_Wasp::get_reading(), AP_RangeFinder_LeddarOne::get_reading(), AP_Proximity_RPLidarA2::get_readings(), AP_YawController::get_servo_out(), AR_AttitudeControl::get_steering_out_lat_accel(), AP_SteerController::get_steering_out_rate(), AR_AttitudeControl::get_steering_out_rate(), F4Light::Util::get_system_clock_ms(), AP_Follow::get_target_heading(), AP_Follow::get_target_location_and_velocity(), AP_Airspeed_MS4525::get_temperature(), AP_Airspeed_SDP3X::get_temperature(), AP_Airspeed_MS5525::get_temperature(), AP_BattMonitor::get_temperature(), AR_AttitudeControl::get_throttle_out_speed(), AR_AttitudeControl::get_throttle_out_stop(), AP_AHRS::get_time_flying_ms(), AP_Proximity_MAV::get_upward_distance(), AP_Proximity_RangeFinder::get_upward_distance(), AP_Beacon::get_vehicle_position_ned(), SoloGimbalEKF::getStatus(), HALSITL::SITL_State::gps2_pipe(), HALSITL::SITL_State::gps_pipe(), AP_Gripper_Servo::grab(), AP_Gripper_EPM::grab(), DataFlash_MAVLink::handle_ack(), AP_Avoidance::handle_avoidance_local(), RGBLed::handle_led_control(), DataFlash_Class::handle_log_send_data(), DataFlash_Class::handle_log_send_listing(), GCS_MAVLINK::handle_mission_count(), GCS_MAVLINK::handle_mission_item(), GCS_MAVLINK::handle_mission_write_partial_list(), AP_RangeFinder_MAVLink::handle_msg(), AP_Proximity_MAV::handle_msg(), AP_GPS_MAV::handle_msg(), AC_PrecLand_Companion::handle_msg(), AP_Follow::handle_msg(), AP_Avoidance::handle_msg(), GCS_MAVLINK::handle_param_request_read(), GCS_MAVLINK::handle_radio_status(), DataFlash_MAVLink::handle_retry(), AP_Avoidance::handle_threat_gcs_notify(), AP_ADSB::handle_transceiver_report(), AP_ADSB::handle_vehicle(), AP_Gripper_Servo::has_state_pwm(), AC_PrecLand_SITL::have_los_meas(), AP_Beacon_SITL::healthy(), AP_Beacon_Pozyx::healthy(), AP_Beacon_Marvelmind::healthy(), AP_VisualOdom::healthy(), AP_AHRS_DCM::healthy(), F4Light::DSM_parser::init(), AP_Compass_BMM150::init(), AP_Mission::init(), AP_Proximity_LightWareSF40C::initialise(), AP_AHRS_NavEKF::initialised(), AP_GPS_NOVA::inject_data(), AP_GPS_SBP2::inject_data(), AP_GPS_SBP::inject_data(), AP_Arming::ins_checks(), AP_WheelEncoder_Quadrature::irq_handler(), AC_PosControl::is_active_xy(), AC_PosControl::is_active_z(), AP_TempCalibration::learn_calibration(), AP_Proximity_SITL::load_fence(), DataFlash_MAVLink::Log_Write_DF_MAV(), DataFlash_Class::Log_Write_POS(), loop(), AC_Fence::manual_recovery_start(), SITL::Vicon::maybe_send_heartbeat(), OSDns::millis(), F4Light::Scheduler::millis(), millis_plus(), CompassCalibrator::new_sample(), AccelCalibrator::new_sample(), PX4::PX4AnalogIn::next_stop_pin(), VRBRAIN::VRBRAINAnalogIn::next_stop_pin(), AP_AHRS_DCM::normalize(), SchedTest::one_hz_print(), TCPServerDevice::open(), AP_Landing_Deepstall::override_servos(), GCS_MAVLINK::packet_overhead_chan(), AP_GPS_SBF::parse(), AP_Beacon_Pozyx::parse_buffer(), AP_Proximity_RPLidarA2::parse_response_data(), AP_Proximity_RPLidarA2::parse_response_descriptor(), DataFlash_Backend::periodic_tasks(), Linux::ToneAlarm_Disco::play(), Linux::ToneAlarm::play(), ToneAlarm_PX4::play_tone(), AP_Beacon_Marvelmind::process_beacons_distances_datagram(), AP_GPS_GSOF::process_message(), AP_GPS_NOVA::process_message(), AP_GPS_SBF::process_message(), AP_RCProtocol::process_pulse(), AP_Proximity_LightWareSF40C::process_reply(), AP_Compass_Backend::publish_filtered_field(), AP_Compass_Backend::publish_raw_field(), AP_InertialSensor::BatchSampler::push_data_to_log(), GCS_MAVLINK::queued_param_send(), AP_GPS_NOVA::read(), AP_GPS_GSOF::read(), AP_GPS_MTK19::read(), AP_GPS_SBF::read(), Compass::read(), AP_GPS_UBLOX::read(), AP_Airspeed::read(), AP_IRLock_I2C::read_block(), AP_IRLock_I2C::read_frames(), AP_BattMonitor_SMBus::read_temp(), NavEKF2_core::readIMUData(), F4Light::AnalogSource::reading_settled(), SITL::XPlane::receive_data(), AC_Fence::record_breach(), AP_Gripper_Servo::release(), AP_Gripper_EPM::release(), AP_Parachute::release(), AP_Proximity_LightWareSF40C::request_new_data(), AP_SmartRTL::request_thorough_cleanup(), AP_AHRS_DCM::reset(), AP_Proximity_RPLidarA2::reset_rplidar(), HAL_F4Light::run(), AC_PrecLand::run_estimator(), MissionTest::run_resume_test(), MissionTest::run_set_current_cmd_while_stopped_test(), SoloGimbalEKF::RunEKF(), ChibiOS::RCOutput::safety_update(), GCS_MAVLINK::save_signing_timestamp(), AP_ADSB::send_adsb_vehicle(), GCS_MAVLINK::send_attitude(), AP_Frsky_Telem::send_D(), GCS_MAVLINK::send_distance_sensor(), AP_Mount_SToRM32::send_do_mount_control(), GCS_MAVLINK::send_global_position_int(), GCS_MAVLINK::send_local_position(), DataFlash_MAVLink::send_log_block(), AP_GPS::send_mavlink_gps_raw(), GCS_MAVLINK::send_named_float(), GCS_MAVLINK::send_proximity(), GCS_MAVLINK::send_radio_in(), GCS_MAVLINK::send_raw_imu(), AP_Button::send_report(), SITL::ADSB::send_report(), SITL::Gimbal::send_report(), AP_Proximity_LightWareSF40C::send_request_for_distance(), AP_Proximity_LightWareSF40C::send_request_for_health(), AP_Proximity_RPLidarA2::send_request_for_health(), GCS_MAVLINK::send_scaled_pressure(), GCS_MAVLINK::send_scaled_pressure3(), AP_Frsky_Telem::send_SPort_Passthrough(), GCS_MAVLINK::send_system_time(), AP_Mount_SToRM32_serial::send_target_angles(), AP_Notify::send_text(), AP_InertialSensor::set_accel_peak_hold(), AP_Beacon_Backend::set_beacon_distance(), AP_VisualOdom_Backend::set_deltas(), AP_LeakDetector::set_detect(), AP_Baro::set_external_temperature(), AP_Stats::set_flying(), AP_Proximity_LightWareSF40C::set_forward_direction(), AP_SmartRTL::set_home(), Linux::HeatPwm::set_imu_temp(), ChibiOS::Util::set_imu_temp(), PX4::PX4Util::set_imu_temp(), VRBRAIN::VRBRAINUtil::set_imu_temp(), AP_AHRS::set_likely_flying(), AP_Proximity_LightWareSF40C::set_motor_direction(), AP_Proximity_LightWareSF40C::set_motor_speed(), SoloGimbal_Parameters::set_param(), AP_Rally::set_rally_point_with_index(), AP_Proximity_RPLidarA2::set_scan_mode(), AC_WPNav::set_spline_destination(), AC_WPNav::set_spline_origin_and_destination(), AP_Beacon_Marvelmind::set_stationary_beacons_positions(), CompassCalibrator::set_status(), AccelCalibrator::set_status(), AP_Beacon_Backend::set_vehicle_position(), AC_WPNav::set_wp_destination(), AP_Airspeed::setHIL(), AP_GPS::setHIL(), NavEKF3_core::setup_core(), F4Light::AnalogSource::setup_read(), AP_InertialSensor::simple_accel_cal(), AR_AttitudeControl::speed_control_active(), CompassCalibrator::start(), AP_AutoTune::start(), AP_RangeFinder_VL53L0X::start_continuous(), DataFlash_MAVLink::stop_logging(), AP_IRLock_I2C::sync_frame_start(), AC_PrecLand::target_acquired(), GCS_MAVLINK::telemetry_delayed(), AP_Baro_SITL::temperature_adjustment(), AP_Landing_Deepstall::terminate(), test_uart(), AP_DEVO_Telem::tick(), AP_GPS::time_epoch_usec(), time_since(), AC_PosControl::time_since_last_xy_update(), AP_Compass_MMC3416::timer(), AP_OpticalFlow_Pixart::timer(), VRBRAIN::VRBRAINUARTDriver::try_initialise(), PX4::PX4UARTDriver::try_initialise(), GCS_MAVLINK::try_send_message(), AP_Landing::type_slope_verify_land(), AP_Proximity_MAV::update(), AP_OpticalFlow_Pixart::update(), AP_Proximity_RangeFinder::update(), AP_IRLock_I2C::update(), AP_OpticalFlow_SITL::update(), AP_RangeFinder_Wasp::update(), AP_RangeFinder_uLanding::update(), AP_RangeFinder_MaxsonarSerialLV::update(), AP_Proximity_TeraRangerTower::update(), AP_RangeFinder_LightWareSerial::update(), AP_Proximity_LightWareSF40C::update(), AP_RangeFinder_MAVLink::update(), AP_Beacon_SITL::update(), AC_PrecLand_Companion::update(), AC_PrecLand_SITL::update(), AC_PrecLand_SITL_Gazebo::update(), AP_AccelCal::update(), AP_RangeFinder_Benewake::update(), AP_Stats::update(), AP_RCProtocol_DSM::update(), AC_PrecLand_IRLock::update(), AP_OpticalFlow_Onboard::update(), AP_Mount_SToRM32_serial::update(), AP_RPM_Pin::update(), AP_RPM_SITL::update(), AP_Winch_Servo::update(), AP_Mount_SToRM32::update(), AP_ICEngine::update(), AP_RPM_PX4_PWM::update(), AP_RangeFinder_PX4_PWM::update(), AP_Button::update(), AP_RangeFinder_NMEA::update(), SITL::XPlane::update(), AP_Mount_Servo::update(), Buzzer::update(), AP_LeakDetector::update(), AP_AutoTune::update(), AP_Proximity_RPLidarA2::update(), OpticalFlow::update(), AP_ADSB::update(), AP_RangeFinder_LeddarOne::update(), SoloGimbal_Parameters::update(), AP_SmartRTL::update(), AC_Sprayer::update(), AP_Parachute::update(), AP_Camera::update(), AP_AHRS_DCM::update(), GCS_MAVLINK::update(), AP_GPS::update(), AP_InertialSensor::update(), AP_AHRS::update_AOA_SSA(), AP_Baro::update_calibration(), AP_Airspeed::update_calibration(), SITL::Aircraft::update_dynamics(), AP_AHRS_NavEKF::update_EKF2(), AP_AHRS_NavEKF::update_EKF3(), AP_ServoRelayEvents::update_events(), AP_Stats::update_flighttime(), AP_Gripper_EPM::update_gripper(), AP_Baro_Backend::update_healthy_flag(), AP_GPS::update_instance(), RGBLed::update_override(), AP_BattMonitor_Backend::update_resistance_estimate(), AP_Stats::update_runtime(), AP_Proximity_TeraRangerTower::update_sector_data(), AP_AHRS_NavEKF::update_SITL(), AC_WPNav::update_spline(), AP_Landing_Deepstall::update_steering(), Display::update_text(), AP_Avoidance::update_threat_level(), AC_PosControl::update_vel_controller_xy(), AC_WPNav::update_wpnav(), AC_PosControl::update_xy_controller(), AC_PosControl::update_z_controller(), AP_AHRS_DCM::uptime_ms(), AP_AHRS_DCM::use_compass(), AP_AHRS_DCM::use_fast_gains(), AP_Landing_Deepstall::verify_land(), and AP_Mission::write_cmd_to_storage().
uint64_t AP_HAL::millis64 | ( | ) |
Definition at line 167 of file system.cpp.
Referenced by Linux::Perf::_debug_counters(), Linux::Scheduler::_debug_stack(), SITL::Plane::calculate_forces(), cond_yield(), Linux::Scheduler::delay(), millis(), AP_Button::timer_update(), and AP_Button::update().
|
inline |
|
inline |
|
inline |
|
inline |
void AP_HAL::panic | ( | const char * | errormsg, |
... | |||
) |
Definition at line 140 of file system.cpp.
Referenced by RangeFinder::_add_backend(), AP_Baro::_add_backend(), Compass::_add_backend(), AP_InertialSensor::_add_backend(), AP_InertialSensor_BMI160::_check_err_reg(), AP_ADC_ADS1115::_convert_register_data_to_mv(), ChibiOS::Storage::_flash_load(), Linux::PWM_Sysfs::_generate_duty_path(), Linux::PWM_Sysfs_Bebop::_generate_duty_path(), Linux::PWM_Sysfs::_generate_enable_path(), Linux::PWM_Sysfs_Bebop::_generate_enable_path(), Linux::PWM_Sysfs::_generate_export_path(), Linux::PWM_Sysfs::_generate_period_path(), Linux::PWM_Sysfs_Bebop::_generate_period_path(), Linux::PWM_Sysfs::_generate_polarity_path(), F4Light::SPIDeviceManager::_get_device(), AP_InertialSensor_LSM9DS0::_gyro_disable_i2c(), AP_Compass_LSM303D::_hardware_init(), AP_Compass_MAG3110::_hardware_init(), AP_Baro_BMP085::_init(), AP_Baro_MS56XX::_init(), AP_Baro_KellerLD::_init(), AP_InertialSensor_L3G4200D::_init_sensor(), AP_InertialSensor_PX4::_init_sensor(), AP_InertialSensor_LSM9DS1::_init_sensor(), AP_InertialSensor_LSM9DS0::_init_sensor(), Linux::CameraSensor_Mt9v117::_init_sensor(), PX4::PX4Storage::_mtd_load(), VRBRAIN::VRBRAINStorage::_mtd_load(), HALSITL::SITL_State::_parse_command_line(), Linux::UARTDriver::_parseDevicePath(), F4Light::AnalogIn::_register_channel(), Linux::OpticalFlow_Onboard::_run_optflow(), Linux::RCOutput_Bebop::_run_rcout(), AP_InertialSensor::_start_backends(), F4Light::Scheduler::_start_task(), HALSITL::UARTDriver::_uart_start_connection(), AP_AHRS_View::AP_AHRS_View(), AP_Airspeed::AP_Airspeed(), AP_BattMonitor::AP_BattMonitor(), AP_GPS::AP_GPS(), AP_InertialSensor::AP_InertialSensor(), AP_Notify::AP_Notify(), AP_Proximity::AP_Proximity(), AP_Proximity_SITL::AP_Proximity_SITL(), AP_RSSI::AP_RSSI(), Linux::SPIUARTDriver::begin(), ChibiOS::DeviceBus::bouncebuffer_setup_rx(), ChibiOS::DeviceBus::bouncebuffer_setup_tx(), AP_Baro::calibrate(), Linux::CameraSensor_Mt9v117::CameraSensor_Mt9v117(), catch_sigbus(), Compass::Compass(), AP_Param::count_embedded_param_defaults(), SITL::JSBSim::create_templates(), DataFlash_Class::DataFlash_Class(), F4Light::Storage::error_parse(), FlashTest::flash_erase(), FlashTest::flash_read(), FlashTest::flash_write(), SITL::FlightAxis::FlightAxis(), GCS::GCS(), Linux::I2CDeviceManager::get_device(), Linux::VideoIn::get_frame(), GCS_MAVLINK::handle_serial_control(), AP_Baro_ICM20789::imu_spi_init(), Linux::RCInput_Navio2::init(), PX4::PX4RCOutput::init(), VRBRAIN::VRBRAINRCOutput::init(), Linux::RCInput_ZYNQ::init(), VRBRAIN::VRBRAINRCInput::init(), TSYS01::init(), PX4::PX4RCInput::init(), Linux::RCInput_PRU::init(), Linux::RCInput_UART::init(), Linux::RCOutput_Sysfs::init(), Linux::PWM_Sysfs_Base::init(), Linux::Storage::init(), VRBRAIN::VRBRAINGPIO::init(), AP_Baro_ICM20789::init(), Linux::Scheduler::init(), Linux::Led_Sysfs::init(), Linux::RCOutput_AeroIO::init(), Linux::RCInput_115200::init(), Linux::RCInput_AioPRU::init(), Linux::RCInput_SoloLink::init(), DataFlash_MAVLink::Init(), PX4::PX4GPIO::init(), Linux::OpticalFlow_Onboard::init(), Linux::GPIO_RPI::init(), PX4::PX4AnalogIn::init(), VRBRAIN::VRBRAINAnalogIn::init(), DataFlash_Class::Init(), Linux::GPIO_BBB::init(), F4Light::Scheduler::init(), DataFlash_Class::internal_error(), AP_Param::load_embedded_param_defaults(), DataFlash_Class::Log_Write_calc_msg_len(), Linux::SPIBus::open(), Linux::RCInput_Navio2::open_channel(), AP_Param::parse_param_line(), Linux::Perf::Perf(), AP_BoardConfig::px4_setup_pwm(), RangeFinder::RangeFinder(), Linux::RCInput_Multi::RCInput_Multi(), Linux::RCInput_UART::RCInput_UART(), read_calibration_data(), AP_InertialSensor::register_accel(), Compass::register_compass(), AP_InertialSensor::register_gyro(), Linux::SPIDevice::register_periodic_callback(), Linux::I2CDevice::register_periodic_callback(), AP_Baro::register_sensor(), HAL_SITL::run(), HALSITL::Scheduler::Scheduler(), AnalogSource_Navio2::set_channel(), FlashTest::setup(), setup(), AP_OpticalFlow_Pixart::setup_sensor(), HALSITL::SITL_State::sim_fd(), SITL::SITL::SITL(), Linux::SPIDevice::SPIDevice(), F4Light::SPIDevice::SPIDevice(), AP_InertialSensor_BMI160::start(), Linux::Thread::start(), AP_InertialSensor_Invensense::start(), SITL::JSBSim::start_JSBSim(), Linux::Scheduler::system_initialized(), VRBRAIN::VRBRAINScheduler::system_initialized(), PX4::PX4Scheduler::system_initialized(), ChibiOS::Scheduler::system_initialized(), F4Light::Scheduler::system_initialized(), Linux::RCInput_RPI::termination_handler(), GCS_MAVLINK::try_send_message(), and SITL::Vicon::Vicon().
void AP_HAL::yield | ( | uint32_t | us | ) |
Definition at line 99 of file system.cpp.
Referenced by cond_yield(), HAL_F4Light::connect_uart(), and F4Light::Scheduler::task_resume().
struct timeval AP_HAL::start_time |
Definition at line 16 of file system.cpp.
Referenced by MissionTest::run_resume_test(), MissionTest::run_set_current_cmd_while_stopped_test(), and setup().
struct { ... } AP_HAL::state |
struct { ... } AP_HAL::state |