Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
Core autopilot interface common to all firmwares. More...
#include "autopilot.h"
#include "generated/modules.h"
#include "mcu_periph/uart.h"
#include "mcu_periph/sys_time.h"
#include "mcu_periph/gpio.h"
#include "modules/core/commands.h"
#include "modules/datalink/telemetry.h"
#include "modules/core/abi.h"
#include "modules/checks/preflight_checks.h"
#include "modules/core/settings.h"
#include "generated/settings.h"
#include "pprz_version.h"
Go to the source code of this file.
Macros | |
#define | AUTOPILOT_RC_ID ABI_BROADCAST |
Functions | |
static void | rc_cb (uint8_t sender_id, struct RadioControl *rc) |
static void | send_autopilot_version (struct transport_tx *trans, struct link_device *dev) |
static void | send_alive (struct transport_tx *trans, struct link_device *dev) |
static void | send_attitude (struct transport_tx *trans, struct link_device *dev) |
static void | send_dl_value (struct transport_tx *trans, struct link_device *dev) |
static void | send_minimal_com (struct transport_tx *trans, struct link_device *dev) |
void | autopilot_init (void) |
Autopilot initialization function. More... | |
void | autopilot_periodic (void) |
AP periodic call. More... | |
void WEAK | autopilot_event (void) |
AP event call. More... | |
void | autopilot_on_rc_frame (void) |
RC frame handler. More... | |
void WEAK | autopilot_failsafe_checks (void) |
Failsafe checks. More... | |
bool | autopilot_set_mode (uint8_t new_autopilot_mode) |
set autopilot mode More... | |
void | autopilot_SetModeHandler (float mode) |
AP mode setting handler. More... | |
uint8_t | autopilot_get_mode (void) |
get autopilot mode More... | |
void | autopilot_reset_flight_time (void) |
reset flight time and launch More... | |
void | autopilot_force_motors_on (bool motors_on) |
Force the motors on/off skipping preflight checks. More... | |
bool | autopilot_set_motors_on (bool motors_on) |
turn motors on/off, eventually depending of the current mode set kill_throttle accordingly FIXME is it true for FW firmware ? More... | |
bool | autopilot_arming_motors_on (bool motors_on) |
turn motors on/off during arming, not done automatically prevents takeoff with preflight checks More... | |
bool | autopilot_get_motors_on (void) |
get motors status More... | |
void | autopilot_set_kill_throttle (bool kill) |
set kill throttle More... | |
bool | autopilot_throttle_killed (void) |
get kill status More... | |
void WEAK | autopilot_check_in_flight (bool motors_on) |
in flight check utility function actual implementation is firmware dependent More... | |
void WEAK | autopilot_reset_in_flight_counter (void) |
reset in_flight counter actual implementation is firmware dependent More... | |
void | autopilot_set_in_flight (bool in_flight) |
set in_flight flag More... | |
bool | autopilot_in_flight (void) |
get in_flight flag More... | |
void | autopilot_store_settings (void) |
store settings More... | |
void | autopilot_clear_settings (void) |
clear settings More... | |
void | autopilot_send_version (void) |
send autopilot version More... | |
void WEAK | autopilot_send_mode (void) |
send autopilot mode actual implementation is firmware dependent More... | |
Variables | |
struct pprz_autopilot | autopilot |
Global autopilot structure. More... | |
static abi_event | rc_ev |
Core autopilot interface common to all firmwares.
Using either static or generated autopilot logic, which depends on the firmware.
Definition in file autopilot.c.
#define AUTOPILOT_RC_ID ABI_BROADCAST |
Definition at line 52 of file autopilot.c.
bool autopilot_arming_motors_on | ( | bool | motors_on | ) |
turn motors on/off during arming, not done automatically prevents takeoff with preflight checks
Start or stop the motors during arming May not happen when preflight checks are failing.
Definition at line 273 of file autopilot.c.
References autopilot, pprz_autopilot::motors_on, preflight_bypass, and preflight_check().
Referenced by autopilot_arming_check_motors_on().
void WEAK autopilot_check_in_flight | ( | bool | motors_on | ) |
in flight check utility function actual implementation is firmware dependent
Check if airframe is in flight.
Definition at line 321 of file autopilot.c.
Referenced by autopilot_periodic().
void autopilot_clear_settings | ( | void | ) |
clear settings
Clear marked settings in flash try to make sure that we don't write to flash while flying Also provide macro for dl_setting backward compatibility.
Definition at line 357 of file autopilot.c.
References autopilot, pprz_autopilot::kill_throttle, settings_clear(), and settings_clear_flag.
void WEAK autopilot_event | ( | void | ) |
void WEAK autopilot_failsafe_checks | ( | void | ) |
Failsafe checks.
Autopilot periodic failsafe checks.
Definition at line 189 of file autopilot.c.
Referenced by autopilot_periodic(), and main_ap_init().
void autopilot_force_motors_on | ( | bool | motors_on | ) |
Force the motors on/off skipping preflight checks.
Force start/stop the motors WARNING This will skip he preflight checks.
Definition at line 237 of file autopilot.c.
References autopilot, autopilot_generated_set_motors_on(), autopilot_static_set_motors_on(), pprz_autopilot::kill_throttle, and pprz_autopilot::motors_on.
Referenced by autopilot_set_motors_on().
uint8_t autopilot_get_mode | ( | void | ) |
get autopilot mode
Get autopilot mode.
Definition at line 222 of file autopilot.c.
References autopilot, and pprz_autopilot::mode.
Referenced by attitude_loop(), autopilot_arming_check_motors_on(), autopilot_arming_check_valid(), autopilot_arming_set(), autopilot_failsafe_checks(), autopilot_static_on_rc_frame(), cam_periodic(), collective_tracking_control(), distributed_circular(), generic_com_periodic(), guidance_flip_enter(), gvf_low_level_control_2D(), gvf_parametric_low_level_control_2D(), gvf_parametric_low_level_control_3D(), h_ctl_pitch_loop(), h_ctl_roll_loop(), mavlink_common_message_handler(), mavlink_send_heartbeat(), navigation_task(), NavKillThrottle(), NavResurrect(), periodic_auto1_commands(), pprz_mode_update(), send_fbw_status(), send_mode(), v_ctl_set_pitch(), v_ctl_set_throttle(), and vPoint().
bool autopilot_get_motors_on | ( | void | ) |
get motors status
Get motor status.
Definition at line 295 of file autopilot.c.
References autopilot, and pprz_autopilot::motors_on.
Referenced by actuators_ardrone_motor_status(), actuators_bebop_commit(), actuators_esc32_commit(), autopilot_arming_check_motors_on(), autopilot_failsafe_checks(), autopilot_periodic(), get_act_state_oneloop(), hott_check_serial_data(), hott_update_eam_msg(), hott_update_gam_msg(), intermcu_send_commands(), mavlink_common_message_handler(), nav_takeoff_run(), nps_autopilot_run_step(), sdlogger_spi_direct_periodic(), stabilization_attitude_run(), and throttle_curve_run().
bool autopilot_in_flight | ( | void | ) |
get in_flight flag
Get in flight status.
Definition at line 340 of file autopilot.c.
References autopilot, and pprz_autopilot::in_flight.
Referenced by autopilot_generated_periodic(), autopilot_periodic(), autopilot_static_periodic(), e_identification_fr_periodic(), ekf_aw_wrapper_periodic(), guidance_flip_run(), guidance_h_run(), guidance_module_enter(), ins_ekf2_update(), ins_flow_update(), mav_exercise_periodic(), mavlink_send_extended_sys_state(), nav_is_in_flight(), orange_avoider_periodic(), and rc_cb().
void autopilot_init | ( | void | ) |
Autopilot initialization function.
Definition at line 107 of file autopilot.c.
References autopilot, autopilot_firmware_init(), autopilot_generated_init(), AUTOPILOT_RC_ID, autopilot_static_init(), DefaultPeriodic, pprz_autopilot::detect_ground_once, pprz_autopilot::flight_time, pprz_autopilot::ground_detected, pprz_autopilot::in_flight, pprz_autopilot::kill_throttle, pprz_autopilot::mode_auto2, MODE_AUTO2, pprz_autopilot::motors_on, rc_cb(), rc_ev, register_periodic_telemetry(), send_alive(), send_attitude(), send_autopilot_version(), send_dl_value(), send_minimal_com(), pprz_autopilot::throttle, and pprz_autopilot::use_rc.
void autopilot_on_rc_frame | ( | void | ) |
RC frame handler.
Autopilot RC input event hadler.
Definition at line 178 of file autopilot.c.
References autopilot_generated_on_rc_frame(), and autopilot_static_on_rc_frame().
Referenced by rc_cb().
void autopilot_periodic | ( | void | ) |
AP periodic call.
Autopilot periodic call at PERIODIC_FREQUENCY.
Definition at line 146 of file autopilot.c.
References autopilot, autopilot_check_in_flight(), autopilot_failsafe_checks(), autopilot_generated_periodic(), autopilot_get_motors_on(), autopilot_in_flight(), autopilot_static_periodic(), and pprz_autopilot::flight_time.
void autopilot_reset_flight_time | ( | void | ) |
reset flight time and launch
Reset flight time and launch status Also provide macro for dl_setting backward compatibility.
Definition at line 229 of file autopilot.c.
References autopilot, pprz_autopilot::flight_time, and pprz_autopilot::launch.
void WEAK autopilot_reset_in_flight_counter | ( | void | ) |
reset in_flight counter actual implementation is firmware dependent
Definition at line 326 of file autopilot.c.
Referenced by autopilot_set_in_flight().
void WEAK autopilot_send_mode | ( | void | ) |
send autopilot mode actual implementation is firmware dependent
Report autopilot mode on default downlink channel.
Definition at line 375 of file autopilot.c.
Referenced by autopilot_set_mode().
void autopilot_send_version | ( | void | ) |
send autopilot version
Report autopilot version on default downlink channel.
Definition at line 367 of file autopilot.c.
References DefaultChannel, DefaultDevice, and send_autopilot_version().
Referenced by telemetry_reporting_task().
void autopilot_set_in_flight | ( | bool | in_flight | ) |
set in_flight flag
Set in flight status.
Definition at line 330 of file autopilot.c.
References autopilot, autopilot_reset_in_flight_counter(), and pprz_autopilot::in_flight.
Referenced by autopilot_arming_check_motors_on(), autopilot_static_set_mode(), and nav_takeoff_run().
void autopilot_set_kill_throttle | ( | bool | kill | ) |
set kill throttle
Enable or disable motor control from autopilot Also provide macro for dl_setting backward compatibility.
Definition at line 302 of file autopilot.c.
References autopilot_set_motors_on().
Referenced by actuators_disco_commit(), autopilot_failsafe_checks(), nav_bungee_takeoff_run(), nav_bungee_takeoff_setup(), and nav_skid_landing_run().
bool autopilot_set_mode | ( | uint8_t | new_autopilot_mode | ) |
set autopilot mode
Set new autopilot mode.
Definition at line 193 of file autopilot.c.
References autopilot, autopilot_generated_set_mode(), autopilot_send_mode(), autopilot_static_set_mode(), pprz_autopilot::mode, and mode.
Referenced by autopilot_failsafe_checks(), guidance_flip_run(), guidance_module_run(), mavlink_common_message_handler(), nav_set_failsafe(), and pprz_mode_update().
bool autopilot_set_motors_on | ( | bool | motors_on | ) |
turn motors on/off, eventually depending of the current mode set kill_throttle accordingly FIXME is it true for FW firmware ?
Start or stop motors May have no effect if motors has auto-start based on throttle setpoint or when the preflight checks are failing.
Definition at line 250 of file autopilot.c.
References autopilot, autopilot_force_motors_on(), pprz_autopilot::motors_on, preflight_bypass, and preflight_check().
Referenced by actuators_ardrone_motor_status(), actuators_bebop_commit(), autopilot_set_kill_throttle(), autopilot_static_set_mode(), ground_detect_periodic(), mavlink_common_message_handler(), nav_takeoff_run(), NavKillThrottle(), and NavResurrect().
void autopilot_SetModeHandler | ( | float | mode | ) |
AP mode setting handler.
Handler for setter function with dl_setting.
Definition at line 211 of file autopilot.c.
References autopilot_generated_SetModeHandler(), autopilot_static_SetModeHandler(), and mode.
void autopilot_store_settings | ( | void | ) |
store settings
Store marked settings in flash Try to make sure that we don't write to flash while flying Also provide macro for dl_setting backward compatibility.
Definition at line 347 of file autopilot.c.
References autopilot, pprz_autopilot::kill_throttle, settings_store(), and settings_store_flag.
bool autopilot_throttle_killed | ( | void | ) |
get kill status
Get kill status.
Definition at line 313 of file autopilot.c.
References autopilot, and pprz_autopilot::kill_throttle.
Referenced by electrical_periodic(), geo_mag_periodic(), mavlink_send_heartbeat(), nav_skid_landing_run(), v_ctl_climb_loop(), and v_ctl_landing_loop().
|
static |
Definition at line 57 of file autopilot.c.
References autopilot_on_rc_frame().
Referenced by autopilot_init().
|
static |
Definition at line 71 of file autopilot.c.
References dev.
Referenced by autopilot_init().
|
static |
Definition at line 76 of file autopilot.c.
References dev, FloatEulers::phi, FloatEulers::psi, stateGetNedToBodyEulers_f(), and FloatEulers::theta.
Referenced by autopilot_init().
|
static |
Definition at line 64 of file autopilot.c.
References dev.
Referenced by autopilot_init(), and autopilot_send_version().
|
static |
Definition at line 82 of file autopilot.c.
References dev.
Referenced by autopilot_init().
|
static |
Definition at line 87 of file autopilot.c.
References UtmCoor_f::alt, autopilot, course, dev, electrical, GpsState::fix, pprz_autopilot::flight_time, gps, MAX_PPRZ, pprz_autopilot::mode, nav_block, stateGetHorizontalSpeedDir_f(), stateGetHorizontalSpeedNorm_f(), stateGetPositionLla_f(), stateGetPositionUtm_f(), stateGetSpeedEnu_f(), pprz_autopilot::throttle, Electrical::vsupply, and EnuCoor_f::z.
Referenced by autopilot_init().
struct pprz_autopilot autopilot |
Global autopilot structure.
Definition at line 1 of file autopilot.c.
Referenced by attitude_loop(), autopilot_arming_check_motors_on(), autopilot_arming_check_valid(), autopilot_arming_motors_on(), autopilot_check_in_flight(), autopilot_clear_settings(), autopilot_event(), autopilot_failsafe_checks(), autopilot_force_motors_on(), autopilot_generated_init(), autopilot_generated_on_rc_frame(), autopilot_generated_periodic(), autopilot_generated_set_mode(), autopilot_generated_set_motors_on(), autopilot_get_mode(), autopilot_get_motors_on(), autopilot_in_flight(), autopilot_init(), autopilot_periodic(), autopilot_reset_flight_time(), autopilot_set_in_flight(), autopilot_set_mode(), autopilot_set_motors_on(), autopilot_static_init(), autopilot_static_on_rc_frame(), autopilot_static_periodic(), autopilot_static_set_mode(), autopilot_static_set_motors_on(), autopilot_store_settings(), autopilot_throttle_killed(), calc_flight_time_left(), check_parachute_arming(), check_parachute_trigger(), draw_osd(), Drift_correction(), e_identification_fr_periodic(), eff_scheduling_rotwing_update_hover_motor_effectiveness(), gazebo_write(), generic_com_periodic(), gsm_send_report_continue(), h_ctl_course_loop(), h_ctl_pitch_loop(), h_ctl_roll_loop(), main_recovery_init(), mf_daq_send_state(), monitor_task(), nav_bungee_takeoff_run(), nav_catapult_highrate_module(), nav_check_wp_time(), nav_detect_ground(), nav_home(), nav_takeoff_run(), nps_autopilot_run_step(), oneloop_andi_run(), parse_mf_daq_msg(), send_energy(), send_fp(), send_minimal_com(), send_mode(), send_status(), uav_recovery_periodic(), v_ctl_climb_loop(), v_ctl_guidance_loop(), v_ctl_set_pitch(), and v_ctl_set_throttle().
|
static |
Definition at line 55 of file autopilot.c.
Referenced by autopilot_init().