58 PRINT_CONFIG_MSG_VALUE(
"USE_BARO_BOARD is TRUE, reading onboard baro: ",
BARO_BOARD)
69 #include "generated/flight_plan.h"
79 #if PERIODIC_TELEMETRY
85 #include "generated/modules.h"
86 #include "generated/settings.h"
87 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
95 #include "nps_autopilot.h"
99 #ifndef COMMAND_ROLL_TRIM
100 #define COMMAND_ROLL_TRIM 0
103 #ifndef COMMAND_PITCH_TRIM
104 #define COMMAND_PITCH_TRIM 0
107 #ifndef COMMAND_YAW_TRIM
108 #define COMMAND_YAW_TRIM 0
119 #ifndef TELEMETRY_FREQUENCY
120 #define TELEMETRY_FREQUENCY 60
127 PRINT_CONFIG_VAR(MODULES_FREQUENCY)
130 #ifndef BARO_PERIODIC_FREQUENCY
131 #define BARO_PERIODIC_FREQUENCY 50
138 #ifdef AHRS_PROPAGATE_FREQUENCY
139 #if (AHRS_PROPAGATE_FREQUENCY > PERIODIC_FREQUENCY)
140 #warning "PERIODIC_FREQUENCY should be least equal or greater than AHRS_PROPAGATE_FREQUENCY"
141 INFO_VALUE(
"it is recommended to configure in your airframe PERIODIC_FREQUENCY to at least ",
AHRS_PROPAGATE_FREQUENCY)
146 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
163 #ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
166 static void new_att_cb(
uint8_t sender_id __attribute__((unused)),
167 uint32_t stamp __attribute__((unused)),
168 struct Int32Rates *gyro __attribute__((unused)))
170 new_ins_attitude = 1;
181 #if defined(PPRZ_TRIG_INT_COMPR_FLASH)
182 pprz_trig_int_init();
203 #ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
204 AbiBindMsgIMU_GYRO_INT32(
ABI_BROADCAST, &new_att_ev, &new_att_cb);
218 #if defined MCU_SPI_LINK || defined MCU_UART_LINK || defined MCU_CAN_LINK
221 #if USE_AUDIO_TELEMETRY
253 #if defined AEROCOMM_DATA_PIN
254 IO0DIR |= _BV(AEROCOMM_DATA_PIN);
255 IO0SET = _BV(AEROCOMM_DATA_PIN);
295 #ifndef AHRS_TRIGGERED_ATTITUDE_LOOP
302 modules_periodic_task();
321 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
330 #ifndef RADIO_AUTO_MODE
333 INFO(
"Using RADIO_AUTO_MODE to switch between AUTO1 and AUTO2.")
348 #endif // RADIO_AUTO_MODE
353 #else // not RADIO_CONTROL
364 bool_t changed = ((
mcu1_status & MASK_FBW_CHANGED) != (new_status & MASK_FBW_CHANGED));
376 #ifdef SetAutoCommandsFromRC
378 #elif defined RADIO_YAW && defined COMMAND_YAW
385 #define RC_LOST_MODE PPRZ_MODE_HOME
397 uint8_t really_lost = bit_is_set(
fbw_state->status, STATUS_RADIO_REALLY_LOST) &&
410 if (bit_is_set(
fbw_state->status, AVERAGED_CHANNELS_SENT)) {
412 mode_changed |= pprz_mode_changed;
413 #if defined RADIO_CALIB && defined RADIO_CONTROL_SETTINGS
414 bool_t calib_mode_changed = RcSettingsModeUpdate(
fbw_state->channels);
415 rc_settings(calib_mode_changed || pprz_mode_changed);
416 mode_changed |= calib_mode_changed;
422 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
432 #if H_CTL_YAW_LOOP && defined RADIO_YAW
446 #endif // RADIO_CONTROL
486 #if PERIODIC_TELEMETRY
493 #ifdef FAILSAFE_DELAY_WITHOUT_GPS
494 #define GpsTimeoutError (sys_time.nb_sec - gps.last_3dfix_time > FAILSAFE_DELAY_WITHOUT_GPS)
502 #if defined FAILSAFE_DELAY_WITHOUT_GPS
509 if (GpsTimeoutError) {
538 #if DOWNLINK && !defined PERIOD_NAVIGATION_Ap_0 // If not sent periodically (in default 0 mode)
551 #ifdef H_CTL_RATE_LOOP
575 #if defined V_CTL_THROTTLE_IDLE
579 #ifdef V_CTL_POWER_CTL_BAT_NOMINAL
599 #if H_CTL_YAW_LOOP && defined COMMAND_YAW
600 ap_state->commands[COMMAND_YAW] = h_ctl_rudder_setpoint;
602 #if H_CTL_CL_LOOP && defined COMMAND_CL
603 ap_state->commands[COMMAND_CL] = h_ctl_flaps_setpoint;
606 #if defined MCU_SPI_LINK || defined MCU_UART_LINK || defined MCU_CAN_LINK
608 #elif defined INTER_MCU && defined SINGLE_MCU
624 #if USE_AHRS && defined SITL && !USE_NPS
639 #ifdef LOW_BATTERY_KILL_DELAY
640 #warning LOW_BATTERY_KILL_DELAY has been renamed to CATASTROPHIC_BAT_KILL_DELAY, please update your airframe file!
644 #ifndef CATASTROPHIC_BAT_KILL_DELAY
645 #define CATASTROPHIC_BAT_KILL_DELAY 5
649 #ifndef KILL_MODE_DISTANCE
650 #define KILL_MODE_DISTANCE (1.5*MAX_DIST_FROM_HOME)
654 #ifndef MIN_SPEED_FOR_TAKEOFF
655 #define MIN_SPEED_FOR_TAKEOFF 5.
664 #if defined DATALINK || defined SITL
669 if (
vsupply < CATASTROPHIC_BAT_LEVEL * 10) {
705 TODO(
"calling InsEvent, remove me..")
720 #if defined MCU_SPI_LINK || defined MCU_UART_LINK
730 modules_event_task();
732 #ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
733 if (new_ins_attitude > 0) {
735 new_ins_attitude = 0;
#define COMMAND_PITCH_TRIM
void monitor_task(void)
monitor stuff run at 1Hz
Event structure to store callbacks in a linked list.
Interface to align the AHRS via low-passed measurements at startup.
void h_ctl_course_loop(void)
uint16_t vsupply
Supply voltage in deciVolt.
tid_t monitor_tid
id for monitor_task() timer
tid_t modules_tid
id for modules_periodic_task() timer
Communication between fbw and ap processes.
Dispatcher to register actual AHRS implementations.
void traffic_info_init(void)
static float stateGetHorizontalSpeedNorm_f(void)
Get norm of horizontal ground speed (float).
Common barometric sensor implementation.
void h_ctl_attitude_loop(void)
void send_autopilot_version(struct transport_tx *trans, struct link_device *dev)
#define AHRS_PROPAGATE_FREQUENCY
void autopilot_init(void)
Autopilot inititalization.
tid_t telemetry_tid
id for telemetry_periodic() timer
static uint8_t mcu1_status_update(void)
Variable setting though the radio control.
pprz_t v_ctl_throttle_setpoint
Periodic telemetry system header (includes downlink utility and generated code).
void navigation_task(void)
Compute desired_course.
uint16_t autopilot_flight_time
flight time in seconds.
volatile bool_t inter_mcu_received_ap
AP ( AutoPilot ) process API.
static void audio_telemetry_init(void)
float dist2_to_home
squared distance to home waypoint
tid_t attitude_tid
id for attitude_loop() timer
Handling of messages coming from ground and other A/Cs.
static void telecommand_task(void)
Function to be called when a message from FBW is available.
Main include for ABI (AirBorneInterface).
volatile bool_t inter_mcu_received_fbw
uint8_t tid_t
sys_time timer id type
void nav_home(void)
Home mode navigation (circle around HOME)
void imu_periodic(void)
optional.
Integrated Navigation System interface.
tid_t sensors_tid
id for sensors_task() timer
#define COMMAND_ROLL_TRIM
#define V_CTL_MODE_AUTO_THROTTLE
#define RC_LOST_MODE
mode to enter when RC is lost in PPRZ_MODE_MANUAL or PPRZ_MODE_AUTO1
pprz_t h_ctl_elevator_setpoint
pprz_t h_ctl_aileron_setpoint
void v_ctl_throttle_slew(void)
Computes slewed throttle from throttle setpoint called at 20Hz.
void v_ctl_climb_loop(void)
Auto-throttle inner loop.
static uint8_t pprz_mode_update(void)
Update paparazzi mode.
static uint8_t mcu1_ppm_cpt
void ahrs_init(void)
AHRS initialization.
struct fbw_state * fbw_state
int32_t current
Supply current in milliAmpere.
void link_mcu_event_task(void)
float v_ctl_pitch_setpoint
struct ap_state * ap_state
Fixed wing horizontal control.
void common_nav_periodic_task_4Hz()
#define V_CTL_MODE_AUTO_ALT
#define THROTTLE_THRESHOLD_TAKEOFF
Common transport functions for the communication between FBW and AP.
Architecture independent timing functions.
static void copy_from_to_fbw(void)
Send back uncontrolled channels.
Device independent GPS code (interface)
struct Imu imu
global IMU state
void ins_init(void)
INS initialization.
void update_ahrs_from_sim(void)
#define DefaultPeriodic
Set default periodic telemetry.
#define CATASTROPHIC_BAT_KILL_DELAY
Maximum time allowed for catastrophic battery level before going into kill mode.
void reporting_task(void)
Send a series of initialisation messages followed by a stream of periodic ones.
Inertial Measurement Unit interface.
int sys_time_register_timer(float duration, sys_time_cb cb)
Register a new system timer.
#define V_CTL_MODE_AUTO_CLIMB
static bool_t sys_time_check_and_ack_timer(tid_t id)
Check if timer has elapsed.
void nav_init(void)
Periodic telemetry.
struct OrientationReps body_to_imu
rotation from body to imu frame
void autopilot_send_mode(void)
Send mode over telemetry.
#define DefaultChannel
SITL.
#define ModeUpdate(_mode, _value)
Assignment, returning _old_value != _value Using GCC expression statements.
Arch independent mcu ( Micro Controller Unit ) utilities.
float energy
Energy consumption (mAh) This is the ap copy of the measurement from fbw.
float h_ctl_pitch_setpoint
API to get/set the generic vehicle states.
volatile uint8_t new_ins_attitude
Persistent settings interface.
volatile uint32_t nb_sec
full seconds since startup
float h_ctl_roll_setpoint
float nav_pitch
with INT32_ANGLE_FRAC
void nav_without_gps(void)
Failsafe navigation without position estimation.
void gps_periodic_check(void)
Periodic GPS check.
#define TELEMETRY_FREQUENCY
#define FLOAT_OF_PPRZ(pprz, center, travel)
Common code for AP and FBW telemetry.
#define PERIODIC_FREQUENCY
arch independent LED (Light Emitting Diodes) API
#define ABI_BROADCAST
Broadcast address.
#define MIN_SPEED_FOR_TAKEOFF
Default minimal speed for takeoff in m/s.
#define NAVIGATION_FREQUENCY
void mcu_event(void)
MCU event functions.
#define CONTROL_FREQUENCY
void nav_periodic_task(void)
Navigation main: call to the code generated from the XML flight plan.
#define UNLOCKED_HOME_MODE
void rc_settings(bool_t mode_changed)
Includes generated code from tuning_rc.xml.
#define PPRZ_MODE_OF_PULSE(pprz)
#define PPRZ_MODE_MANUAL
AP modes.
tid_t navigation_tid
id for navigation_task() timer
#define KILL_MODE_DISTANCE
Maximum distance from HOME waypoint before going into kill mode.
#define LATERAL_MODE_COURSE
Fixedwing Navigation library.
#define BARO_PERIODIC_FREQUENCY
void ahrs_aligner_init(void)
pprz_t v_ctl_throttle_slewed
#define PPRZ_MODE_GPS_OUT_OF_ORDER
void gps_init(void)
initialize the global GPS state
pprz_t nav_throttle_setpoint
static struct FloatQuat * orientationGetQuat_f(struct OrientationReps *orientation)
Get vehicle body attitude quaternion (float).
Information relative to the other aircrafts.
void sensors_task(void)
Run at PERIODIC_FREQUENCY (60Hz if not defined)
void handle_periodic_tasks_ap(void)
void v_ctl_altitude_loop(void)
outer loop
Fixedwing autopilot modes.