Paparazzi UAS
v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
|
#include "autopilot.h"
#include "generated/modules.h"
#include "mcu_periph/uart.h"
#include "mcu_periph/sys_time.h"
#include "mcu_periph/gpio.h"
#include "subsystems/radio_control.h"
#include "subsystems/commands.h"
#include "subsystems/actuators.h"
#include "subsystems/datalink/telemetry.h"
#include "subsystems/settings.h"
#include "generated/settings.h"
#include "pprz_version.h"
Go to the source code of this file.
Functions | |
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_rc (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... | |
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_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_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_set_power_switch (bool power_switch) |
set power switch 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... | |
Core autopilot interface common to all firmwares. Using either static or generated autopilot logic, which depends on the firmware.
Definition in file autopilot.c.
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 238 of file autopilot.c.
Referenced by failsafe_check().
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 288 of file autopilot.c.
References autopilot, pprz_autopilot::kill_throttle, settings_clear(), and settings_clear_flag.
void WEAK autopilot_event | ( | void | ) |
AP event call.
Autopilot event check function.
Definition at line 146 of file autopilot.c.
Referenced by event_task_ap(), and main_event().
uint8_t autopilot_get_mode | ( | void | ) |
get autopilot mode
Get autopilot mode.
Definition at line 184 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_guided_goto_body_relative(), autopilot_guided_goto_ned(), autopilot_guided_goto_ned_relative(), autopilot_guided_move_ned(), autopilot_guided_update(), autopilot_static_on_rc_frame(), cam_periodic(), collective_tracking_control(), distributed_circular(), failsafe_check(), generic_com_periodic(), guidance_flip_enter(), gvf_control_2D(), gvf_parametric_low_level_control_2D(), gvf_parametric_low_level_control_3D(), h_ctl_pitch_loop(), h_ctl_roll_loop(), main_periodic(), mavlink_common_message_handler(), mavlink_send_heartbeat(), navigation_task(), NavKillThrottle(), NavResurrect(), periodic_auto1_commands(), pprz_mode_update(), stabilization_opticflow_vel_cb(), takeoff_detect_periodic(), 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 212 of file autopilot.c.
References autopilot, and pprz_autopilot::motors_on.
Referenced by actuators_ardrone_motor_status(), actuators_bebop_commit(), actuators_esc32_commit(), failsafe_check(), hott_check_serial_data(), hott_update_eam_msg(), hott_update_gam_msg(), intermcu_set_actuators(), mavlink_common_message_handler(), 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 257 of file autopilot.c.
References autopilot, and pprz_autopilot::in_flight.
Referenced by autopilot_generated_periodic(), autopilot_static_on_rc_frame(), autopilot_static_periodic(), e_identification_fr_periodic(), gps_sim_hitl_event(), guidance_flip_run(), ins_ekf2_publish_attitude(), ins_ekf2_update(), main_periodic(), mav_exercise_periodic(), nav_is_in_flight(), and orange_avoider_periodic().
void autopilot_init | ( | void | ) |
Autopilot initialization function.
Definition at line 91 of file autopilot.c.
References autopilot, autopilot_firmware_init(), autopilot_set_power_switch(), DefaultPeriodic, pprz_autopilot::detect_ground_once, pprz_autopilot::flight_time, gpio_clear(), gpio_setup_output(), pprz_autopilot::ground_detected, pprz_autopilot::in_flight, pprz_autopilot::kill_throttle, pprz_autopilot::mode_auto2, MODE_AUTO2, pprz_autopilot::motors_on, pprz_autopilot::power_switch, POWER_SWITCH_GPIO, register_periodic_telemetry(), send_actuators(), send_alive(), send_attitude(), send_autopilot_version(), send_dl_value(), send_rc(), pprz_autopilot::throttle, and pprz_autopilot::use_rc.
Referenced by init_ap(), and main_init().
void autopilot_on_rc_frame | ( | void | ) |
RC frame handler.
Autopilot RC input event hadler.
Definition at line 150 of file autopilot.c.
References autopilot_generated_on_rc_frame(), and autopilot_static_on_rc_frame().
Referenced by event_task_ap(), and main_event().
void autopilot_periodic | ( | void | ) |
AP periodic call.
Autopilot periodic call at PERIODIC_FREQUENCY.
Definition at line 135 of file autopilot.c.
References autopilot_generated_periodic(), and autopilot_static_periodic().
Referenced by handle_periodic_tasks_ap(), main_periodic(), and sim_periodic_task().
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 191 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 243 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 306 of file autopilot.c.
Referenced by autopilot_static_on_rc_frame(), and navigation_task().
void autopilot_send_version | ( | void | ) |
send autopilot version
Report autopilot version on default downlink channel.
Definition at line 298 of file autopilot.c.
References DefaultChannel, DefaultDevice, and send_autopilot_version().
Referenced by reporting_task(), and telemetry_periodic().
void autopilot_set_in_flight | ( | bool | in_flight | ) |
set in_flight flag
Set in flight status.
Definition at line 247 of file autopilot.c.
References autopilot, autopilot_reset_in_flight_counter(), and pprz_autopilot::in_flight.
Referenced by autopilot_arming_check_motors_on(), and autopilot_static_set_mode().
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 219 of file autopilot.c.
References autopilot_set_motors_on().
Referenced by actuators_disco_commit(), autopilot_static_on_rc_frame(), 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 161 of file autopilot.c.
References autopilot, autopilot_generated_set_mode(), autopilot_static_set_mode(), and pprz_autopilot::mode.
Referenced by autopilot_static_on_rc_frame(), failsafe_check(), guidance_flip_run(), mavlink_common_message_handler(), nav_set_failsafe(), navigation_task(), and pprz_mode_update().
void 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.
Definition at line 200 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 actuators_ardrone_motor_status(), actuators_bebop_commit(), autopilot_set_kill_throttle(), autopilot_static_set_mode(), mavlink_common_message_handler(), NavKillThrottle(), and NavResurrect().
void autopilot_set_power_switch | ( | bool | power_switch | ) |
set power switch
Set power switch state This will actually enable the switch if POWER_SWITCH_GPIO is defined Also provide macro for dl_setting backward compatibility.
Definition at line 264 of file autopilot.c.
References autopilot, gpio_clear(), gpio_set(), pprz_autopilot::power_switch, and POWER_SWITCH_GPIO.
Referenced by autopilot_init().
void autopilot_SetModeHandler | ( | float | mode | ) |
AP mode setting handler.
Handler for setter function with dl_setting.
Definition at line 173 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 278 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 230 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 60 of file autopilot.c.
References dev.
Referenced by autopilot_init().
|
static |
Definition at line 65 of file autopilot.c.
References dev, FloatEulers::phi, FloatEulers::psi, stateGetNedToBodyEulers_f(), and FloatEulers::theta.
Referenced by autopilot_init().
|
static |
Definition at line 53 of file autopilot.c.
References dev.
Referenced by autopilot_init(), and autopilot_send_version().
|
static |
Definition at line 71 of file autopilot.c.
References dev.
Referenced by autopilot_init().
|
static |
Definition at line 77 of file autopilot.c.
References dev, radio_control, RADIO_CONTROL_NB_CHANNEL, and RadioControl::values.
Referenced by autopilot_init().
struct pprz_autopilot autopilot |
Global autopilot structure.
Definition at line 50 of file autopilot.c.
Referenced by attitude_loop(), autopilot_arming_check_motors_on(), autopilot_arming_check_valid(), autopilot_check_in_flight(), autopilot_clear_settings(), autopilot_event(), 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_reset_flight_time(), autopilot_set_in_flight(), autopilot_set_mode(), autopilot_set_motors_on(), autopilot_set_power_switch(), 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(), draw_osd(), Drift_correction(), e_identification_fr_periodic(), gazebo_write(), generic_com_periodic(), gsm_send_report_continue(), guidance_h_module_enter(), guidance_h_module_read_rc(), guidance_indi_run(), h_ctl_course_loop(), h_ctl_pitch_loop(), h_ctl_roll_loop(), main_event(), main_periodic(), mf_daq_send_state(), monitor_task(), nav_bungee_takeoff_run(), nav_catapult_highrate_module(), nav_check_wp_time(), nav_detect_ground(), nav_home(), navigation_task(), nps_autopilot_run_step(), parse_mf_daq_msg(), send_energy(), send_fp(), send_mode(), send_status(), takeoff_detect_periodic(), uav_recovery_periodic(), v_ctl_climb_loop(), v_ctl_guidance_loop(), v_ctl_set_pitch(), and v_ctl_set_throttle().