Paparazzi UAS
v5.8.2_stable-0-g6260b7c
Paparazzi is a free software Unmanned Aircraft System.
|
AP ( AutoPilot ) tasks. More...
#include <math.h>
#include "firmwares/fixedwing/main_ap.h"
#include "mcu.h"
#include "mcu_periph/sys_time.h"
#include "inter_mcu.h"
#include "link_mcu.h"
#include "subsystems/gps.h"
#include "subsystems/imu.h"
#include "subsystems/ahrs.h"
#include "subsystems/ahrs/ahrs_aligner.h"
#include "subsystems/ins.h"
#include "state.h"
#include "firmwares/fixedwing/autopilot.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
#include <CTRL_TYPE_H>
#include "firmwares/fixedwing/nav.h"
#include "generated/flight_plan.h"
#include "subsystems/datalink/datalink.h"
#include "subsystems/datalink/downlink.h"
#include "subsystems/settings.h"
#include "generated/modules.h"
#include "generated/settings.h"
#include "rc_settings.h"
#include "subsystems/abi.h"
#include "led.h"
Go to the source code of this file.
Macros | |
#define | MODULES_C |
#define | ABI_C |
#define | COMMAND_ROLL_TRIM 0 |
#define | COMMAND_PITCH_TRIM 0 |
#define | COMMAND_YAW_TRIM 0 |
#define | TELEMETRY_FREQUENCY 60 |
#define | RC_LOST_MODE PPRZ_MODE_HOME |
mode to enter when RC is lost in PPRZ_MODE_MANUAL or PPRZ_MODE_AUTO1 More... | |
#define | CATASTROPHIC_BAT_KILL_DELAY 5 |
Maximum time allowed for catastrophic battery level before going into kill mode. More... | |
#define | KILL_MODE_DISTANCE (1.5*MAX_DIST_FROM_HOME) |
Maximum distance from HOME waypoint before going into kill mode. More... | |
#define | MIN_SPEED_FOR_TAKEOFF 5. |
Default minimal speed for takeoff in m/s. More... | |
Functions | |
void | init_ap (void) |
void | handle_periodic_tasks_ap (void) |
static uint8_t | pprz_mode_update (void) |
Update paparazzi mode. More... | |
static uint8_t | mcu1_status_update (void) |
static void | copy_from_to_fbw (void) |
Send back uncontrolled channels. More... | |
static void | telecommand_task (void) |
Function to be called when a message from FBW is available. More... | |
void | reporting_task (void) |
Send a series of initialisation messages followed by a stream of periodic ones. More... | |
void | navigation_task (void) |
Compute desired_course. More... | |
void | attitude_loop (void) |
void | sensors_task (void) |
Run at PERIODIC_FREQUENCY (60Hz if not defined) More... | |
void | monitor_task (void) |
monitor stuff run at 1Hz More... | |
void | event_task_ap (void) |
Variables | |
static uint8_t | mcu1_ppm_cpt |
tid_t | modules_tid |
id for modules_periodic_task() timer More... | |
tid_t | telemetry_tid |
id for telemetry_periodic() timer More... | |
tid_t | sensors_tid |
id for sensors_task() timer More... | |
tid_t | attitude_tid |
id for attitude_loop() timer More... | |
tid_t | navigation_tid |
id for navigation_task() timer More... | |
tid_t | monitor_tid |
id for monitor_task() timer More... | |
AP ( AutoPilot ) tasks.
This process is reponsible for the collecting the different sensors data, calling the appropriate estimation algorithms and running the different control loops.
Definition in file main_ap.c.
#define CATASTROPHIC_BAT_KILL_DELAY 5 |
Maximum time allowed for catastrophic battery level before going into kill mode.
Definition at line 645 of file main_ap.c.
Referenced by monitor_task().
#define KILL_MODE_DISTANCE (1.5*MAX_DIST_FROM_HOME) |
Maximum distance from HOME waypoint before going into kill mode.
Definition at line 650 of file main_ap.c.
Referenced by monitor_task().
#define MIN_SPEED_FOR_TAKEOFF 5. |
Default minimal speed for takeoff in m/s.
Definition at line 655 of file main_ap.c.
Referenced by monitor_task().
#define RC_LOST_MODE PPRZ_MODE_HOME |
mode to enter when RC is lost in PPRZ_MODE_MANUAL or PPRZ_MODE_AUTO1
Definition at line 385 of file main_ap.c.
Referenced by telecommand_task().
#define TELEMETRY_FREQUENCY 60 |
Definition at line 120 of file main_ap.c.
Referenced by init_ap(), and main_init().
void attitude_loop | ( | void | ) |
Definition at line 564 of file main_ap.c.
References ap_state, autopilot_flight_time, h_ctl_aileron_setpoint, h_ctl_attitude_loop(), h_ctl_elevator_setpoint, h_ctl_pitch_setpoint, inter_mcu_received_ap, kill_throttle, launch, link_mcu_send(), MAX_PPRZ, nav_pitch, nav_throttle_setpoint, pprz_mode, PPRZ_MODE_AUTO2, TRIM_PPRZ, TRIM_UPPRZ, TRUE, v_ctl_climb_loop(), v_ctl_mode, V_CTL_MODE_AUTO_CLIMB, V_CTL_MODE_AUTO_THROTTLE, v_ctl_pitch_setpoint, v_ctl_throttle_setpoint, v_ctl_throttle_slew(), v_ctl_throttle_slewed, and vsupply.
Referenced by event_task_ap(), handle_periodic_tasks_ap(), and sim_periodic_task().
|
inlinestatic |
void event_task_ap | ( | void | ) |
Definition at line 691 of file main_ap.c.
References attitude_loop(), BaroEvent, DatalinkEvent, FALSE, GpsEvent, ImuEvent, InsEvent, inter_mcu_received_fbw, link_mcu_event_task(), mcu_event(), and telecommand_task().
Referenced by sim_periodic_task().
void handle_periodic_tasks_ap | ( | void | ) |
Definition at line 278 of file main_ap.c.
References attitude_loop(), baro_periodic(), LED_PERIODIC, monitor_task(), navigation_task(), reporting_task(), sensors_task(), and sys_time_check_and_ack_timer().
void init_ap | ( | void | ) |
init done in main_fbw in single MCU
Definition at line 175 of file main_ap.c.
References ABI_BROADCAST, ahrs_aligner_init(), ahrs_init(), ap_state, audio_telemetry_init(), autopilot_init(), baro_init(), BARO_PERIODIC_FREQUENCY, Imu::body_to_imu, COMMAND_PITCH_TRIM, COMMAND_ROLL_TRIM, COMMAND_YAW_TRIM, CONTROL_FREQUENCY, downlink_init(), gps_init(), h_ctl_init(), imu, imu_init(), ins_init(), IO0DIR, IO0SET, link_mcu_init(), mcu_int_enable, nav_init(), NAVIGATION_FREQUENCY, orientationGetQuat_f(), PERIODIC_FREQUENCY, settings_init(), stateInit(), sys_time_register_timer(), TELEMETRY_FREQUENCY, traffic_info_init(), and v_ctl_init().
Referenced by sim_init().
|
inlinestatic |
Definition at line 360 of file main_ap.c.
References FALSE, fbw_state, and mcu1_status.
Referenced by telecommand_task().
void monitor_task | ( | void | ) |
monitor stuff run at 1Hz
Definition at line 659 of file main_ap.c.
References autopilot_flight_time, CATASTROPHIC_BAT_KILL_DELAY, datalink_time, DefaultChannel, DefaultDevice, dist2_to_home, KILL_MODE_DISTANCE, kill_throttle, launch, MIN_SPEED_FOR_TAKEOFF, sys_time::nb_sec, Square, stateGetHorizontalSpeedNorm_f(), TRUE, and vsupply.
Referenced by handle_periodic_tasks_ap(), and sim_monitor_task().
void navigation_task | ( | void | ) |
Compute desired_course.
Definition at line 500 of file main_ap.c.
References autopilot_send_mode(), CallTCAS, common_nav_periodic_task_4Hz(), DefaultChannel, DefaultDevice, FALSE, gps_lost, h_ctl_auto1_rate, h_ctl_course_loop(), lateral_mode, LATERAL_MODE_COURSE, launch, nav_home(), nav_periodic_task(), nav_without_gps(), pprz_mode, PPRZ_MODE_AUTO2, PPRZ_MODE_GPS_OUT_OF_ORDER, PPRZ_MODE_HOME, TRUE, v_ctl_altitude_loop(), v_ctl_mode, and V_CTL_MODE_AUTO_ALT.
Referenced by handle_periodic_tasks_ap(), and sim_nav_task().
|
inlinestatic |
Update paparazzi mode.
Definition at line 322 of file main_ap.c.
References FALSE, fbw_state, ModeUpdate, pprz_mode, PPRZ_MODE_AUTO1, PPRZ_MODE_AUTO2, PPRZ_MODE_GPS_OUT_OF_ORDER, PPRZ_MODE_HOME, PPRZ_MODE_MANUAL, PPRZ_MODE_OF_PULSE, RADIO_MODE, THRESHOLD2, TRUE, and UNLOCKED_HOME_MODE.
Referenced by telecommand_task().
void reporting_task | ( | void | ) |
Send a series of initialisation messages followed by a stream of periodic ones.
Called at 60Hz.
Definition at line 472 of file main_ap.c.
References DefaultChannel, DefaultDevice, DefaultPeriodic, FALSE, send_autopilot_version(), and TRUE.
Referenced by handle_periodic_tasks_ap(), and sim_periodic_task().
void sensors_task | ( | void | ) |
Run at PERIODIC_FREQUENCY (60Hz if not defined)
Definition at line 617 of file main_ap.c.
References gps_periodic_check(), imu_periodic(), and update_ahrs_from_sim().
Referenced by handle_periodic_tasks_ap(), and sim_periodic_task().
|
inlinestatic |
Function to be called when a message from FBW is available.
In AUTO1 mode, compute roll setpoint and pitch setpoint from RADIO_ROLL and RADIO_PITCH
Roll is bounded between [-AUTO1_MAX_ROLL;AUTO1_MAX_ROLL]
Pitch is bounded between [-AUTO1_MAX_PITCH;AUTO1_MAX_PITCH]
Else asynchronously set by h_ctl_course_loop()
In AUTO1, throttle comes from RADIO_THROTTLE In MANUAL, the value is copied to get it in the telemetry
else asynchronously set by v_ctl_climb_loop();
Definition at line 391 of file main_ap.c.
References autopilot_flight_time, autopilot_send_mode(), copy_from_to_fbw(), current, energy, FALSE, fbw_state, FLOAT_OF_PPRZ, h_ctl_pitch_setpoint, h_ctl_roll_setpoint, launch, mcu1_status_update(), pprz_mode, PPRZ_MODE_AUTO1, PPRZ_MODE_AUTO2, PPRZ_MODE_GPS_OUT_OF_ORDER, PPRZ_MODE_HOME, PPRZ_MODE_MANUAL, pprz_mode_update(), RADIO_PITCH, RADIO_ROLL, RADIO_THROTTLE, RADIO_YAW, RC_LOST_MODE, rc_settings(), THROTTLE_THRESHOLD_TAKEOFF, too_far_from_home, TRUE, v_ctl_throttle_setpoint, and vsupply.
Referenced by event_task_ap().
tid_t attitude_tid |
id for attitude_loop() timer
tid_t monitor_tid |
id for monitor_task() timer
tid_t navigation_tid |
id for navigation_task() timer
tid_t sensors_tid |
id for sensors_task() timer
tid_t telemetry_tid |
id for telemetry_periodic() timer