Paparazzi UAS  v5.8.2_stable-0-g6260b7c
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
main_ap.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2003-2010 The Paparazzi Team
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
31 #define MODULES_C
32 
33 #define ABI_C
34 
35 #include <math.h>
36 
38 #include "mcu.h"
39 #include "mcu_periph/sys_time.h"
40 #include "inter_mcu.h"
41 #include "link_mcu.h"
42 
43 // Sensors
44 #if USE_GPS
45 #include "subsystems/gps.h"
46 #endif
47 #if USE_IMU
48 #include "subsystems/imu.h"
49 #endif
50 #if USE_AHRS
51 #include "subsystems/ahrs.h"
52 #endif
53 #if USE_AHRS_ALIGNER
55 #endif
56 #if USE_BARO_BOARD
58 PRINT_CONFIG_MSG_VALUE("USE_BARO_BOARD is TRUE, reading onboard baro: ", BARO_BOARD)
59 #endif
60 #include "subsystems/ins.h"
61 
62 
63 // autopilot & control
64 #include "state.h"
67 #include CTRL_TYPE_H
69 #include "generated/flight_plan.h"
70 #ifdef TRAFFIC_INFO
72 #endif
73 
74 // datalink & telemetry
75 #if DATALINK || SITL
78 #endif
79 #if PERIODIC_TELEMETRY
81 #endif
82 #include "subsystems/settings.h"
83 
84 // modules & settings
85 #include "generated/modules.h"
86 #include "generated/settings.h"
87 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
88 #include "rc_settings.h"
89 #endif
90 #include "subsystems/abi.h"
91 
92 #include "led.h"
93 
94 #ifdef USE_NPS
95 #include "nps_autopilot.h"
96 #endif
97 
98 /* Default trim commands for roll, pitch and yaw */
99 #ifndef COMMAND_ROLL_TRIM
100 #define COMMAND_ROLL_TRIM 0
101 #endif
102 
103 #ifndef COMMAND_PITCH_TRIM
104 #define COMMAND_PITCH_TRIM 0
105 #endif
106 
107 #ifndef COMMAND_YAW_TRIM
108 #define COMMAND_YAW_TRIM 0
109 #endif
110 
111 /* if PRINT_CONFIG is defined, print some config options */
112 PRINT_CONFIG_VAR(PERIODIC_FREQUENCY)
113 PRINT_CONFIG_VAR(NAVIGATION_FREQUENCY)
114 PRINT_CONFIG_VAR(CONTROL_FREQUENCY)
115 
116 /* TELEMETRY_FREQUENCY is defined in generated/periodic_telemetry.h
117  * defaults to 60Hz or set by TELEMETRY_FREQUENCY configure option in airframe file
118  */
119 #ifndef TELEMETRY_FREQUENCY
120 #define TELEMETRY_FREQUENCY 60
121 #endif
122 PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY)
123 
124 /* MODULES_FREQUENCY is defined in generated/modules.h
125  * according to main_freq parameter set for modules in airframe file
126  */
127 PRINT_CONFIG_VAR(MODULES_FREQUENCY)
128 
129 #if USE_BARO_BOARD
130 #ifndef BARO_PERIODIC_FREQUENCY
131 #define BARO_PERIODIC_FREQUENCY 50
132 #endif
133 PRINT_CONFIG_VAR(BARO_PERIODIC_FREQUENCY)
134 #endif
135 
136 
137 #if USE_IMU
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)
142 #endif
143 #endif
144 #endif // USE_IMU
145 
146 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
148 #endif
149 
150 
157 #if USE_BARO_BOARD
158 tid_t baro_tid;
159 #endif
160 
161 
163 #ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
164 volatile uint8_t new_ins_attitude = 0;
165 static abi_event new_att_ev;
166 static void new_att_cb(uint8_t sender_id __attribute__((unused)),
167  uint32_t stamp __attribute__((unused)),
168  struct Int32Rates *gyro __attribute__((unused)))
169 {
170  new_ins_attitude = 1;
171 }
172 #endif
173 
174 
175 void init_ap(void)
176 {
177 #ifndef SINGLE_MCU
178  mcu_init();
179 #endif /* SINGLE_MCU */
180 
181 #if defined(PPRZ_TRIG_INT_COMPR_FLASH)
182  pprz_trig_int_init();
183 #endif
184 
185  /****** initialize and reset state interface ********/
186 
187  stateInit();
188 
189  /************* Sensors initialization ***************/
190 #if USE_GPS
191  gps_init();
192 #endif
193 
194 #if USE_IMU
195  imu_init();
196 #endif
197 
198 #if USE_AHRS_ALIGNER
200 #endif
201 
203 #ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
204  AbiBindMsgIMU_GYRO_INT32(ABI_BROADCAST, &new_att_ev, &new_att_cb);
205 #endif
206 
207 #if USE_AHRS
208  ahrs_init();
209 #endif
210 
211  ins_init();
212 
213 #if USE_BARO_BOARD
214  baro_init();
215 #endif
216 
217  /************* Links initialization ***************/
218 #if defined MCU_SPI_LINK || defined MCU_UART_LINK || defined MCU_CAN_LINK
219  link_mcu_init();
220 #endif
221 #if USE_AUDIO_TELEMETRY
223 #endif
224 
225  /************ Internal status ***************/
226  autopilot_init();
227  h_ctl_init();
228  v_ctl_init();
229  nav_init();
230 
231  modules_init();
232 
233  settings_init();
234 
235  /**** start timers for periodic functions *****/
236  sensors_tid = sys_time_register_timer(1. / PERIODIC_FREQUENCY, NULL);
237  navigation_tid = sys_time_register_timer(1. / NAVIGATION_FREQUENCY, NULL);
238  attitude_tid = sys_time_register_timer(1. / CONTROL_FREQUENCY, NULL);
239  modules_tid = sys_time_register_timer(1. / MODULES_FREQUENCY, NULL);
240  telemetry_tid = sys_time_register_timer(1. / TELEMETRY_FREQUENCY, NULL);
241  monitor_tid = sys_time_register_timer(1.0, NULL);
242 #if USE_BARO_BOARD
243  baro_tid = sys_time_register_timer(1. / BARO_PERIODIC_FREQUENCY, NULL);
244 #endif
245 
247  mcu_int_enable();
248 
249 #if DOWNLINK
250  downlink_init();
251 #endif
252 
253 #if defined AEROCOMM_DATA_PIN
254  IO0DIR |= _BV(AEROCOMM_DATA_PIN);
255  IO0SET = _BV(AEROCOMM_DATA_PIN);
256 #endif
257 
258  /************ Multi-uavs status ***************/
259 
260 #ifdef TRAFFIC_INFO
262 #endif
263 
264  /* set initial trim values.
265  * these are passed to fbw via inter_mcu.
266  */
267  ap_state->command_roll_trim = COMMAND_ROLL_TRIM;
268  ap_state->command_pitch_trim = COMMAND_PITCH_TRIM;
269  ap_state->command_yaw_trim = COMMAND_YAW_TRIM;
270 
271 #if USE_IMU
272  // send body_to_imu from here for now
273  AbiSendMsgBODY_TO_IMU_QUAT(1, orientationGetQuat_f(&imu.body_to_imu));
274 #endif
275 }
276 
277 
279 {
280 
281  if (sys_time_check_and_ack_timer(sensors_tid)) {
282  sensors_task();
283  }
284 
285 #if USE_BARO_BOARD
286  if (sys_time_check_and_ack_timer(baro_tid)) {
287  baro_periodic();
288  }
289 #endif
290 
291  if (sys_time_check_and_ack_timer(navigation_tid)) {
292  navigation_task();
293  }
294 
295 #ifndef AHRS_TRIGGERED_ATTITUDE_LOOP
296  if (sys_time_check_and_ack_timer(attitude_tid)) {
297  attitude_loop();
298  }
299 #endif
300 
301  if (sys_time_check_and_ack_timer(modules_tid)) {
302  modules_periodic_task();
303  }
304 
305  if (sys_time_check_and_ack_timer(monitor_tid)) {
306  monitor_task();
307  }
308 
309  if (sys_time_check_and_ack_timer(telemetry_tid)) {
310  reporting_task();
311  LED_PERIODIC();
312  }
313 
314 }
315 
316 
317 /******************** Interaction with FBW *****************************/
318 
321 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
322 static inline uint8_t pprz_mode_update(void)
323 {
324  if ((pprz_mode != PPRZ_MODE_HOME &&
326 #ifdef UNLOCKED_HOME_MODE
327  || TRUE
328 #endif
329  ) {
330 #ifndef RADIO_AUTO_MODE
332 #else
333  INFO("Using RADIO_AUTO_MODE to switch between AUTO1 and AUTO2.")
334  /* If RADIO_AUTO_MODE is enabled mode swithing will be seperated between two switches/channels
335  * RADIO_MODE will switch between PPRZ_MODE_MANUAL and any PPRZ_MODE_AUTO mode selected by RADIO_AUTO_MODE.
336  *
337  * This is mainly a cludge for entry level radios with no three-way switch but two available two-way switches which can be used.
338  */
340  /* RADIO_MODE in MANUAL position */
342  } else {
343  /* RADIO_MODE not in MANUAL position.
344  * Select AUTO mode bassed on RADIO_AUTO_MODE channel
345  */
346  return ModeUpdate(pprz_mode, (fbw_state->channels[RADIO_AUTO_MODE] > THRESHOLD2) ? PPRZ_MODE_AUTO2 : PPRZ_MODE_AUTO1);
347  }
348 #endif // RADIO_AUTO_MODE
349  } else {
350  return FALSE;
351  }
352 }
353 #else // not RADIO_CONTROL
354 static inline uint8_t pprz_mode_update(void)
355 {
356  return FALSE;
357 }
358 #endif
359 
360 static inline uint8_t mcu1_status_update(void)
361 {
362  uint8_t new_status = fbw_state->status;
363  if (mcu1_status != new_status) {
364  bool_t changed = ((mcu1_status & MASK_FBW_CHANGED) != (new_status & MASK_FBW_CHANGED));
365  mcu1_status = new_status;
366  return changed;
367  }
368  return FALSE;
369 }
370 
371 
374 static inline void copy_from_to_fbw(void)
375 {
376 #ifdef SetAutoCommandsFromRC
377  SetAutoCommandsFromRC(ap_state->commands, fbw_state->channels);
378 #elif defined RADIO_YAW && defined COMMAND_YAW
379  ap_state->commands[COMMAND_YAW] = fbw_state->channels[RADIO_YAW];
380 #endif
381 }
382 
384 #ifndef RC_LOST_MODE
385 #define RC_LOST_MODE PPRZ_MODE_HOME
386 #endif
387 
391 static inline void telecommand_task(void)
392 {
393  uint8_t mode_changed = FALSE;
395 
396  /* really_lost is true if we lost RC in MANUAL or AUTO1 */
397  uint8_t really_lost = bit_is_set(fbw_state->status, STATUS_RADIO_REALLY_LOST) &&
399 
401  if (too_far_from_home) {
403  mode_changed = TRUE;
404  }
405  if (really_lost) {
407  mode_changed = TRUE;
408  }
409  }
410  if (bit_is_set(fbw_state->status, AVERAGED_CHANNELS_SENT)) {
411  bool_t pprz_mode_changed = pprz_mode_update();
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;
417 #endif
418  }
419  mode_changed |= mcu1_status_update();
420  if (mode_changed) { autopilot_send_mode(); }
421 
422 #if defined RADIO_CONTROL || defined RADIO_CONTROL_AUTO1
423 
426  if (pprz_mode == PPRZ_MODE_AUTO1) {
428  h_ctl_roll_setpoint = FLOAT_OF_PPRZ(fbw_state->channels[RADIO_ROLL], 0., AUTO1_MAX_ROLL);
429 
431  h_ctl_pitch_setpoint = FLOAT_OF_PPRZ(fbw_state->channels[RADIO_PITCH], 0., AUTO1_MAX_PITCH);
432 #if H_CTL_YAW_LOOP && defined RADIO_YAW
433 
434  h_ctl_yaw_rate_setpoint = FLOAT_OF_PPRZ(fbw_state->channels[RADIO_YAW], 0., AUTO1_MAX_YAW_RATE);
435 #endif
436  }
442  }
445  mcu1_ppm_cpt = fbw_state->ppm_cpt;
446 #endif // RADIO_CONTROL
447 
448 
449  vsupply = fbw_state->vsupply;
450  current = fbw_state->current;
451  energy = fbw_state->energy;
452 
453 #ifdef RADIO_CONTROL
454  /* the SITL check is a hack to prevent "automatic" launch in NPS */
455 #ifndef SITL
456  if (!autopilot_flight_time) {
458  launch = TRUE;
459  }
460  }
461 #endif
462 #endif
463 }
464 
465 
466 /**************************** Periodic tasks ***********************************/
467 
472 void reporting_task(void)
473 {
474  static uint8_t boot = TRUE;
475 
476  /* initialisation phase during boot */
477  if (boot) {
478 #if DOWNLINK
479  send_autopilot_version(&(DefaultChannel).trans_tx, &(DefaultDevice).device);
480 #endif
481  boot = FALSE;
482  }
483  /* then report periodicly */
484  else {
485  //PeriodicSendAp(DefaultChannel, DefaultDevice);
486 #if PERIODIC_TELEMETRY
487  periodic_telemetry_send_Ap(DefaultPeriodic, &(DefaultChannel).trans_tx, &(DefaultDevice).device);
488 #endif
489  }
490 }
491 
492 
493 #ifdef FAILSAFE_DELAY_WITHOUT_GPS
494 #define GpsTimeoutError (sys_time.nb_sec - gps.last_3dfix_time > FAILSAFE_DELAY_WITHOUT_GPS)
495 #endif
496 
500 void navigation_task(void)
501 {
502 #if defined FAILSAFE_DELAY_WITHOUT_GPS
503 
504  static uint8_t last_pprz_mode;
505 
508  if (launch) {
509  if (GpsTimeoutError) {
511  last_pprz_mode = pprz_mode;
514  gps_lost = TRUE;
515  }
516  } else if (gps_lost) { /* GPS is ok */
518  pprz_mode = last_pprz_mode;
519  gps_lost = FALSE;
521  }
522  }
523 #endif /* GPS && FAILSAFE_DELAY_WITHOUT_GPS */
524 
526  if (pprz_mode == PPRZ_MODE_HOME) {
527  nav_home();
528  } else if (pprz_mode == PPRZ_MODE_GPS_OUT_OF_ORDER) {
529  nav_without_gps();
530  } else {
532  }
533 
534 #ifdef TCAS
535  CallTCAS();
536 #endif
537 
538 #if DOWNLINK && !defined PERIOD_NAVIGATION_Ap_0 // If not sent periodically (in default 0 mode)
539  SEND_NAVIGATION(&(DefaultChannel).trans_tx, &(DefaultDevice).device);
540 #endif
541 
542  /* The nav task computes only nav_altitude. However, we are interested
543  by desired_altitude (= nav_alt+alt_shift) in any case.
544  So we always run the altitude control loop */
547  }
548 
551 #ifdef H_CTL_RATE_LOOP
552  /* Be sure to be in attitude mode, not roll */
554 #endif
556  h_ctl_course_loop(); /* aka compute nav_desired_roll */
557  }
558 
559  // climb_loop(); //4Hz
560  }
561 }
562 
563 
564 void attitude_loop(void)
565 {
566 
567  if (pprz_mode >= PPRZ_MODE_AUTO2) {
571  } else if (v_ctl_mode >= V_CTL_MODE_AUTO_CLIMB) {
573  }
574 
575 #if defined V_CTL_THROTTLE_IDLE
576  Bound(v_ctl_throttle_setpoint, TRIM_PPRZ(V_CTL_THROTTLE_IDLE * MAX_PPRZ), MAX_PPRZ);
577 #endif
578 
579 #ifdef V_CTL_POWER_CTL_BAT_NOMINAL
580  if (vsupply > 0.) {
581  v_ctl_throttle_setpoint *= 10. * V_CTL_POWER_CTL_BAT_NOMINAL / (float)vsupply;
583  }
584 #endif
585 
586  // Copy the pitch setpoint from the guidance to the stabilization control
588  Bound(h_ctl_pitch_setpoint, H_CTL_PITCH_MIN_SETPOINT, H_CTL_PITCH_MAX_SETPOINT);
591  }
592  }
593 
594  h_ctl_attitude_loop(); /* Set h_ctl_aileron_setpoint & h_ctl_elevator_setpoint */
596  ap_state->commands[COMMAND_THROTTLE] = v_ctl_throttle_slewed;
597  ap_state->commands[COMMAND_ROLL] = -h_ctl_aileron_setpoint;
598  ap_state->commands[COMMAND_PITCH] = h_ctl_elevator_setpoint;
599 #if H_CTL_YAW_LOOP && defined COMMAND_YAW
600  ap_state->commands[COMMAND_YAW] = h_ctl_rudder_setpoint;
601 #endif
602 #if H_CTL_CL_LOOP && defined COMMAND_CL
603  ap_state->commands[COMMAND_CL] = h_ctl_flaps_setpoint;
604 #endif
605 
606 #if defined MCU_SPI_LINK || defined MCU_UART_LINK || defined MCU_CAN_LINK
607  link_mcu_send();
608 #elif defined INTER_MCU && defined SINGLE_MCU
609 
611 #endif
612 
613 }
614 
615 
617 void sensors_task(void)
618 {
619 #if USE_IMU
620  imu_periodic();
621 #endif // USE_IMU
622 
623  //FIXME: this is just a kludge
624 #if USE_AHRS && defined SITL && !USE_NPS
626 #endif
627 
628 #if USE_GPS
630 #endif
631 
632  //FIXME: temporary hack, remove me
633 #ifdef InsPeriodic
634  InsPeriodic();
635 #endif
636 }
637 
638 
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!
641 #endif
642 
644 #ifndef CATASTROPHIC_BAT_KILL_DELAY
645 #define CATASTROPHIC_BAT_KILL_DELAY 5
646 #endif
647 
649 #ifndef KILL_MODE_DISTANCE
650 #define KILL_MODE_DISTANCE (1.5*MAX_DIST_FROM_HOME)
651 #endif
652 
654 #ifndef MIN_SPEED_FOR_TAKEOFF
655 #define MIN_SPEED_FOR_TAKEOFF 5.
656 #endif
657 
659 void monitor_task(void)
660 {
661  if (autopilot_flight_time) {
663  }
664 #if defined DATALINK || defined SITL
665  datalink_time++;
666 #endif
667 
668  static uint8_t t = 0;
669  if (vsupply < CATASTROPHIC_BAT_LEVEL * 10) {
670  t++;
671  } else {
672  t = 0;
673  }
676 
677  if (!autopilot_flight_time &&
680  launch = TRUE; /* Not set in non auto launch */
681 #if DOWNLINK
682  uint16_t time_sec = sys_time.nb_sec;
683  DOWNLINK_SEND_TAKEOFF(DefaultChannel, DefaultDevice, &time_sec);
684 #endif
685  }
686 
687 }
688 
689 
690 /*********** EVENT ***********************************************************/
691 void event_task_ap(void)
692 {
693 
694 #ifndef SINGLE_MCU
695  /* for SINGLE_MCU done in main_fbw */
696  /* event functions for mcu peripherals: i2c, usb_serial.. */
697  mcu_event();
698 #endif /* SINGLE_MCU */
699 
700 #if USE_IMU
701  ImuEvent();
702 #endif
703 
704 #ifdef InsEvent
705  TODO("calling InsEvent, remove me..")
706  InsEvent();
707 #endif
708 
709 #if USE_GPS
710  GpsEvent();
711 #endif /* USE_GPS */
712 
713 #if USE_BARO_BOARD
714  BaroEvent();
715 #endif
716 
717  DatalinkEvent();
718 
719 
720 #if defined MCU_SPI_LINK || defined MCU_UART_LINK
722 #endif
723 
725  /* receive radio control task from fbw */
728  }
729 
730  modules_event_task();
731 
732 #ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
733  if (new_ins_attitude > 0) {
734  attitude_loop();
735  new_ins_attitude = 0;
736  }
737 #endif
738 
739 } /* event_task_ap() */
740 
#define COMMAND_PITCH_TRIM
Definition: main_ap.c:104
void monitor_task(void)
monitor stuff run at 1Hz
Definition: main_ap.c:659
Event structure to store callbacks in a linked list.
Definition: abi_common.h:65
Interface to align the AHRS via low-passed measurements at startup.
unsigned short uint16_t
Definition: types.h:16
angular rates
void h_ctl_course_loop(void)
uint16_t vsupply
Supply voltage in deciVolt.
Definition: autopilot.c:52
tid_t monitor_tid
id for monitor_task() timer
Definition: main_ap.c:156
tid_t modules_tid
id for modules_periodic_task() timer
Definition: main_ap.c:151
bool_t launch
Definition: sim_ap.c:39
Communication between fbw and ap processes.
Dispatcher to register actual AHRS implementations.
void traffic_info_init(void)
Definition: traffic_info.c:37
static float stateGetHorizontalSpeedNorm_f(void)
Get norm of horizontal ground speed (float).
Definition: state.h:912
Common barometric sensor implementation.
void h_ctl_attitude_loop(void)
void send_autopilot_version(struct transport_tx *trans, struct link_device *dev)
Definition: autopilot.c:158
#define AHRS_PROPAGATE_FREQUENCY
Definition: hf_float.c:51
#define RADIO_ROLL
Definition: spektrum_arch.h:43
void autopilot_init(void)
Autopilot inititalization.
Definition: autopilot.c:175
tid_t telemetry_tid
id for telemetry_periodic() timer
Definition: main_ap.c:152
static uint8_t mcu1_status_update(void)
Definition: main_ap.c:360
#define RADIO_YAW
Definition: spektrum_arch.h:45
Variable setting though the radio control.
pprz_t v_ctl_throttle_setpoint
Definition: energy_ctrl.c:131
Periodic telemetry system header (includes downlink utility and generated code).
void navigation_task(void)
Compute desired_course.
Definition: main_ap.c:500
uint16_t autopilot_flight_time
flight time in seconds.
Definition: autopilot.c:48
volatile bool_t inter_mcu_received_ap
Definition: inter_mcu.c:41
AP ( AutoPilot ) process API.
void h_ctl_init(void)
static void audio_telemetry_init(void)
uint8_t pprz_mode
Definition: autopilot.c:41
uint8_t lateral_mode
Definition: autopilot.c:50
tid_t attitude_tid
id for attitude_loop() timer
Definition: main_ap.c:154
static void telecommand_task(void)
Function to be called when a message from FBW is available.
Definition: main_ap.c:391
#define InsEvent
Main include for ABI (AirBorneInterface).
volatile bool_t inter_mcu_received_fbw
Definition: inter_mcu.c:40
uint8_t tid_t
sys_time timer id type
Definition: sys_time.h:57
void imu_periodic(void)
optional.
Definition: imu_apogee.c:95
Integrated Navigation System interface.
tid_t sensors_tid
id for sensors_task() timer
Definition: main_ap.c:153
#define COMMAND_ROLL_TRIM
Definition: main_ap.c:100
void baro_init(void)
Definition: baro_board.c:68
#define V_CTL_MODE_AUTO_THROTTLE
#define PPRZ_MODE_AUTO2
Definition: autopilot.h:52
#define RC_LOST_MODE
mode to enter when RC is lost in PPRZ_MODE_MANUAL or PPRZ_MODE_AUTO1
Definition: main_ap.c:385
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.
Definition: energy_ctrl.c:450
void v_ctl_climb_loop(void)
Auto-throttle inner loop.
Definition: energy_ctrl.c:334
static uint8_t pprz_mode_update(void)
Update paparazzi mode.
Definition: main_ap.c:322
static uint8_t mcu1_ppm_cpt
Definition: main_ap.c:147
void ahrs_init(void)
AHRS initialization.
Definition: ahrs.c:68
struct fbw_state * fbw_state
Definition: inter_mcu.c:36
int32_t current
Supply current in milliAmpere.
Definition: autopilot.c:53
void init_ap(void)
Definition: main_ap.c:175
#define BARO_BOARD
Definition: baro_board.h:33
float v_ctl_pitch_setpoint
Definition: energy_ctrl.c:133
#define FALSE
Definition: std.h:5
struct ap_state * ap_state
Definition: inter_mcu.c:37
void baro_periodic(void)
Definition: baro_board.c:77
#define CallTCAS()
Definition: tcas.h:57
Fixed wing horizontal control.
void settings_init(void)
Definition: settings.c:43
void stateInit(void)
Definition: state.c:43
#define TRUE
Definition: std.h:4
void common_nav_periodic_task_4Hz()
Definition: common_nav.c:124
#define TRIM_UPPRZ(pprz)
Definition: paparazzi.h:14
bool_t gps_lost
Definition: autopilot.c:56
#define V_CTL_MODE_AUTO_ALT
#define THROTTLE_THRESHOLD_TAKEOFF
Definition: autopilot.h:84
Architecture independent timing functions.
static void copy_from_to_fbw(void)
Send back uncontrolled channels.
Definition: main_ap.c:374
#define RADIO_PITCH
Definition: spektrum_arch.h:44
#define PPRZ_MODE_HOME
Definition: autopilot.h:53
Device independent GPS code (interface)
#define COMMAND_YAW_TRIM
Definition: main_ap.c:108
struct Imu imu
global IMU state
Definition: imu_aspirin2.c:43
void ins_init(void)
INS initialization.
Definition: ins.c:60
unsigned long uint32_t
Definition: types.h:18
#define BaroEvent
Definition: baro_board.h:36
void event_task_ap(void)
Definition: main_ap.c:691
void update_ahrs_from_sim(void)
Definition: ahrs_sim.c:52
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
bool_t kill_throttle
Definition: autopilot.c:42
#define PPRZ_MODE_AUTO1
Definition: autopilot.h:51
#define ImuEvent
Definition: imu_apogee.h:113
#define RADIO_THROTTLE
Definition: spektrum_arch.h:42
#define CATASTROPHIC_BAT_KILL_DELAY
Maximum time allowed for catastrophic battery level before going into kill mode.
Definition: main_ap.c:645
void reporting_task(void)
Send a series of initialisation messages followed by a stream of periodic ones.
Definition: main_ap.c:472
uint8_t v_ctl_mode
Definition: energy_ctrl.c:74
Inertial Measurement Unit interface.
int sys_time_register_timer(float duration, sys_time_cb cb)
Register a new system timer.
Definition: sys_time.c:37
#define V_CTL_MODE_AUTO_CLIMB
static bool_t sys_time_check_and_ack_timer(tid_t id)
Check if timer has elapsed.
Definition: sys_time.h:111
struct OrientationReps body_to_imu
rotation from body to imu frame
Definition: imu.h:53
#define IO0SET
Definition: LPC21xx.h:334
#define IO0DIR
Definition: LPC21xx.h:335
uint16_t datalink_time
Definition: sim_ap.c:43
void autopilot_send_mode(void)
Send mode over telemetry.
Definition: autopilot.c:167
#define RADIO_MODE
Definition: spektrum_arch.h:59
#define ModeUpdate(_mode, _value)
Assignment, returning _old_value != _value Using GCC expression statements.
Definition: autopilot.h:107
Arch independent mcu ( Micro Controller Unit ) utilities.
#define mcu_int_enable()
Definition: mcu_arch.h:35
float energy
Energy consumption (mAh) This is the ap copy of the measurement from fbw.
Definition: autopilot.c:54
float h_ctl_pitch_setpoint
unsigned char uint8_t
Definition: types.h:14
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
Definition: sys_time.h:69
float h_ctl_roll_setpoint
bool_t h_ctl_auto1_rate
void gps_periodic_check(void)
Periodic GPS check.
Definition: gps.c:166
#define LED_PERIODIC()
Definition: led_hw.h:47
uint8_t mcu1_status
Definition: autopilot.c:43
#define TELEMETRY_FREQUENCY
Definition: main_ap.c:120
#define FLOAT_OF_PPRZ(pprz, center, travel)
Definition: autopilot.h:82
#define PERIODIC_FREQUENCY
Definition: imu_aspirin2.c:47
arch independent LED (Light Emitting Diodes) API
#define ABI_BROADCAST
Broadcast address.
Definition: abi_common.h:56
#define MIN_SPEED_FOR_TAKEOFF
Default minimal speed for takeoff in m/s.
Definition: main_ap.c:655
void v_ctl_init(void)
Definition: energy_ctrl.c:216
#define NAVIGATION_FREQUENCY
Definition: autopilot.h:145
void mcu_event(void)
MCU event functions.
Definition: mcu.c:192
#define CONTROL_FREQUENCY
Definition: autopilot.h:140
#define MAX_PPRZ
Definition: paparazzi.h:8
#define UNLOCKED_HOME_MODE
Definition: autopilot.c:144
void rc_settings(bool_t mode_changed)
Includes generated code from tuning_rc.xml.
Definition: rc_settings.c:49
#define PPRZ_MODE_OF_PULSE(pprz)
Definition: autopilot.h:57
#define PPRZ_MODE_MANUAL
AP modes.
Definition: autopilot.h:50
tid_t navigation_tid
id for navigation_task() timer
Definition: main_ap.c:155
#define KILL_MODE_DISTANCE
Maximum distance from HOME waypoint before going into kill mode.
Definition: main_ap.c:650
void imu_init(void)
Definition: imu.c:110
#define LATERAL_MODE_COURSE
Definition: autopilot.h:77
#define BARO_PERIODIC_FREQUENCY
Definition: main.c:101
void ahrs_aligner_init(void)
Definition: ahrs_aligner.c:79
#define TRIM_PPRZ(pprz)
Definition: paparazzi.h:11
pprz_t v_ctl_throttle_slewed
Definition: energy_ctrl.c:132
#define THRESHOLD2
Definition: autopilot.h:46
#define PPRZ_MODE_GPS_OUT_OF_ORDER
Definition: autopilot.h:54
void gps_init(void)
initialize the global GPS state
Definition: gps.c:135
void attitude_loop(void)
Definition: main_ap.c:564
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)
Definition: main_ap.c:617
void handle_periodic_tasks_ap(void)
Definition: main_ap.c:278
void v_ctl_altitude_loop(void)
outer loop
Definition: energy_ctrl.c:296
Fixedwing autopilot modes.