From ef43e75b2a2f948fd6c3902600817cc9fe831918 Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Sat, 22 Jun 2013 12:24:36 -0600 Subject: [PATCH 001/309] [nps] Started to add fixed wing support in NPS --- conf/airframes/examples/MentorEnergy.xml | 11 ++ sw/airborne/firmwares/fixedwing/main_ap.c | 4 + sw/airborne/firmwares/fixedwing/main_fbw.c | 3 + sw/simulator/nps/nps_autopilot_fixedwing.c | 143 +++++++++++++++++++++ sw/simulator/nps/nps_autopilot_fixedwing.h | 10 ++ 5 files changed, 171 insertions(+) create mode 100644 sw/simulator/nps/nps_autopilot_fixedwing.c create mode 100644 sw/simulator/nps/nps_autopilot_fixedwing.h diff --git a/conf/airframes/examples/MentorEnergy.xml b/conf/airframes/examples/MentorEnergy.xml index 39c98a1283..d6d954baf6 100644 --- a/conf/airframes/examples/MentorEnergy.xml +++ b/conf/airframes/examples/MentorEnergy.xml @@ -22,6 +22,11 @@ + + + + + @@ -251,4 +256,10 @@ +
+ + + +
+ diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 08a3c1342a..dfc5dd6088 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -84,6 +84,10 @@ #include "led.h" +#ifdef SITL +#include "nps_autopilot_fixedwing.h" +#endif + /* if PRINT_CONFIG is defined, print some config options */ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) PRINT_CONFIG_VAR(NAVIGATION_FREQUENCY) diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index ea95ecd386..6a22fcb5b8 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -57,6 +57,9 @@ uint8_t fbw_mode; #include "inter_mcu.h" +#ifdef SITL +#include "nps_autopilot_fixedwing.h" +#endif /** Trim commands for roll and pitch/ */ diff --git a/sw/simulator/nps/nps_autopilot_fixedwing.c b/sw/simulator/nps/nps_autopilot_fixedwing.c new file mode 100644 index 0000000000..149091828f --- /dev/null +++ b/sw/simulator/nps/nps_autopilot_fixedwing.c @@ -0,0 +1,143 @@ +/* + * Copyright (C) 2009 Antoine Drouin + * Copyright (C) 2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "nps_autopilot_fixedwing.h" + +//#include "firmwares/rotorcraft/main.h" +/////// #include "firmwares/fixedwing/main.h" +#include "firmwares/fixedwing/main_fbw.h" +#include "firmwares/fixedwing/main_ap.h" +#include "nps_sensors.h" +#include "nps_radio_control.h" +#include "subsystems/radio_control.h" +#include "subsystems/imu.h" +#include "subsystems/sensors/baro.h" +#include "baro_board.h" +#include "subsystems/electrical.h" +#include "mcu_periph/sys_time.h" +#include "state.h" + +//#include "subsystems/actuators/motor_mixing.h" + + +struct NpsAutopilot autopilot; +bool_t nps_bypass_ahrs; + +#ifndef NPS_BYPASS_AHRS +#define NPS_BYPASS_AHRS FALSE +#endif + +#if !defined (FBW) || !defined (AP) +#error NPS does not currently support dual processor simulation for FBW and AP on fixedwing! +#endif + +void nps_autopilot_init(enum NpsRadioControlType type_rc, int num_rc_script, char* rc_dev) { + + nps_radio_control_init(type_rc, num_rc_script, rc_dev); + nps_bypass_ahrs = NPS_BYPASS_AHRS; + + //main_init(); + init_fbw(); + init_ap(); + + +#ifdef MAX_BAT_LEVEL + electrical.vsupply = MAX_BAT_LEVEL * 10; +#else + electrical.vsupply = 111; +#endif + +} + +void nps_autopilot_run_systime_step( void ) { + sys_tick_handler(); +} + +#include +#include "subsystems/gps.h" + +void nps_autopilot_run_step(double time __attribute__ ((unused))) { + + if (nps_radio_control_available(time)) { + radio_control_feed(); + //main_event(); + event_task_fbw(); + event_task_ap(); + } + + if (nps_sensors_gyro_available()) { + imu_feed_gyro_accel(); + //main_event(); + event_task_fbw(); + event_task_ap(); + } + + if (nps_sensors_mag_available()) { + imu_feed_mag(); + //main_event(); + event_task_fbw(); + event_task_ap(); + } + + if (nps_sensors_baro_available()) { + baro_feed_value(sensors.baro.value); + //main_event(); + event_task_fbw(); + event_task_ap(); + } + + if (nps_sensors_gps_available()) { + gps_feed_value(); + //main_event(); + event_task_fbw(); + event_task_ap(); + } + + if (nps_bypass_ahrs) { + sim_overwrite_ahrs(); + } + + //handle_periodic_tasks(); + handle_periodic_tasks_fbw(); + handle_periodic_tasks_ap(); + + /* scale final motor commands to 0-1 for feeding the fdm */ + /* FIXME: autopilot.commands is of length NB_COMMANDS instead of number of motors */ + for (uint8_t i=0; i Date: Tue, 2 Jul 2013 22:46:16 +0200 Subject: [PATCH 002/309] [rotorcraft] improve in_flight detection heuristic Simply checks if thrust, speed and acceleration are above a threshold. Does not rely on RC thrust command anymore, but only on actual thrust command. Not tested on real vehicle at all so far... Attempt to improve issue #201 and replaces #468 --- sw/airborne/firmwares/rotorcraft/autopilot.c | 75 ++++++++------------ sw/airborne/firmwares/rotorcraft/autopilot.h | 1 + sw/airborne/firmwares/rotorcraft/main.c | 2 + 3 files changed, 34 insertions(+), 44 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 1652b0b4ed..17d802181f 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -52,7 +52,22 @@ bool_t autopilot_power_switch; bool_t autopilot_detect_ground; bool_t autopilot_detect_ground_once; -#define AUTOPILOT_IN_FLIGHT_TIME 40 +#define AUTOPILOT_IN_FLIGHT_TIME 20 + +/** minimum vertical speed for in_flight condition in m/s */ +#ifndef AUTOPILOT_IN_FLIGHT_MIN_SPEED +#define AUTOPILOT_IN_FLIGHT_MIN_SPEED 0.2 +#endif + +/** minimum vertical acceleration for in_flight condition in m/s^2 */ +#ifndef AUTOPILOT_IN_FLIGHT_MIN_ACCEL +#define AUTOPILOT_IN_FLIGHT_MIN_ACCEL 2.0 +#endif + +/** minimum thrust for in_flight condition in pprz_t units */ +#ifndef AUTOPILOT_IN_FLIGHT_MIN_THRUST +#define AUTOPILOT_IN_FLIGHT_MIN_THRUST 50 +#endif #ifndef AUTOPILOT_DISABLE_AHRS_KILL #include "subsystems/ahrs.h" @@ -97,36 +112,6 @@ void autopilot_init(void) { } -static inline void autopilot_check_in_flight_no_rc( bool_t motors_on ) { - if (autopilot_in_flight) { - if (autopilot_in_flight_counter > 0) { - if (stabilization_cmd[COMMAND_THRUST] == 0) { - autopilot_in_flight_counter--; - if (autopilot_in_flight_counter == 0) { - autopilot_in_flight = FALSE; - } - } - else { /* !THROTTLE_STICK_DOWN */ - autopilot_in_flight_counter = AUTOPILOT_IN_FLIGHT_TIME; - } - } - } - else { /* not in flight */ - if (autopilot_in_flight_counter < AUTOPILOT_IN_FLIGHT_TIME && - motors_on) { - if (stabilization_cmd[COMMAND_THRUST] > 0) { - autopilot_in_flight_counter++; - if (autopilot_in_flight_counter == AUTOPILOT_IN_FLIGHT_TIME) - autopilot_in_flight = TRUE; - } - else { /* THROTTLE_STICK_DOWN */ - autopilot_in_flight_counter = 0; - } - } - } -} - - void autopilot_periodic(void) { RunOnceEvery(NAV_PRESCALER, nav_periodic_task()); @@ -153,10 +138,6 @@ INFO("Using FAILSAFE_GROUND_DETECT") SetRotorcraftCommands(stabilization_cmd, autopilot_in_flight, autopilot_motors_on); } - // when we dont have RC, check in flight by looking at throttle - if (radio_control.status != RC_OK) { - autopilot_check_in_flight_no_rc(autopilot_motors_on); - } } @@ -255,29 +236,37 @@ void autopilot_set_mode(uint8_t new_autopilot_mode) { } -static inline void autopilot_check_in_flight( bool_t motors_on ) { +void autopilot_check_in_flight(bool_t motors_on) { if (autopilot_in_flight) { if (autopilot_in_flight_counter > 0) { - if (THROTTLE_STICK_DOWN()) { + /* probably in_flight if thrust, speed and accel above IN_FLIGHT_MIN thresholds */ + if ((stabilization_cmd[COMMAND_THRUST] <= AUTOPILOT_IN_FLIGHT_MIN_THRUST) && + (abs(stateGetSpeedNed_f()->z) < AUTOPILOT_IN_FLIGHT_MIN_SPEED) && + (abs(stateGetAccelNed_f()->z) < AUTOPILOT_IN_FLIGHT_MIN_ACCEL)) + { autopilot_in_flight_counter--; if (autopilot_in_flight_counter == 0) { autopilot_in_flight = FALSE; } } - else { /* !THROTTLE_STICK_DOWN */ + else { /* thrust, speed or accel not above min threshold, reset counter */ autopilot_in_flight_counter = AUTOPILOT_IN_FLIGHT_TIME; } } } - else { /* not in flight */ + else { /* currently not in flight */ if (autopilot_in_flight_counter < AUTOPILOT_IN_FLIGHT_TIME && - motors_on) { - if (!THROTTLE_STICK_DOWN()) { + motors_on) + { + /* if thrust above min threshold, assume in_flight. + * Don't check for velocity and acceleration above threshold here... + */ + if (stabilization_cmd[COMMAND_THRUST] > AUTOPILOT_IN_FLIGHT_MIN_THRUST) { autopilot_in_flight_counter++; if (autopilot_in_flight_counter == AUTOPILOT_IN_FLIGHT_TIME) autopilot_in_flight = TRUE; } - else { /* THROTTLE_STICK_DOWN */ + else { /* currently not in_flight and thrust below threshold, reset counter */ autopilot_in_flight_counter = 0; } } @@ -330,8 +319,6 @@ void autopilot_on_rc_frame(void) { autopilot_arming_check_motors_on(); kill_throttle = ! autopilot_motors_on; - autopilot_check_in_flight(autopilot_motors_on); - guidance_v_read_rc(); guidance_h_read_rc(autopilot_in_flight); } diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.h b/sw/airborne/firmwares/rotorcraft/autopilot.h index 7e874ef0f3..d970b9aba7 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot.h @@ -67,6 +67,7 @@ extern void autopilot_periodic(void); extern void autopilot_on_rc_frame(void); extern void autopilot_set_mode(uint8_t new_autopilot_mode); extern void autopilot_set_motors_on(bool_t motors_on); +extern void autopilot_check_in_flight(bool_t motors_on); extern bool_t autopilot_detect_ground; extern bool_t autopilot_detect_ground_once; diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 544073e355..5ba12b51c7 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -233,6 +233,8 @@ STATIC_INLINE void failsafe_check( void ) { autopilot_set_mode(AP_MODE_FAILSAFE); } #endif + + autopilot_check_in_flight(autopilot_motors_on); } STATIC_INLINE void main_event( void ) { From e160b739388c44d1c83ee18b7c233cd01259d6ad Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Sat, 13 Jul 2013 16:16:18 -0600 Subject: [PATCH 003/309] [nps] A few more NPS for FW updates * tweaked FBW for USE_NPS, not SITL * Better support for AP or FBW or both * added start of a subsystem makefile --- .../subsystems/fixedwing/fdm_jsbsim.makefile | 135 ++++++++++++++++++ sw/airborne/firmwares/fixedwing/main_fbw.c | 2 +- sw/simulator/nps/nps_autopilot_fixedwing.c | 43 ++++-- 3 files changed, 164 insertions(+), 16 deletions(-) create mode 100644 conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile diff --git a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile new file mode 100644 index 0000000000..b45b49c090 --- /dev/null +++ b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile @@ -0,0 +1,135 @@ +# Hey Emacs, this is a -*- makefile -*- + +# +# SITL Simulator +# + +JSBSIM_ROOT ?= /opt/jsbsim +JSBSIM_INC = $(JSBSIM_ROOT)/include/JSBSim +JSBSIM_LIB = $(JSBSIM_ROOT)/lib + +SRC_FIRMWARE=firmwares/fixedwing + +SRC_BOARD=boards/$(BOARD) + +NPSDIR = $(SIMDIR)/nps + + +nps.ARCHDIR = sim + +# include Makefile.nps instead of Makefile.sim +nps.MAKEFILE = nps + +nps.CFLAGS += -DSITL -DUSE_NPS +nps.CFLAGS += $(shell pkg-config glib-2.0 --cflags) +nps.LDFLAGS += $(shell pkg-config glib-2.0 --libs) -lm -lglibivy -lpcre -lgsl -lgslcblas +nps.CFLAGS += -I$(NPSDIR) -I$(SRC_FIRMWARE) -I$(SRC_BOARD) -I../simulator -I$(PAPARAZZI_HOME)/conf/simulator/nps +nps.LDFLAGS += $(shell sdl-config --libs) + +# use the paparazzi-jsbsim package if it is installed, otherwise look for JSBsim under /opt/jsbsim +JSBSIM_PKG ?= $(shell pkg-config JSBSim --exists && echo 'yes') +ifeq ($(JSBSIM_PKG), yes) + nps.CFLAGS += $(shell pkg-config JSBSim --cflags) + nps.LDFLAGS += $(shell pkg-config JSBSim --libs) +else + JSBSIM_PKG = no + nps.CFLAGS += -I$(JSBSIM_INC) + nps.LDFLAGS += -L$(JSBSIM_LIB) -lJSBSim +endif + + +nps.srcs += $(NPSDIR)/nps_main.c \ + $(NPSDIR)/nps_fdm_jsbsim.c \ + $(NPSDIR)/nps_random.c \ + $(NPSDIR)/nps_sensors.c \ + $(NPSDIR)/nps_sensors_utils.c \ + $(NPSDIR)/nps_sensor_gyro.c \ + $(NPSDIR)/nps_sensor_accel.c \ + $(NPSDIR)/nps_sensor_mag.c \ + $(NPSDIR)/nps_sensor_baro.c \ + $(NPSDIR)/nps_sensor_gps.c \ + $(NPSDIR)/nps_radio_control.c \ + $(NPSDIR)/nps_radio_control_joystick.c \ + $(NPSDIR)/nps_radio_control_spektrum.c \ + $(NPSDIR)/nps_autopilot_fixedwing.c \ + $(NPSDIR)/nps_ivy.c \ + $(NPSDIR)/nps_flightgear.c \ + + + +nps.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) -DPERIPHERALS_AUTO_INIT + +nps.srcs += firmwares/fixedwing/main_ap.c firmwares/fixedwing/main_fbw.c +nps.srcs += mcu.c +nps.srcs += $(SRC_ARCH)/mcu_arch.c + +nps.srcs += mcu_periph/i2c.c +nps.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c + + +PERIODIC_FREQUENCY ?= 60 +TELEMETRY_FREQUENCY ?= 60 +nps.CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY) +nps.CFLAGS += -DTELEMETRY_FREQUENCY=$(TELEMETRY_FREQUENCY) +#nps.CFLAGS += -DUSE_LED +nps.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c + +nps.srcs += subsystems/settings.c +nps.srcs += $(SRC_ARCH)/subsystems/settings_arch.c + +nps.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=IvyTransport +nps.srcs += $(SRC_FIRMWARE)/telemetry.c \ + subsystems/datalink/downlink.c \ + $(SRC_ARCH)/ivy_transport.c + +nps.srcs += subsystems/actuators.c +nps.srcs += subsystems/commands.c + +nps.srcs += $(SRC_FIRMWARE)/datalink.c + +# +# Math functions +# +nps.srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c math/pprz_trig_int.c math/pprz_orientation_conversion.c + +nps.CFLAGS += -DROTORCRAFT_BARO_LED=2 +nps.srcs += $(SRC_BOARD)/baro_board.c + +nps.CFLAGS += -DUSE_ADC +nps.srcs += $(SRC_ARCH)/mcu_periph/adc_arch.c +nps.srcs += subsystems/electrical.c + +nps.srcs += $(SRC_FIRMWARE)/autopilot.c + +nps.srcs += state.c + +# +# in makefile section of airframe xml +# include $(CFG_BOOZ)/subsystems/booz2_ahrs_lkf.makefile +# or +# include $(CFG_BOOZ)/subsystems/booz2_ahrs_cmpl.makefile +# + +# nps.srcs += $(SRC_FIRMWARE)/stabilization.c +# nps.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_rate.c +# nps.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_none.c + +# nps.CFLAGS += -DUSE_NAVIGATION +# nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_h.c +# nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_h_ref.c +# nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v.c +# nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_ref.c + +# +# INS choice +# +# include subsystems/rotorcraft/ins.makefile +# or +# include subsystems/rotorcraft/ins_extended.makefile +# +# extra: +# include subsystems/rotorcraft/ins_hff.makefile +# + +nps.srcs += $(SRC_FIRMWARE)/navigation.c +nps.srcs += $(SRC_SUBSYSTEMS)/navigation/common_flight_plan.c diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 6a22fcb5b8..1c104c958b 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -57,7 +57,7 @@ uint8_t fbw_mode; #include "inter_mcu.h" -#ifdef SITL +#ifdef USE_NPS #include "nps_autopilot_fixedwing.h" #endif diff --git a/sw/simulator/nps/nps_autopilot_fixedwing.c b/sw/simulator/nps/nps_autopilot_fixedwing.c index 149091828f..340eeb97eb 100644 --- a/sw/simulator/nps/nps_autopilot_fixedwing.c +++ b/sw/simulator/nps/nps_autopilot_fixedwing.c @@ -23,9 +23,21 @@ #include "nps_autopilot_fixedwing.h" //#include "firmwares/rotorcraft/main.h" -/////// #include "firmwares/fixedwing/main.h" + +#ifdef FBW #include "firmwares/fixedwing/main_fbw.h" +#define Fbw(f) f ## _fbw() +#else +#define Fbw(f) +#endif + +#ifdef AP #include "firmwares/fixedwing/main_ap.h" +#define Ap(f) f ## _ap() +#else +#define Ap(f) +#endif + #include "nps_sensors.h" #include "nps_radio_control.h" #include "subsystems/radio_control.h" @@ -56,8 +68,8 @@ void nps_autopilot_init(enum NpsRadioControlType type_rc, int num_rc_script, cha nps_bypass_ahrs = NPS_BYPASS_AHRS; //main_init(); - init_fbw(); - init_ap(); + Fbw(init); + Ap(init); #ifdef MAX_BAT_LEVEL @@ -80,36 +92,36 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { if (nps_radio_control_available(time)) { radio_control_feed(); //main_event(); - event_task_fbw(); - event_task_ap(); + Fbw(event_task); + Ap(event_task); } if (nps_sensors_gyro_available()) { imu_feed_gyro_accel(); //main_event(); - event_task_fbw(); - event_task_ap(); + Fbw(event_task); + Ap(event_task); } if (nps_sensors_mag_available()) { imu_feed_mag(); //main_event(); - event_task_fbw(); - event_task_ap(); + Fbw(event_task); + Ap(event_task); } if (nps_sensors_baro_available()) { baro_feed_value(sensors.baro.value); //main_event(); - event_task_fbw(); - event_task_ap(); + Fbw(event_task); + Ap(event_task); } if (nps_sensors_gps_available()) { gps_feed_value(); //main_event(); - event_task_fbw(); - event_task_ap(); + Fbw(event_task); + Ap(event_task); } if (nps_bypass_ahrs) { @@ -117,11 +129,12 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { } //handle_periodic_tasks(); - handle_periodic_tasks_fbw(); - handle_periodic_tasks_ap(); + Fbw(handle_periodic_tasks); + Ap(handle_periodic_tasks); /* scale final motor commands to 0-1 for feeding the fdm */ /* FIXME: autopilot.commands is of length NB_COMMANDS instead of number of motors */ + /***************** HOW TO HANDLE THIS FOR FW ********************/ for (uint8_t i=0; i Date: Mon, 15 Jul 2013 21:13:08 +0200 Subject: [PATCH 004/309] [fixedwing] energy_ctrl: don't keywords reserved in c++ --- sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c b/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c index 3f07c7b0ac..fa2b328e49 100644 --- a/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c +++ b/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c @@ -162,9 +162,9 @@ float ac_char_cruise_throttle = 0.0f; float ac_char_cruise_pitch = 0.0f; int ac_char_cruise_count = 0; -static void ac_char_average(float* last, float new, int count) +static void ac_char_average(float* last_v, float new_v, int count) { - *last = (((*last) * (((float)count) - 1.0f)) + new) / ((float) count); + *last_v = (((*last_v) * (((float)count) - 1.0f)) + new_v) / ((float) count); } static void ac_char_update(float throttle, float pitch, float climb, float accelerate) From 97d81cf4371ea7f395352a0258557b6e50fafb45 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 15 Jul 2013 21:14:19 +0200 Subject: [PATCH 005/309] [modules] light only for ap --- conf/modules/light.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/modules/light.xml b/conf/modules/light.xml index 33cfd74154..5761db11f1 100644 --- a/conf/modules/light.xml +++ b/conf/modules/light.xml @@ -15,7 +15,7 @@ - + - diff --git a/conf/airframes/esden/gain_scheduling_example.xml b/conf/airframes/esden/gain_scheduling_example.xml index e9491e181a..b38357f11f 100644 --- a/conf/airframes/esden/gain_scheduling_example.xml +++ b/conf/airframes/esden/gain_scheduling_example.xml @@ -233,7 +233,7 @@ - diff --git a/conf/airframes/esden/hexy_ll11a2pwm.xml b/conf/airframes/esden/hexy_ll11a2pwm.xml index 6ae1d2b368..f3705ebc95 100644 --- a/conf/airframes/esden/hexy_ll11a2pwm.xml +++ b/conf/airframes/esden/hexy_ll11a2pwm.xml @@ -244,7 +244,7 @@ - diff --git a/conf/airframes/esden/hexy_lm2a2pwm.xml b/conf/airframes/esden/hexy_lm2a2pwm.xml index 00cf6e1bcc..c900b0e7ae 100644 --- a/conf/airframes/esden/hexy_lm2a2pwm.xml +++ b/conf/airframes/esden/hexy_lm2a2pwm.xml @@ -205,7 +205,7 @@ - diff --git a/conf/airframes/esden/lisa2_hex.xml b/conf/airframes/esden/lisa2_hex.xml index 41d1d67104..f17936a89a 100644 --- a/conf/airframes/esden/lisa2_hex.xml +++ b/conf/airframes/esden/lisa2_hex.xml @@ -220,7 +220,7 @@ - diff --git a/conf/airframes/esden/qs_asp22.xml b/conf/airframes/esden/qs_asp22.xml index 671309a1a6..f47a8715d1 100644 --- a/conf/airframes/esden/qs_asp22.xml +++ b/conf/airframes/esden/qs_asp22.xml @@ -244,7 +244,7 @@ - diff --git a/conf/airframes/esden/quady_ll11a2pwm.xml b/conf/airframes/esden/quady_ll11a2pwm.xml index 368bdb9a9e..3e39b0575e 100644 --- a/conf/airframes/esden/quady_ll11a2pwm.xml +++ b/conf/airframes/esden/quady_ll11a2pwm.xml @@ -239,7 +239,7 @@ - diff --git a/conf/airframes/esden/quady_lm1a1pwm.xml b/conf/airframes/esden/quady_lm1a1pwm.xml index 3ce579cf50..99a2840dbd 100644 --- a/conf/airframes/esden/quady_lm1a1pwm.xml +++ b/conf/airframes/esden/quady_lm1a1pwm.xml @@ -200,7 +200,7 @@ - diff --git a/conf/airframes/esden/quady_lm2a2pwm.xml b/conf/airframes/esden/quady_lm2a2pwm.xml index 6be1758980..bebf1bd2d6 100644 --- a/conf/airframes/esden/quady_lm2a2pwm.xml +++ b/conf/airframes/esden/quady_lm2a2pwm.xml @@ -207,7 +207,7 @@ - diff --git a/conf/airframes/esden/quady_lm2a2pwmppm.xml b/conf/airframes/esden/quady_lm2a2pwmppm.xml index 298bcc8244..3c97b2ad2f 100644 --- a/conf/airframes/esden/quady_lm2a2pwmppm.xml +++ b/conf/airframes/esden/quady_lm2a2pwmppm.xml @@ -202,7 +202,7 @@ - diff --git a/conf/airframes/examples/booz2.xml b/conf/airframes/examples/booz2.xml index 36ceee5817..dca8389581 100644 --- a/conf/airframes/examples/booz2.xml +++ b/conf/airframes/examples/booz2.xml @@ -210,7 +210,7 @@ - + diff --git a/conf/airframes/examples/h_hex.xml b/conf/airframes/examples/h_hex.xml index ca779e54ce..5faaedebe3 100644 --- a/conf/airframes/examples/h_hex.xml +++ b/conf/airframes/examples/h_hex.xml @@ -189,7 +189,7 @@ - + diff --git a/conf/airframes/examples/lisa_asctec.xml b/conf/airframes/examples/lisa_asctec.xml index 8b72be5c70..75f60ddfdf 100644 --- a/conf/airframes/examples/lisa_asctec.xml +++ b/conf/airframes/examples/lisa_asctec.xml @@ -207,7 +207,7 @@ - + diff --git a/conf/airframes/examples/quadrotor_navgo.xml b/conf/airframes/examples/quadrotor_navgo.xml index fe108b4d6f..143f5fb701 100644 --- a/conf/airframes/examples/quadrotor_navgo.xml +++ b/conf/airframes/examples/quadrotor_navgo.xml @@ -33,7 +33,7 @@ - + diff --git a/conf/airframes/obsolete/ENAC/mkk1.xml b/conf/airframes/obsolete/ENAC/mkk1.xml index 9633595152..18a9742bc7 100644 --- a/conf/airframes/obsolete/ENAC/mkk1.xml +++ b/conf/airframes/obsolete/ENAC/mkk1.xml @@ -16,7 +16,7 @@ - + diff --git a/conf/airframes/obsolete/ENAC/nova1.xml b/conf/airframes/obsolete/ENAC/nova1.xml index f3a066a809..0ef106ba39 100644 --- a/conf/airframes/obsolete/ENAC/nova1.xml +++ b/conf/airframes/obsolete/ENAC/nova1.xml @@ -15,7 +15,7 @@ - + diff --git a/conf/airframes/obsolete/Poine/booz2_a1.xml b/conf/airframes/obsolete/Poine/booz2_a1.xml index 269bd6da8d..8d66978f1b 100644 --- a/conf/airframes/obsolete/Poine/booz2_a1.xml +++ b/conf/airframes/obsolete/Poine/booz2_a1.xml @@ -204,7 +204,7 @@ - + diff --git a/conf/airframes/obsolete/Poine/booz2_a7.xml b/conf/airframes/obsolete/Poine/booz2_a7.xml index 905a6d4d2a..59f3bb2082 100644 --- a/conf/airframes/obsolete/Poine/booz2_a7.xml +++ b/conf/airframes/obsolete/Poine/booz2_a7.xml @@ -231,7 +231,7 @@ - + diff --git a/conf/airframes/obsolete/Poine/h_hex.xml b/conf/airframes/obsolete/Poine/h_hex.xml index b76881c9fa..252cdacf33 100644 --- a/conf/airframes/obsolete/Poine/h_hex.xml +++ b/conf/airframes/obsolete/Poine/h_hex.xml @@ -168,7 +168,7 @@ - + diff --git a/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml b/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml index a79cea2d5c..4061167138 100644 --- a/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml +++ b/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml @@ -291,7 +291,7 @@ second attempt - + diff --git a/conf/airframes/obsolete/UofAdelaide/A1000_LISA.xml b/conf/airframes/obsolete/UofAdelaide/A1000_LISA.xml index ebd6bd5bbe..5f3ee2a945 100644 --- a/conf/airframes/obsolete/UofAdelaide/A1000_LISA.xml +++ b/conf/airframes/obsolete/UofAdelaide/A1000_LISA.xml @@ -200,7 +200,7 @@ - + diff --git a/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml b/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml index 5d38914b96..564e7dbcc4 100644 --- a/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml +++ b/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml @@ -249,7 +249,7 @@ - + diff --git a/conf/airframes/obsolete/example_heli_lisam.xml b/conf/airframes/obsolete/example_heli_lisam.xml index 6ed0bf3d66..e3dbdfd842 100644 --- a/conf/airframes/obsolete/example_heli_lisam.xml +++ b/conf/airframes/obsolete/example_heli_lisam.xml @@ -252,7 +252,7 @@ AP_MODE_NAV - + diff --git a/conf/airframes/obsolete/mm/rotor/qmk1.xml b/conf/airframes/obsolete/mm/rotor/qmk1.xml index 7d561384d0..8066ee667d 100644 --- a/conf/airframes/obsolete/mm/rotor/qmk1.xml +++ b/conf/airframes/obsolete/mm/rotor/qmk1.xml @@ -200,7 +200,7 @@ - + From 08c9baf84745ca68d369232a0f89c3c21df8b84a Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 25 Jul 2013 17:05:41 +0200 Subject: [PATCH 013/309] [airframe] add new airframe for Quark plane --- conf/airframes/ENAC/fixed-wing/quark1.xml | 219 ++++++++++++++++++++++ 1 file changed, 219 insertions(+) create mode 100644 conf/airframes/ENAC/fixed-wing/quark1.xml diff --git a/conf/airframes/ENAC/fixed-wing/quark1.xml b/conf/airframes/ENAC/fixed-wing/quark1.xml new file mode 100644 index 0000000000..10dfc81fe2 --- /dev/null +++ b/conf/airframes/ENAC/fixed-wing/quark1.xml @@ -0,0 +1,219 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + +
+ +
+ + + +
+ +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + +
+ +
+ +
+ +
From 69b1ae38ce46ba5ef3c15cdadc6c0b23eb59a008 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 25 Jul 2013 22:25:58 +0200 Subject: [PATCH 014/309] [dox] nicer doxygen formatting for pprz_transport --- .../subsystems/datalink/pprz_transport.h | 21 ++++++++++++------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/sw/airborne/subsystems/datalink/pprz_transport.h b/sw/airborne/subsystems/datalink/pprz_transport.h index 10138a0726..502d54ebce 100644 --- a/sw/airborne/subsystems/datalink/pprz_transport.h +++ b/sw/airborne/subsystems/datalink/pprz_transport.h @@ -20,17 +20,22 @@ * */ -/** \file pprz_transport.h - * \brief Building and parsing Paparazzi frames +/** + * @file subsystems/datalink/pprz_transport.h * - * Pprz frame: + * Building and parsing Paparazzi frames. * - * |STX|length|... payload=(length-4) bytes ...|Checksum A|Checksum B| + * Pprz frame: * - * where checksum is computed over length and payload: - * ck_A = ck_B = length - * for each byte b in payload - * ck_A += b; ck_b += ck_A + * |STX|length|... payload=(length-4) bytes ...|Checksum A|Checksum B| + * + * where checksum is computed over length and payload: + * @code + * ck_A = ck_B = length + * for each byte b in payload + * ck_A += b; + * ck_b += ck_A; + * @endcode */ #ifndef PPRZ_TRANSPORT_H From 97461555cf6eacdc0882b373d8974efa10fe4285 Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Thu, 25 Jul 2013 16:36:17 -0600 Subject: [PATCH 015/309] [dfu] Improved progress bar during programming --- sw/tools/dfu/stm32_mem.py | 27 ++++++++++++++++++++++++--- 1 file changed, 24 insertions(+), 3 deletions(-) diff --git a/sw/tools/dfu/stm32_mem.py b/sw/tools/dfu/stm32_mem.py index d6da3e6831..48418433f2 100644 --- a/sw/tools/dfu/stm32_mem.py +++ b/sw/tools/dfu/stm32_mem.py @@ -76,6 +76,21 @@ def print_copyright(): print("License GPLv3+: GNU GPL version 3 or later ") print("") +def init_progress_bar(): + max_symbols = 50 + print("[0%" + "="*int(max_symbols/2 - 4) + "50%" + "="*int(max_symbols/2 - 4) + "100%]") + print(" ", end="") + update_progress_bar.count = 0 + update_progress_bar.symbol_limit = max_symbols + +def update_progress_bar(completed, total): + if completed and total: + percent = 100 * (float(completed)/float(total)) + if (percent >= (update_progress_bar.count + (100.0 / update_progress_bar.symbol_limit))): + update_progress_bar.count += (100.0 / update_progress_bar.symbol_limit) + print("#", end="") + stdout.flush() + if __name__ == "__main__": usage = "Usage: %prog [options] firmware.bin" + "\n" + "Run %prog --help to list the options." parser = OptionParser(usage, version='%prog version 1.3') @@ -193,20 +208,26 @@ if __name__ == "__main__": print("Could not open binary file.") raise + # Get the file length for progress bar + bin_length = len(bin) + #addr = APP_ADDRESS addr = options.addr print ("Programming memory from 0x%08X...\r" % addr) + init_progress_bar() + while bin: -# print("Programming memory at 0x%08X\r" % addr), - print('#', end="") - stdout.flush() + update_progress_bar((addr - options.addr),bin_length) stm32_erase(target, addr) stm32_write(target, bin[:SECTOR_SIZE]) bin = bin[SECTOR_SIZE:] addr += SECTOR_SIZE + # Need to check all the way to 100% complete + update_progress_bar((addr - options.addr),bin_length) + stm32_manifest(target) print("\nAll operations complete!\n") From 081079bc7295196f2c4d90014111d0bd07281c7f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 26 Jul 2013 00:48:56 +0200 Subject: [PATCH 016/309] [boards] krooz_sd: fix I2C1_GPIO_SDA pin --- sw/airborne/boards/krooz_sd.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/boards/krooz_sd.h b/sw/airborne/boards/krooz_sd.h index dc24cbda4a..1ecd270753 100644 --- a/sw/airborne/boards/krooz_sd.h +++ b/sw/airborne/boards/krooz_sd.h @@ -126,7 +126,7 @@ /* I2C mapping */ #define I2C1_GPIO_PORT GPIOB #define I2C1_GPIO_SCL GPIO8 -#define I2C1_GPIO_SDA GPIO7 +#define I2C1_GPIO_SDA GPIO9 #define I2C2_GPIO_PORT GPIOB #define I2C2_GPIO_SCL GPIO10 From 8c698d7138e753b427bf7afa85e61c674c5f5c9e Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 26 Jul 2013 01:12:10 +0200 Subject: [PATCH 017/309] [i2c] fix i2c3 compilation --- sw/airborne/arch/stm32/mcu_periph/i2c_arch.c | 16 ++++++++-------- sw/airborne/mcu_periph/i2c.c | 13 +++++++++++++ 2 files changed, 21 insertions(+), 8 deletions(-) diff --git a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c index 902d915759..046f0c9441 100644 --- a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c @@ -1090,17 +1090,17 @@ void i2c3_hw_init(void) { /* Enable I2C3 clock */ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_I2C3EN); /* Enable GPIO clock */ - gpio_enable_clock(I2C3_GPIO_SCL_PORT); - gpio_mode_setup(I2C3_GPIO_SCL_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, I2C3_GPIO_SCL); - gpio_set_output_options(I2C3_GPIO_SCL_PORT, GPIO_OTYPE_OD, GPIO_OSPEED_25MHZ, + gpio_enable_clock(I2C3_GPIO_PORT_SCL); + gpio_mode_setup(I2C3_GPIO_PORT_SCL, GPIO_MODE_AF, GPIO_PUPD_NONE, I2C3_GPIO_SCL); + gpio_set_output_options(I2C3_GPIO_PORT_SCL, GPIO_OTYPE_OD, GPIO_OSPEED_25MHZ, I2C3_GPIO_SCL); - gpio_set_af(I2C3_GPIO_SCL_PORT, GPIO_AF4, I2C3_GPIO_SCL); + gpio_set_af(I2C3_GPIO_PORT_SCL, GPIO_AF4, I2C3_GPIO_SCL); - gpio_enable_clock(I2C3_GPIO_SDA_PORT); - gpio_mode_setup(I2C3_GPIO_SDA_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, I2C3_GPIO_SDA); - gpio_set_output_options(I2C3_GPIO_SDA_PORT, GPIO_OTYPE_OD, GPIO_OSPEED_25MHZ, + gpio_enable_clock(I2C3_GPIO_PORT_SDA); + gpio_mode_setup(I2C3_GPIO_PORT_SDA, GPIO_MODE_AF, GPIO_PUPD_NONE, I2C3_GPIO_SDA); + gpio_set_output_options(I2C3_GPIO_PORT_SDA, GPIO_OTYPE_OD, GPIO_OSPEED_25MHZ, I2C3_GPIO_SDA); - gpio_set_af(I2C3_GPIO_SDA_PORT, GPIO_AF4, I2C3_GPIO_SDA); + gpio_set_af(I2C3_GPIO_PORT_SDA, GPIO_AF4, I2C3_GPIO_SDA); i2c_reset(I2C3); diff --git a/sw/airborne/mcu_periph/i2c.c b/sw/airborne/mcu_periph/i2c.c index 897278d41c..15dca0d1e5 100644 --- a/sw/airborne/mcu_periph/i2c.c +++ b/sw/airborne/mcu_periph/i2c.c @@ -62,6 +62,19 @@ void i2c2_init(void) { #endif /* USE_I2C2 */ + +#ifdef USE_I2C3 + +struct i2c_periph i2c3; + +void i2c3_init(void) { + i2c_init(&i2c3); + i2c3_hw_init(); +} + +#endif /* USE_I2C2 */ + + void i2c_init(struct i2c_periph* p) { p->trans_insert_idx = 0; p->trans_extract_idx = 0; From a9044e18f0535eaa3aae7ca292c9e4d4c32dc1f3 Mon Sep 17 00:00:00 2001 From: softsr Date: Fri, 26 Jul 2013 00:55:15 +0200 Subject: [PATCH 018/309] [modules] add max7456 osd module --- conf/modules/osd_max7456.xml | 28 ++ sw/airborne/modules/max7456/max7456.c | 444 +++++++++++++++++++++ sw/airborne/modules/max7456/max7456.h | 35 ++ sw/airborne/modules/max7456/max7456_regs.h | 108 +++++ 4 files changed, 615 insertions(+) create mode 100644 conf/modules/osd_max7456.xml create mode 100644 sw/airborne/modules/max7456/max7456.c create mode 100644 sw/airborne/modules/max7456/max7456.h create mode 100755 sw/airborne/modules/max7456/max7456_regs.h diff --git a/conf/modules/osd_max7456.xml b/conf/modules/osd_max7456.xml new file mode 100644 index 0000000000..7b54b9679a --- /dev/null +++ b/conf/modules/osd_max7456.xml @@ -0,0 +1,28 @@ + + + + + MAX7456 driver (SPI) + +
+ +
+ + + + + + include $(CFG_SHARED)/spi_master.makefile + + + + + + + + + + +
+ + diff --git a/sw/airborne/modules/max7456/max7456.c b/sw/airborne/modules/max7456/max7456.c new file mode 100644 index 0000000000..c022b4eb16 --- /dev/null +++ b/sw/airborne/modules/max7456/max7456.c @@ -0,0 +1,444 @@ +/* + * Copyright (C) 2013 Chris + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file modules/max7456/max7456.c + * Maxim MAX7456 single-channel monochrome on-screen display driver. + * + */ + +#include "std.h" +#include "stdio.h" + +#include "mcu_periph/sys_time.h" +#include "mcu_periph/gpio.h" +#include "mcu_periph/spi.h" +#include "led.h" +#include "autopilot.h" + +#include "subsystems/nav.h" +#include "generated/flight_plan.h" +#include "generated/airframe.h" +#include "subsystems/datalink/datalink.h" +#include "subsystems/electrical.h" + +#include "messages.h" +#include "subsystems/datalink/downlink.h" +#include "state.h" + +// Peripherials +#include "max7456.h" +#include "max7456_regs.h" + +#define OSD_STRING_SIZE 31 +#define osd_sprintf _osd_sprintf + +static char ascii_to_osd_c( char c); +static void osd_put_s(char *string, uint8_t attributes, uint8_t char_nb, uint8_t row, uint8_t column); +static bool_t _osd_sprintf(char* buffer, char* string, float value); + +struct spi_transaction max7456_trans; + +uint8_t osd_spi_tx_buffer[2]; +uint8_t osd_spi_rx_buffer[2]; +char osd_string[OSD_STRING_SIZE]; +char osd_str_buf[OSD_STRING_SIZE]; +char osd_char = ' '; +uint8_t step = 0; +uint16_t osd_char_address = 0; +uint8_t osd_attr = FALSE; + +enum max7456_osd_status_codes { + OSD_UNINIT, + OSD_INIT1, + OSD_INIT2, + OSD_INIT3, + OSD_INIT4, + OSD_READ_STATUS, + OSD_IDLE, + OSD_S_STEP1, + OSD_S_STEP2, + OSD_S_STEP3, + OSD_FINISHED, +}; + +enum osd_attributes{ + BLINK = OSD_BLINK_CHAR, + INVERT = OSD_INVERT_PIXELS, +}; + +uint8_t max7456_osd_status = OSD_UNINIT; +uint8_t osd_enable = TRUE; +uint8_t osd_enable_val = OSD_IMAGE_ENABLE; +uint8_t osd_stat_reg = 0; +bool_t osd_stat_reg_valid = FALSE; + +void max7456_init(void) { + + max7456_trans.slave_idx = MAX7456_SLAVE_IDX; + max7456_trans.select = SPISelectUnselect; + max7456_trans.cpol = SPICpolIdleLow; + max7456_trans.cpha = SPICphaEdge1; + max7456_trans.dss = SPIDss8bit; + max7456_trans.bitorder = SPIMSBFirst; + max7456_trans.cdiv = SPIDiv64; + max7456_trans.output_length = sizeof(osd_spi_tx_buffer); + max7456_trans.output_buf = (uint8_t*) osd_spi_tx_buffer; + max7456_trans.input_length = 0; + max7456_trans.input_buf = (uint8_t*)osd_spi_rx_buffer; + max7456_trans.before_cb = NULL; + max7456_trans.after_cb = NULL; + + osd_enable = 1; + osd_enable_val = OSD_IMAGE_ENABLE; + max7456_osd_status = OSD_UNINIT; + + return; +} + +void max7456_periodic(void) { + + float temp = 0; +//This code is executed always and checks if the "osd_enable" var has been changed by telemetry. +//If yes then it commands a reset but this time turns on or off the osd overlay, not the video. + if (max7456_osd_status == OSD_IDLE) { + if(osd_enable > 1) + osd_enable = 1; + if ((osd_enable<<3) != osd_enable_val) { + osd_enable_val = (osd_enable<<3); + max7456_osd_status = OSD_UNINIT; + } + } + + //INITIALIZATION OF THE OSD + if (max7456_osd_status == OSD_UNINIT) { + step = 0; + max7456_trans.status = SPITransDone; + max7456_trans.output_buf[0] = OSD_VM0_REG; + //This operation needs at least 100us but when the periodic function will be invoked again + //sufficient time will have elapsed even with at a periodic frequency of 1000 Hz + max7456_trans.output_buf[1] = OSD_RESET; + max7456_osd_status = OSD_INIT1; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + } + else + if (max7456_osd_status == OSD_INIT2) { + max7456_trans.output_length = 1; + max7456_trans.input_length = 1; + max7456_trans.output_buf[0] = OSD_OSDBL_REG_R; + max7456_osd_status = OSD_INIT3; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + } + else + if (max7456_osd_status == OSD_IDLE && osd_enable > 0) { // DRAW THE OSD SCREEN + //draw_osd(); + switch (step) { + case (0): + osd_put_s("HDG", FALSE, 3, 0, 13); + step = 10; + break; + case (10): + temp = ((float)electrical.vsupply)/10; + osd_sprintf(osd_string, "%.1fV", temp ); + if (temp > LOW_BAT_LEVEL) + osd_put_s(osd_string, FALSE, 8, 0, 2); + else + osd_put_s(osd_string, BLINK|INVERT, 8, 0, 2); + step = 20; + break; + case (20): + #if MAG_HEADING_AVAILABLE && !defined(SITL) + temp = DegOfRad(MAG_Heading); + if (temp < 0) + temp += 360; + #else + temp = DegOfRad(state.h_speed_dir_f); + if (temp < 0) + temp += 360; + #endif + osd_sprintf(osd_string, "%.0f", temp); + osd_put_s(osd_string, FALSE, 8, 1, 13); + step = 30; + break; + case (30): + osd_sprintf(osd_string, "%.0fKm", (state.h_speed_norm_f*3.6)); + osd_put_s(osd_string, FALSE, 8, 0, 24); + step = 40; + break; + case (40): + osd_sprintf(osd_string, "%.0fm", GetPosAlt() ); + osd_put_s(osd_string, FALSE, 10, 13, 2); + step = 50; + break; + case (50): + osd_sprintf(osd_string, "%.1fVZ", stateGetSpeedEnu_f()->z); + osd_put_s(osd_string, FALSE, 7, 13, 24); + step = 10; + break; + default: break; + } + } + return; +} + +void max7456_event(void) { + + static uint8_t x = 0; + + if (max7456_trans.status == SPITransSuccess) { + max7456_trans.status = SPITransDone; + + switch (max7456_osd_status) { + case (OSD_INIT1): + max7456_osd_status = OSD_INIT2; + break; + case (OSD_INIT3): + max7456_trans.output_length = 2; + max7456_trans.input_length = 0; + max7456_trans.output_buf[0] = OSD_OSDBL_REG; + max7456_trans.output_buf[1] = max7456_trans.input_buf[0] & (~(1<<4)); + max7456_osd_status = OSD_INIT4; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + break; + case (OSD_INIT4): + max7456_trans.output_buf[0] = OSD_VM0_REG; +#if USE_PAL_FOR_OSD_VIDEO + max7456_trans.output_buf[1] = OSD_VIDEO_MODE_PAL|osd_enable_val; +#else + max7456_trans.output_buf[1] = osd_enable_val; +#endif + max7456_osd_status = OSD_FINISHED; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + break; + case (OSD_READ_STATUS): + osd_stat_reg = max7456_trans.input_buf[0]; + osd_stat_reg_valid = TRUE; + max7456_osd_status = OSD_FINISHED; + break; + case (OSD_S_STEP1): + max7456_trans.output_length = 2; + max7456_trans.output_buf[0] = OSD_DMAL_REG; + max7456_trans.output_buf[1] = (uint8_t)(osd_char_address); + max7456_osd_status = OSD_S_STEP2; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + break; + case (OSD_S_STEP2): + max7456_trans.output_length = 2; + max7456_trans.output_buf[0] = OSD_DMM_REG; + max7456_trans.output_buf[1] = OSD_AUTO_INCREMENT_MODE | osd_attr; + max7456_osd_status = OSD_S_STEP3; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + x = 0; + break; + case (OSD_S_STEP3): + max7456_trans.output_length = 1; //1 byte tranfers, auto address incrementing. + if (osd_string[x] != 0XFF) { + max7456_trans.output_buf[0] = osd_string[x++]; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + } + else { + max7456_trans.output_buf[0] = 0xFF; //Exit the auto increment mode + max7456_osd_status = OSD_FINISHED; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + } + break; + case (OSD_FINISHED): + osd_attr = 0; + max7456_trans.status = SPITransDone; + max7456_osd_status = OSD_IDLE; + break; + default: break; + } + } + return; +} + +static char ascii_to_osd_c(char c) { + + if (c >= '0' && c <= '9') { + if (c == '0') + c -= 38; + else + c -= 48; + } + else { + if (c >= 'A' && c <= 'Z') + c -= 54; + else { + if (c >= 'a' && c <= 'z') + c -= 60; + else { + switch (c) { + case('('): c = 0x3f; break; + case(')'): c = 0x40; break; + case('.'): c = 0x41; break; + case('?'): c = 0x42; break; + case(';'): c = 0x43; break; + case(':'): c = 0x44; break; + case(','): c = 0x45; break; + //case('''): c = 0x46; break; + case('/'): c = 0x47; break; + case('"'): c = 0x48; break; + case('-'): c = 0x49; break; + case('<'): c = 0x4A; break; + case('>'): c = 0x4B; break; + case('@'): c = 0x4C; break; + case(' '): c = 0x00; break; + case('\0'): c = 0xFF; break; + default : break; + } + } + } + } + return(c); +} + +static void osd_put_s(char *string, uint8_t attributes, uint8_t char_nb, uint8_t row, uint8_t column){ + + uint8_t x=0; + + if (row > 15) + column = 15; + if (column > 29) + column = 29; + osd_char_address = ((uint16_t)row*30) + column; + + // translate the string and put it to the "osd_string" '\0' = 0xff + x = 0; + while (*(string+x) != '\0') { + osd_string[x] = ascii_to_osd_c(*(string+x)); + x++; + } + osd_string[x] = ascii_to_osd_c(*(string+x)); + + for (x=0; x < sizeof(osd_string); x++) { + if(osd_string[x] == 0xff) + break; + } + + //Adjust for the reserved character number. + for (; x< char_nb; x++) { + osd_string[x] = 0; + } + osd_string[x] = 0xff; + + osd_attr = attributes; + + //TRIGGER THE SPI TRANSFERS. The rest of the spi transfers occur in the "max7456_event" function. + if (max7456_osd_status == OSD_IDLE){ + max7456_trans.output_length = 2; + max7456_trans.output_buf[0] = OSD_DMAH_REG; + max7456_trans.output_buf[1] = (uint8_t)((osd_char_address>>8) & 0x0001); + max7456_osd_status = OSD_S_STEP1; + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + } + return; +} + +// A VERY VERY STRIPED DOWN sprintf function suitable only for the paparazzi OSD. +static bool_t _osd_sprintf(char* buffer, char* string, float value) { + + uint8_t param_start = 0; + uint8_t param_end = 0; + uint8_t frac_nb = 0; + uint8_t digit = 0; + uint8_t x = 0, y = 0, z = 0; + + uint16_t i_dec = 0; + uint16_t i_frac = 0; + + char to_asc[10] = {48,48,48,48,48,48,48,48,48,48}; + + // Clear the osd string. + for (x=0; x < sizeof(osd_string); x++) { + osd_string[x] = 0; + } + x = 0; + // Search for the prameter start and stop positions. + while (*(string+x) != '\0'){ + if (*(string+x) == '%'){ + param_start = x; + } + else + if (*(string+x) == 'f') { + param_end = x; + break; + } + x++; + } + // find and bound the precision specified. + frac_nb = *(string+param_end-1) - 48; // Convert to number, ASCII 48 = '0' + if(frac_nb > 3) { + frac_nb = 3; // Bound value. + } + y = (sizeof(to_asc)- 1); // Point y to the end of the array. + i_dec = abs((int16_t)value); + // Fist we will deal with the fractional part if specified. + if (frac_nb > 0 && frac_nb <= 3) { + i_frac = abs((int16_t)((value - (int16_t)value) * 1000)); // Max precision is 3 digits. + x = 100; + z = frac_nb; + do { // Example if frac_nb=2 then 952 will show as .95 + z--; + digit = (i_frac / x); + to_asc[y+z] = digit + 48; // Convert to ASCII + i_frac -= digit * x; // Calculate the remainder. + x /= 10; // 952-(9*100) = 52, 52-(10*5)=2 etc. + } while(z > 0); + y -= frac_nb; // set y to point where the dot must be placed. + to_asc[y] = '.'; + y--; // Set y to point where the rest of the numbers must be written. + } + + // Now it is time for the integer part. "y" already points to the position just before the dot. + do { + to_asc[y] = (i_dec % 10) + 48; //Write at least one digit even if value is zero. + i_dec /= 10; + if (i_dec <= 0) { // This way the leading zero is ommited. + if(value < 0) { + y--; to_asc[y] = '-'; // Place the minus sign if needed. + } + break; + } + else + y--; + } while(1); + + // Fill the buffer with the characters in the beggining of the string if any. + for (x=0; x Date: Fri, 26 Jul 2013 00:55:15 +0200 Subject: [PATCH 019/309] [boards] krooz: baro_board.c corrected --- sw/airborne/boards/krooz/baro_board.c | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/sw/airborne/boards/krooz/baro_board.c b/sw/airborne/boards/krooz/baro_board.c index 7b531ec97b..bc042c6cd0 100644 --- a/sw/airborne/boards/krooz/baro_board.c +++ b/sw/airborne/boards/krooz/baro_board.c @@ -1,11 +1,6 @@ #include "subsystems/sensors/baro.h" #include "baro_board.h" -/* -#include "subsystems/datalink/downlink.h" -#include "mcu_periph/uart.h" -#include "mcu_periph/sys_time.h" -*/ struct Baro baro; @@ -28,5 +23,8 @@ void baro_periodic(void) { baro_ms5611_d2(); cnt = 0; break; + default: + cnt = 0; + break; } } From d4d1dfeec8a1be8ba2cc95bad92c27908b0c4f97 Mon Sep 17 00:00:00 2001 From: softsr Date: Fri, 26 Jul 2013 09:09:15 +0200 Subject: [PATCH 020/309] [mcu] Added i2c3 initializationto mcu.c closes #489 --- sw/airborne/mcu.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sw/airborne/mcu.c b/sw/airborne/mcu.c index c0472a7d59..1757c1f889 100644 --- a/sw/airborne/mcu.c +++ b/sw/airborne/mcu.c @@ -101,6 +101,9 @@ void mcu_init(void) { #ifdef USE_I2C2 i2c2_init(); #endif +#ifdef USE_I2C3 + i2c3_init(); +#endif #ifdef USE_ADC adc_init(); #endif From 58842b839b7b22fe759e4907ddd5811f9bab1f36 Mon Sep 17 00:00:00 2001 From: Dino Hensen Date: Sat, 27 Jul 2013 22:39:29 +0200 Subject: [PATCH 021/309] [ardrone2_raw] Battery readout for ARDrone2 RAW version. Formula to convert from 10bit ADC value to battery voltage can be improved --- conf/firmwares/rotorcraft.makefile | 2 +- .../subsystems/electrical/electrical_arch.c | 37 ------- sw/airborne/boards/ardrone/electrical_raw.c | 102 ++++++++++++++++++ .../ardrone/electrical_raw.h} | 11 +- 4 files changed, 110 insertions(+), 42 deletions(-) delete mode 100644 sw/airborne/arch/omap/subsystems/electrical/electrical_arch.c create mode 100644 sw/airborne/boards/ardrone/electrical_raw.c rename sw/airborne/{arch/omap/subsystems/electrical/electrical_arch.h => boards/ardrone/electrical_raw.h} (80%) diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index bd5519ef4c..ffbea72141 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -238,7 +238,7 @@ ap.srcs += subsystems/electrical.c else ifeq ($(BOARD)$(BOARD_TYPE), ardronesdk) ap.srcs += $(SRC_BOARD)/electrical_dummy.c else ifeq ($(BOARD)$(BOARD_TYPE), ardroneraw) -ap.srcs += $(SRC_ARCH)/subsystems/electrical/electrical_arch.c +ap.srcs += $(SRC_BOARD)/electrical_raw.c endif diff --git a/sw/airborne/arch/omap/subsystems/electrical/electrical_arch.c b/sw/airborne/arch/omap/subsystems/electrical/electrical_arch.c deleted file mode 100644 index 52f1e41ef7..0000000000 --- a/sw/airborne/arch/omap/subsystems/electrical/electrical_arch.c +++ /dev/null @@ -1,37 +0,0 @@ -/* - * - * Copyright (C) 2009-2013 The Paparazzi Team - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - * - */ - -/** - * @file arch/omap/subsystems/electrical/electrical_arch.c - * arch specific electrical status readings - */ - -#include "subsystems/electrical/electrical_arch.h" - -struct Electrical electrical; - -void electrical_init(void) { } - -void electrical_periodic(void) { - electrical.vsupply = 120; -} diff --git a/sw/airborne/boards/ardrone/electrical_raw.c b/sw/airborne/boards/ardrone/electrical_raw.c new file mode 100644 index 0000000000..c327f38f45 --- /dev/null +++ b/sw/airborne/boards/ardrone/electrical_raw.c @@ -0,0 +1,102 @@ +/* + * + * Copyright (C) 2009-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file boards/ardrone/electrical_raw.c + * arch specific electrical status readings + */ + +#include "electrical_raw.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include "i2c-dev.h" + +struct Electrical electrical; + +int fd; + +void electrical_init(void) { + + fd = open( "/dev/i2c-1", O_RDWR ); + + + if ( ioctl( fd, I2C_SLAVE_FORCE, 0x4a) < 0 ) { + fprintf( stderr, "Failed to set slave address: %m\n" ); + } + + electrical_setup(); +} + +void electrical_setup(void) { + // Turn on MADC in CTRL1 + if( i2c_smbus_write_byte_data( fd, 0x00, 0x01)) { + fprintf( stderr, "Failed to write to I2C device. 1\n" ); + } + // Select ADCIN0 for conversion in SW1SELECT_LSB + if( i2c_smbus_write_byte_data( fd, 0x06, 0xff)){ + fprintf( stderr, "Failed to write to I2C device. 2\n" ); + } + // Select ADCIN12 for conversion in SW1SELECT_MSB + if( i2c_smbus_write_byte_data( fd, 0x07, 0xff)) { + fprintf( stderr, "Failed to write to I2C device. 3\n" ); + } + // Setup register for averaging + if( i2c_smbus_write_byte_data( fd, 0x08, 0xff)) { + fprintf( stderr, "Failed to write to I2C device. 4\n" ); + } + // Start all channel conversion by setting bit 5 to one in CTRL_SW1 + if( i2c_smbus_write_byte_data( fd, 0x12, 0x20)) { + fprintf( stderr, "Failed to write to I2C device. 5\n" ); + } +} + +void electrical_periodic(void) { + + electrical_setup(); + + unsigned char lsb, msb; + lsb = i2c_smbus_read_byte_data(fd, 0x37); + msb = i2c_smbus_read_byte_data(fd, 0x38); + + int raw_voltage = (lsb >> 6) | (msb << 2); + + // we know from spec sheet that ADCIN0 has no prescaler + // so that the max voltage range is 1.5 volt + // multiply by ten to get decivolts + electrical.vsupply = 10 * electrical_calculate_voltage(raw_voltage, 1.5); +} + +float electrical_calculate_voltage(int raw, float range_max) +{ + float step_size = 1.5/(pow(2,10)-1); + float R = ( 1.5 / range_max ); + float output = (float)raw * ( step_size / R ); + + return 6.6 + (3 * output); // todo improve this line to get more accurate voltage readings +} diff --git a/sw/airborne/arch/omap/subsystems/electrical/electrical_arch.h b/sw/airborne/boards/ardrone/electrical_raw.h similarity index 80% rename from sw/airborne/arch/omap/subsystems/electrical/electrical_arch.h rename to sw/airborne/boards/ardrone/electrical_raw.h index 450acec3e2..9f6062cb80 100644 --- a/sw/airborne/arch/omap/subsystems/electrical/electrical_arch.h +++ b/sw/airborne/boards/ardrone/electrical_raw.h @@ -22,13 +22,16 @@ */ /** - * @file arch/omap/subsystems/electrical/electrical_arch.h + * @file boards/ardrone/electrical_raw.h * arch specific electrical status readings */ -#ifndef ELECTRICAL_ARCH_H_ -#define ELECTRICAL_ARCH_H_ +#ifndef ELECTRICAL_RAW_H_ +#define ELECTRICAL_RAW_H_ #include "subsystems/electrical.h" -#endif /* ELECTRICAL_ARCH_H_ */ +void electrical_setup(void); +float electrical_calculate_voltage(int raw, float range_max); + +#endif /* ELECTRICAL_RAW_H_ */ From 4196580afb8ce59294fdeeacda61be408bd14184 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 30 Jul 2013 14:10:40 +0200 Subject: [PATCH 022/309] [boards] ardone2: correct voltage scale, thx Eric --- sw/airborne/boards/ardrone/electrical_raw.c | 13 ++++--------- sw/airborne/boards/ardrone/electrical_raw.h | 1 - 2 files changed, 4 insertions(+), 10 deletions(-) diff --git a/sw/airborne/boards/ardrone/electrical_raw.c b/sw/airborne/boards/ardrone/electrical_raw.c index c327f38f45..6dd9e93cd0 100644 --- a/sw/airborne/boards/ardrone/electrical_raw.c +++ b/sw/airborne/boards/ardrone/electrical_raw.c @@ -89,14 +89,9 @@ void electrical_periodic(void) { // we know from spec sheet that ADCIN0 has no prescaler // so that the max voltage range is 1.5 volt // multiply by ten to get decivolts - electrical.vsupply = 10 * electrical_calculate_voltage(raw_voltage, 1.5); -} -float electrical_calculate_voltage(int raw, float range_max) -{ - float step_size = 1.5/(pow(2,10)-1); - float R = ( 1.5 / range_max ); - float output = (float)raw * ( step_size / R ); - - return 6.6 + (3 * output); // todo improve this line to get more accurate voltage readings + //from raw measurement we got quite a lineair response + //9.0V=662, 9.5V=698, 10.0V=737,10.5V=774, 11.0V=811, 11.5V=848, 12.0V=886, 12.5V=923 + //leading to our 0.13595166 magic number for decivolts conversion + electrical.vsupply = raw_voltage*0.13595166; } diff --git a/sw/airborne/boards/ardrone/electrical_raw.h b/sw/airborne/boards/ardrone/electrical_raw.h index 9f6062cb80..9db3a59c29 100644 --- a/sw/airborne/boards/ardrone/electrical_raw.h +++ b/sw/airborne/boards/ardrone/electrical_raw.h @@ -32,6 +32,5 @@ #include "subsystems/electrical.h" void electrical_setup(void); -float electrical_calculate_voltage(int raw, float range_max); #endif /* ELECTRICAL_RAW_H_ */ From bfaeadb6bbb5b5da0ddca735d8317061ced4a7a4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 30 Jul 2013 13:19:42 +0200 Subject: [PATCH 023/309] [peripherals] updates to l3g4200 gyro from Eduardo --- sw/airborne/peripherals/l3g4200.c | 20 ++++++++++++-------- sw/airborne/peripherals/l3g4200.h | 25 ++++++++++++++----------- sw/airborne/peripherals/l3g4200_regs.h | 7 +++++++ 3 files changed, 33 insertions(+), 19 deletions(-) diff --git a/sw/airborne/peripherals/l3g4200.c b/sw/airborne/peripherals/l3g4200.c index 757f8ea8e3..64d82302c7 100644 --- a/sw/airborne/peripherals/l3g4200.c +++ b/sw/airborne/peripherals/l3g4200.c @@ -1,5 +1,4 @@ /* - * * Copyright (C) 2011 Gautier Hattenberger * 2013 Felix Ruess * 2013 Eduardo Lavratti @@ -33,6 +32,7 @@ void l3g4200_set_default_config(struct L3g4200Config *c) { c->ctrl_reg1 = L3G4200_DEFAULT_CTRL_REG1; + c->ctrl_reg4 = L3G4200_DEFAULT_CTRL_REG4; c->ctrl_reg5 = L3G4200_DEFAULT_CTRL_REG5; } @@ -71,6 +71,10 @@ static void l3g4200_send_config(struct L3g4200 *l3g) l3g4200_i2c_tx_reg(l3g, L3G4200_REG_CTRL_REG1, l3g->config.ctrl_reg1); l3g->init_status++; break; + case L3G_CONF_REG4: + l3g4200_i2c_tx_reg(l3g, L3G4200_REG_CTRL_REG4, l3g->config.ctrl_reg4); + l3g->init_status++; + break; case L3G_CONF_REG5: l3g4200_i2c_tx_reg(l3g, L3G4200_REG_CTRL_REG5, l3g->config.ctrl_reg5); l3g->init_status++; @@ -99,12 +103,12 @@ void l3g4200_start_configure(struct L3g4200 *l3g) void l3g4200_read(struct L3g4200 *l3g) { if (l3g->initialized && l3g->i2c_trans.status == I2CTransDone) { - l3g->i2c_trans.buf[0] = L3G4200_REG_STATUS_REG; - i2c_transceive(l3g->i2c_p, &(l3g->i2c_trans), l3g->i2c_trans.slave_addr, 1, 9); + l3g->i2c_trans.buf[0] = 0x80 | L3G4200_REG_STATUS_REG; + i2c_transceive(l3g->i2c_p, &(l3g->i2c_trans), l3g->i2c_trans.slave_addr, 1, 7); } } -#define Int16FromBuf(_buf,_idx) ((int16_t)((_buf[_idx]<<8) | _buf[_idx+1])) +#define Int16FromBuf(_buf,_idx) ((int16_t)((_buf[_idx+1]<<8) | _buf[_idx])) void l3g4200_event(struct L3g4200 *l3g) { @@ -114,11 +118,11 @@ void l3g4200_event(struct L3g4200 *l3g) } else if (l3g->i2c_trans.status == I2CTransSuccess) { // Successfull reading and new data available - if (l3g->i2c_trans.buf[0] & 0x01) { // ver oque é o sinal antes do & + if (l3g->i2c_trans.buf[0] & 0x08) { // New data available - l3g->data.rates.p = Int16FromBuf(l3g->i2c_trans.buf,3); - l3g->data.rates.q = Int16FromBuf(l3g->i2c_trans.buf,5); - l3g->data.rates.r = Int16FromBuf(l3g->i2c_trans.buf,7); + l3g->data.rates.p = Int16FromBuf(l3g->i2c_trans.buf,1); + l3g->data.rates.q = Int16FromBuf(l3g->i2c_trans.buf,3); + l3g->data.rates.r = Int16FromBuf(l3g->i2c_trans.buf,5); l3g->data_available = TRUE; } l3g->i2c_trans.status = I2CTransDone; diff --git a/sw/airborne/peripherals/l3g4200.h b/sw/airborne/peripherals/l3g4200.h index 16b572ee52..ccfa6d25a8 100644 --- a/sw/airborne/peripherals/l3g4200.h +++ b/sw/airborne/peripherals/l3g4200.h @@ -19,7 +19,6 @@ * along with paparazzi; see the file COPYING. If not, write to * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. - * */ /** @@ -38,25 +37,29 @@ #include "peripherals/l3g4200_regs.h" -/// Default Output rate 800hz -#define L3G4200_DEFAULT_DR L3G4200_DR_800Hz -/// Default digital lowpass filter 35hz -#define L3G4200_DEFAULT_DLPF L3G4200_DLPF_2 - +// Default Output rate 100hz +#define L3G4200_DEFAULT_DR L3G4200_DR_100Hz +// Default digital lowpass filter 25hz +#define L3G4200_DEFAULT_DLPF L3G4200_DLPF_1 +// Default Scale +#define L3G4200_DEFAULT_SCALE L3G4200_SCALE_2000 /* Default conf */ -#define L3G4200_DEFAULT_CTRL_REG1 0x8f // 400hz ODR, 20hz filter, run! -#define L3G4200_DEFAULT_CTRL_REG5 0x02 // low pass filter enable +#define L3G4200_DEFAULT_CTRL_REG1 ((L3G4200_DEFAULT_DR<<6) | (L3G4200_DEFAULT_DLPF<<4) | 0xf); +#define L3G4200_DEFAULT_CTRL_REG4 (L3G4200_DEFAULT_SCALE<<4) | 0x00; // 2000deg = 0x30 +#define L3G4200_DEFAULT_CTRL_REG5 0x00 // first low pass filter enable struct L3g4200Config { - uint8_t ctrl_reg1; ///< - uint8_t ctrl_reg5; ///< + uint8_t ctrl_reg1; + uint8_t ctrl_reg4; + uint8_t ctrl_reg5; }; /** config status states */ enum L3g4200ConfStatus { L3G_CONF_UNINIT, L3G_CONF_REG1, + L3G_CONF_REG4, L3G_CONF_REG5, L3G_CONF_DONE }; @@ -75,7 +78,7 @@ struct L3g4200 { }; // Functions -extern void l3g4200_init(struct L3g4200 *itg, struct i2c_periph *i2c_p, uint8_t i2c_address); +extern void l3g4200_init(struct L3g4200 *l3g, struct i2c_periph *i2c_p, uint8_t i2c_address); extern void l3g4200_set_default_config(struct L3g4200Config *conf); extern void l3g4200_start_configure(struct L3g4200 *l3g); extern void l3g4200_read(struct L3g4200 *l3g); diff --git a/sw/airborne/peripherals/l3g4200_regs.h b/sw/airborne/peripherals/l3g4200_regs.h index 46f8486d20..57082f11bb 100644 --- a/sw/airborne/peripherals/l3g4200_regs.h +++ b/sw/airborne/peripherals/l3g4200_regs.h @@ -70,6 +70,7 @@ enum L3g4200_DR { L3G4200_DR_400Hz = 0x2, L3G4200_DR_800Hz = 0x3 }; + /** Digital Low Pass Filter Options */ enum L3g4200_DLPF { L3G4200_DLPF_1 = 0x0, @@ -78,4 +79,10 @@ enum L3g4200_DLPF { L3G4200_DLPF_4 = 0x3 }; +enum L3g4200_SCALE { + L3G4200_SCALE_250 = 0x0, + L3G4200_SCALE_500 = 0x1, + L3G4200_SCALE_2000 = 0x2, +}; + #endif /* L3G4200_REGS_H */ From bee90ba116dbbc3358d5a9f022c91b5b7b154a69 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 30 Jul 2013 13:48:17 +0200 Subject: [PATCH 024/309] [imu] new GL1 driver from Eduardo IMU from Goodluckbuy with L3G4200, ADXL345 and HMC5883. --- .../subsystems/shared/imu_gl1.makefile | 51 ++++++ sw/airborne/subsystems/imu/imu_gl1.c | 154 ++++++++++++++++++ sw/airborne/subsystems/imu/imu_gl1.h | 72 ++++++++ sw/airborne/subsystems/imu/imu_gl1_defaults.h | 94 +++++++++++ 4 files changed, 371 insertions(+) create mode 100644 conf/firmwares/subsystems/shared/imu_gl1.makefile create mode 100644 sw/airborne/subsystems/imu/imu_gl1.c create mode 100644 sw/airborne/subsystems/imu/imu_gl1.h create mode 100644 sw/airborne/subsystems/imu/imu_gl1_defaults.h diff --git a/conf/firmwares/subsystems/shared/imu_gl1.makefile b/conf/firmwares/subsystems/shared/imu_gl1.makefile new file mode 100644 index 0000000000..041f92f684 --- /dev/null +++ b/conf/firmwares/subsystems/shared/imu_gl1.makefile @@ -0,0 +1,51 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# IMU from Goodluckbuy +# + + +IMU_GL1_CFLAGS = -DIMU_TYPE_H=\"imu/imu_gl1.h\" +IMU_GL1_SRCS = $(SRC_SUBSYSTEMS)/imu.c +IMU_GL1_SRCS += $(SRC_SUBSYSTEMS)/imu/imu_gl1.c + +# for fixedwing firmware and ap only +ifeq ($(TARGET), ap) + IMU_GL1_CFLAGS += -DUSE_IMU +endif + +# Accelerometer +IMU_GL1_SRCS += peripherals/adxl345_i2c.c + +# Gyro +IMU_GL1_SRCS += peripherals/l3g4200.c + +# Magnetometer +IMU_GL1_SRCS += peripherals/hmc58xx.c + +ifeq ($(ARCH), lpc21) +ifndef GL1_I2C_DEV +GL1_I2C_DEV=i2c0 +endif +else ifeq ($(ARCH), stm32) +ifndef GL1_I2C_DEV +GL1_I2C_DEV=i2c2 +endif +endif + +# convert i2cx to upper case +GL1_I2C_DEV_UPPER=$(shell echo $(GL1_I2C_DEV) | tr a-z A-Z) + +IMU_GL1_CFLAGS += -DGL1_I2C_DEV=$(GL1_I2C_DEV) +IMU_GL1_CFLAGS += -DUSE_$(GL1_I2C_DEV_UPPER) + +# Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets +# see: conf/autopilot/subsystems/lisa_passthrough/imu_b2_v1.1.makefile for example +ap.CFLAGS += $(IMU_GL1_CFLAGS) +ap.srcs += $(IMU_GL1_SRCS) + + + +# +# NPS simulator +# +include $(CFG_SHARED)/imu_nps.makefile diff --git a/sw/airborne/subsystems/imu/imu_gl1.c b/sw/airborne/subsystems/imu/imu_gl1.c new file mode 100644 index 0000000000..eb035d6704 --- /dev/null +++ b/sw/airborne/subsystems/imu/imu_gl1.c @@ -0,0 +1,154 @@ +/* + * Copyright (C) 2010 Antoine Drouin + * 2013 Felix Ruess + * 2013 Eduardo Lavratti + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/imu/imu_gl1.c + * Driver for I2C IMU using L3G4200, ADXL345, HMC5883 and BMP085. + */ + +#include "subsystems/imu.h" +#include "mcu_periph/i2c.h" + +PRINT_CONFIG_VAR(GL1_I2C_DEV) + +/** adxl345 accelerometer output rate, lowpass is set to half of rate */ +#ifndef GL1_ACCEL_RATE +# if PERIODIC_FREQUENCY <= 60 +# define GL1_ACCEL_RATE ADXL345_RATE_50HZ +# elif PERIODIC_FREQUENCY <= 120 +# define GL1_ACCEL_RATE ADXL345_RATE_100HZ +# else +# define GL1_ACCEL_RATE ADXL345_RATE_200HZ +# endif +#endif +PRINT_CONFIG_VAR(GL1_ACCEL_RATE) + +/** gyro internal lowpass frequency */ +#ifndef GL1_GYRO_LOWPASS +# if PERIODIC_FREQUENCY <= 60 +# define GL1_GYRO_LOWPASS L3G4200_DLPF_1 +# elif PERIODIC_FREQUENCY <= 120 +# define GL1_GYRO_LOWPASS L3G4200_DLPF_2 +# else +# define GL1_GYRO_LOWPASS L3G4200_DLPF_3 +# endif +#endif +PRINT_CONFIG_VAR(GL1_GYRO_LOWPASS) + +/** gyro sample rate divider */ +#ifndef GL1_GYRO_SMPLRT +# if PERIODIC_FREQUENCY <= 60 +# define GL1_GYRO_SMPLRT L3G4200_DR_100Hz +PRINT_CONFIG_MSG("Gyro output rate is 100Hz") +# else +# define GL1_GYRO_SMPLRT L3G4200_DR_100Hz +PRINT_CONFIG_MSG("Gyro output rate is 100Hz") +# endif +#endif +PRINT_CONFIG_VAR(GL1_GYRO_SMPLRT) + +#ifdef GL1_GYRO_SCALE +# define L3G4200_SCALE GL1_GYRO_SCALE +# else +# define L3G4200_SCALE L3G4200_SCALE_2000 +#endif +PRINT_CONFIG_VAR(L3G4200_SCALE) + +struct ImuGL1I2c imu_gl1; + +void imu_impl_init(void) +{ + imu_gl1.accel_valid = FALSE; + imu_gl1.gyro_valid = FALSE; + imu_gl1.mag_valid = FALSE; + + /* Set accel configuration */ + adxl345_i2c_init(&imu_gl1.acc_adxl, &(GL1_I2C_DEV), ADXL345_ADDR); + // set the data rate + imu_gl1.acc_adxl.config.rate = GL1_ACCEL_RATE; + /// @todo drdy int handling for adxl345 + //imu_aspirin.acc_adxl.config.drdy_int_enable = TRUE; + + + /* Gyro configuration and initalization */ + l3g4200_init(&imu_gl1.gyro_l3g, &(GL1_I2C_DEV), L3G4200_ADDR_ALT); + /* change the default config */ + // output data rate, bandwidth, enable axis (0x1f = 100 ODR, 25hz) (0x5f = 200hz ODR, 25hz) + imu_gl1.gyro_l3g.config.ctrl_reg1 = ((GL1_GYRO_SMPLRT<<6) | (GL1_GYRO_LOWPASS<<4) | 0xf); + // senstivity + imu_gl1.gyro_l3g.config.ctrl_reg4 = (L3G4200_SCALE<<4) | 0x00; + // filter config + imu_gl1.gyro_l3g.config.ctrl_reg5 = 0x00; // only first LPF active + + + /* initialize mag and set default options */ + hmc58xx_init(&imu_gl1.mag_hmc, &(GL1_I2C_DEV), HMC58XX_ADDR); + imu_gl1.mag_hmc.type = HMC_TYPE_5883; +} + + +void imu_periodic(void) +{ + adxl345_i2c_periodic(&imu_gl1.acc_adxl); + + // Start reading the latest gyroscope data + l3g4200_periodic(&imu_gl1.gyro_l3g); + + // Read HMC58XX at 50Hz (main loop for rotorcraft: 512Hz) + RunOnceEvery(10, hmc58xx_periodic(&imu_gl1.mag_hmc)); +} + +void imu_gl1_i2c_event(void) +{ + adxl345_i2c_event(&imu_gl1.acc_adxl); + if (imu_gl1.acc_adxl.data_available) { + VECT3_COPY(imu.accel_unscaled, imu_gl1.acc_adxl.data.vect); + imu.accel_unscaled.x = imu_gl1.acc_adxl.data.vect.y; + imu.accel_unscaled.y = imu_gl1.acc_adxl.data.vect.x; + imu.accel_unscaled.z = -imu_gl1.acc_adxl.data.vect.z; + imu_gl1.acc_adxl.data_available = FALSE; + imu_gl1.accel_valid = TRUE; + } + + /* If the lg34200 I2C transaction has succeeded: convert the data */ + l3g4200_event(&imu_gl1.gyro_l3g); + if (imu_gl1.gyro_l3g.data_available) { + RATES_COPY(imu.gyro_unscaled, imu_gl1.gyro_l3g.data.rates); + imu.gyro_unscaled.p = imu_gl1.gyro_l3g.data.rates.q; + imu.gyro_unscaled.q = imu_gl1.gyro_l3g.data.rates.p; + imu.gyro_unscaled.r = -imu_gl1.gyro_l3g.data.rates.r; + imu_gl1.gyro_l3g.data_available = FALSE; + imu_gl1.gyro_valid = TRUE; + } + + /* HMC58XX event task */ + hmc58xx_event(&imu_gl1.mag_hmc); + if (imu_gl1.mag_hmc.data_available) { + // VECT3_COPY(imu.mag_unscaled, imu_gl1.mag_hmc.data.vect); + imu.mag_unscaled.y = imu_gl1.mag_hmc.data.vect.x; + imu.mag_unscaled.x = imu_gl1.mag_hmc.data.vect.y; + imu.mag_unscaled.z = -imu_gl1.mag_hmc.data.vect.z; + imu_gl1.mag_hmc.data_available = FALSE; + imu_gl1.mag_valid = TRUE; + } +} diff --git a/sw/airborne/subsystems/imu/imu_gl1.h b/sw/airborne/subsystems/imu/imu_gl1.h new file mode 100644 index 0000000000..a222ca6459 --- /dev/null +++ b/sw/airborne/subsystems/imu/imu_gl1.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2010 Antoine Drouin + * 2013 Felix Ruess + * 2013 Eduardo Lavratti + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/imu/imu_gl1.h + * Interface for I2c IMU using using L3G4200, ADXL345, HMC5883 and BMP085. + */ + + +#ifndef IMU_GL1_H +#define IMU_GL1_H + +#include "generated/airframe.h" +#include "subsystems/imu.h" + +/* include default GL1 sensitivity/channel definitions */ +#include "subsystems/imu/imu_gl1_defaults.h" + +#include "peripherals/l3g4200.h" +#include "peripherals/hmc58xx.h" +#include "peripherals/adxl345_i2c.h" + +struct ImuGL1I2c { + volatile uint8_t accel_valid; + volatile uint8_t gyro_valid; + volatile uint8_t mag_valid; + struct Adxl345_I2c acc_adxl; + struct L3g4200 gyro_l3g; + struct Hmc58xx mag_hmc; +}; + +extern struct ImuGL1I2c imu_gl1; + +extern void imu_gl1_i2c_event(void); + +static inline void ImuEvent(void (* _gyro_handler)(void), void (* _accel_handler)(void), void (* _mag_handler)(void)) { + imu_gl1_i2c_event(); + if (imu_gl1.gyro_valid) { + imu_gl1.gyro_valid = FALSE; + _gyro_handler(); + } + if (imu_gl1.accel_valid) { + imu_gl1.accel_valid = FALSE; + _accel_handler(); + } + if (imu_gl1.mag_valid) { + imu_gl1.mag_valid = FALSE; + _mag_handler(); + } +} + +#endif /* IMU_GL1_H */ diff --git a/sw/airborne/subsystems/imu/imu_gl1_defaults.h b/sw/airborne/subsystems/imu/imu_gl1_defaults.h new file mode 100644 index 0000000000..874afd3cd3 --- /dev/null +++ b/sw/airborne/subsystems/imu/imu_gl1_defaults.h @@ -0,0 +1,94 @@ +/* + * Copyright (C) 2010-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/imu/imu_gl1_defaults.h + * Default sensitivity definitions for IMU GL1. + */ + + +#ifndef IMU_GL1_DEFAULTS_H +#define IMU_GL1_DEFAULTS_H + +#include "generated/airframe.h" + +#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN +#define IMU_MAG_X_SIGN 1 +#define IMU_MAG_Y_SIGN 1 +#define IMU_MAG_Z_SIGN 1 +#endif +#if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN +#define IMU_GYRO_P_SIGN 1 +#define IMU_GYRO_Q_SIGN 1 +#define IMU_GYRO_R_SIGN 1 +#endif +#if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN +#define IMU_ACCEL_X_SIGN 1 +#define IMU_ACCEL_Y_SIGN 1 +#define IMU_ACCEL_Z_SIGN 1 +#endif + + +/** default gyro sensitivy and neutral from the datasheet + * L3G4200 has 8.75 LSB/(deg/s) + * sens = 1/xxx * pi/180 * 2^INT32_RATE_FRAC + * sens = 1/xxx * pi/180 * 4096 = ????? + * + * 250deg = 114.28 = 0.625 + * 500deg = 57.14 = 1.25 + * 2000deg = 14.28 = 5.006 + */ +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS 5.006 +#define IMU_GYRO_P_SENS_NUM 2503 +#define IMU_GYRO_P_SENS_DEN 500 +#define IMU_GYRO_Q_SENS 5.006 +#define IMU_GYRO_Q_SENS_NUM 2503 +#define IMU_GYRO_Q_SENS_DEN 500 +#define IMU_GYRO_R_SENS 5.006 +#define IMU_GYRO_R_SENS_NUM 2503 +#define IMU_GYRO_R_SENS_DEN 500 +#endif + +/** default accel sensitivy from the ADXL345 datasheet + * sensitivity of x & y axes depends on supply voltage: + * - 256 LSB/g @ 2.5V + * - 265 LSB/g @ 3.3V + * z sensitivity stays at 256 LSB/g + * fixed point sens: 9.81 [m/s^2] / 256 [LSB/g] * 2^INT32_ACCEL_FRAC + * x/y sens = 9.81 / 265 * 1024 = 37.91 + * z sens = 9.81 / 256 * 1024 = 39.24 + * + * what about the offset at 3.3V? + */ +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS 37.91 +#define IMU_ACCEL_X_SENS_NUM 3791 +#define IMU_ACCEL_X_SENS_DEN 100 +#define IMU_ACCEL_Y_SENS 37.91 +#define IMU_ACCEL_Y_SENS_NUM 3791 +#define IMU_ACCEL_Y_SENS_DEN 100 +#define IMU_ACCEL_Z_SENS 39.24 +#define IMU_ACCEL_Z_SENS_NUM 3924 +#define IMU_ACCEL_Z_SENS_DEN 100 +#endif + +#endif /* IMU_GL1_DEFAULTS_H */ From 707dc7bb29592178dae7cdfe7f53ba6ec9013cb3 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 30 Jul 2013 16:33:07 +0200 Subject: [PATCH 025/309] [dox] fix filename in doxygen header --- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h index 3b5552fcad..a5b6522ee7 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h @@ -21,7 +21,7 @@ */ /** - * @file subsystems/ahrs/ahrs_float_mlkf_opt.h + * @file subsystems/ahrs/ahrs_float_mlkf.h * * Multiplicative linearized Kalman Filter in quaternion formulation. * From 71efabe590e3a2f623ea1665854ac7352a7c835f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 30 Jul 2013 16:38:10 +0200 Subject: [PATCH 026/309] [rotorcraft] only reset psi and integrators if previous mode was not attitude --- sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index 44d11f3b29..39995aad2f 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -139,7 +139,11 @@ void guidance_h_mode_changed(uint8_t new_mode) { stabilization_attitude_reset_care_free_heading(); case GUIDANCE_H_MODE_FORWARD: case GUIDANCE_H_MODE_ATTITUDE: - stabilization_attitude_enter(); + /* reset attitude stabilization if previous mode was not using it */ + if (guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT || + guidance_h_mode == GUIDANCE_H_MODE_RATE) { + stabilization_attitude_enter(); + } break; case GUIDANCE_H_MODE_HOVER: From 4dd870b8ebd6f711802adc414da57b26ee5110c5 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 25 Jul 2013 15:08:08 +0200 Subject: [PATCH 027/309] [imu] aspirin_2_spi: default AHRS_PROPAGATE_FREQUENCY is 512 With DLPF_256HZ (value zero) the internal sampling rate is 8kHz and with a sample rate divider of 1 the output freq was actually 4kHz and not 500Hz. Since the data is polled from the mpu at PERIODIC_FREQUENCY the AHRS_PROPAGATE_FREQUENCY (defaulting to PERIODIC_FREQUENCY) is also 512Hz for a default rotorcraft config. Set the output freq to 2kHz now, AHRS_PROPAGATE_FREQUENCY stays at PERIODIC_FREQUENCY=512Hz so doesn't have to be defined in the airframe file. Also added defaults for PERIODIC_FREQUENCY of 60 and 120Hz: - DLPF_42HZ - output rate of 100Hz In these cases add --- conf/airframes/esden/cocto_lm2a2.xml | 8 +++----- conf/airframes/esden/hexy_ll11a2pwm.xml | 18 ++++++++--------- conf/airframes/esden/hexy_lm2a2pwm.xml | 8 +++----- conf/airframes/esden/lisa2_hex.xml | 2 -- conf/airframes/esden/quady_ll11a2pwm.xml | 8 +++----- conf/airframes/esden/quady_lm1a1pwm.xml | 8 +++----- conf/airframes/esden/quady_lm2a2pwm.xml | 8 +++----- conf/airframes/esden/quady_lm2a2pwmppm.xml | 4 +--- .../quadrotor_lisa_m_2_pwm_spektrum.xml | 3 +-- ...uadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml | 2 -- conf/airframes/examples/quadrotor_mlkf.xml | 2 -- .../subsystems/imu/imu_aspirin_2_spi.c | 20 ++++++++++++++++--- 12 files changed, 42 insertions(+), 49 deletions(-) diff --git a/conf/airframes/esden/cocto_lm2a2.xml b/conf/airframes/esden/cocto_lm2a2.xml index 144f12eb18..6d77ad1dcb 100644 --- a/conf/airframes/esden/cocto_lm2a2.xml +++ b/conf/airframes/esden/cocto_lm2a2.xml @@ -223,12 +223,10 @@ B2L -> CW - - - + + + - - diff --git a/conf/airframes/esden/hexy_ll11a2pwm.xml b/conf/airframes/esden/hexy_ll11a2pwm.xml index f3705ebc95..55412a313b 100644 --- a/conf/airframes/esden/hexy_ll11a2pwm.xml +++ b/conf/airframes/esden/hexy_ll11a2pwm.xml @@ -215,16 +215,14 @@ - - - - - - - - - - + + + + + + + + diff --git a/conf/airframes/esden/hexy_lm2a2pwm.xml b/conf/airframes/esden/hexy_lm2a2pwm.xml index c900b0e7ae..53292099a9 100644 --- a/conf/airframes/esden/hexy_lm2a2pwm.xml +++ b/conf/airframes/esden/hexy_lm2a2pwm.xml @@ -178,12 +178,10 @@ - - - + + + - - diff --git a/conf/airframes/esden/lisa2_hex.xml b/conf/airframes/esden/lisa2_hex.xml index f17936a89a..ce6a348d5f 100644 --- a/conf/airframes/esden/lisa2_hex.xml +++ b/conf/airframes/esden/lisa2_hex.xml @@ -195,8 +195,6 @@ - - diff --git a/conf/airframes/esden/quady_ll11a2pwm.xml b/conf/airframes/esden/quady_ll11a2pwm.xml index 3e39b0575e..876ee4a2c3 100644 --- a/conf/airframes/esden/quady_ll11a2pwm.xml +++ b/conf/airframes/esden/quady_ll11a2pwm.xml @@ -213,12 +213,10 @@ - - - + + + - - diff --git a/conf/airframes/esden/quady_lm1a1pwm.xml b/conf/airframes/esden/quady_lm1a1pwm.xml index 99a2840dbd..e94f7008ae 100644 --- a/conf/airframes/esden/quady_lm1a1pwm.xml +++ b/conf/airframes/esden/quady_lm1a1pwm.xml @@ -174,12 +174,10 @@ - - - + + + - - diff --git a/conf/airframes/esden/quady_lm2a2pwm.xml b/conf/airframes/esden/quady_lm2a2pwm.xml index bebf1bd2d6..6b8b5da46d 100644 --- a/conf/airframes/esden/quady_lm2a2pwm.xml +++ b/conf/airframes/esden/quady_lm2a2pwm.xml @@ -180,12 +180,10 @@ - - - + + + - - diff --git a/conf/airframes/esden/quady_lm2a2pwmppm.xml b/conf/airframes/esden/quady_lm2a2pwmppm.xml index 3c97b2ad2f..f33377fe79 100644 --- a/conf/airframes/esden/quady_lm2a2pwmppm.xml +++ b/conf/airframes/esden/quady_lm2a2pwmppm.xml @@ -178,10 +178,8 @@ - + - - diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index e9e9aa9dba..2d507056ae 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -16,8 +16,7 @@ - - + diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml index 3511bb9772..90932d24e5 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml @@ -16,8 +16,6 @@
- -
diff --git a/conf/airframes/examples/quadrotor_mlkf.xml b/conf/airframes/examples/quadrotor_mlkf.xml index c4f1066f5f..7a858bf286 100644 --- a/conf/airframes/examples/quadrotor_mlkf.xml +++ b/conf/airframes/examples/quadrotor_mlkf.xml @@ -6,8 +6,6 @@ - - diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c index bd463158df..0fcd038a6e 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c @@ -40,11 +40,25 @@ PRINT_CONFIG_VAR(ASPIRIN_2_SPI_SLAVE_IDX) #endif PRINT_CONFIG_VAR(ASPIRIN_2_SPI_DEV) -/* gyro internal lowpass frequency */ +/* MPU60x0 gyro/accel internal lowpass frequency */ #if !defined ASPIRIN_2_LOWPASS_FILTER && !defined ASPIRIN_2_SMPLRT_DIV +#if (PERIODIC_FREQUENCY == 60) || (PERIODIC_FREQUENCY == 120) +/* Accelerometer: Bandwidth 44Hz, Delay 4.9ms + * Gyroscope: Bandwidth 42Hz, Delay 4.8ms sampling 1kHz + */ +#define ASPIRIN_2_LOWPASS_FILTER MPU60X0_DLPF_42HZ +#define ASPIRIN_2_SMPLRT_DIV 9 +PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") +#elif PERIODIC_FREQUENCY == 512 +/* Accelerometer: Bandwidth 260Hz, Delay 0ms + * Gyroscope: Bandwidth 256Hz, Delay 0.98ms sampling 8kHz + */ #define ASPIRIN_2_LOWPASS_FILTER MPU60X0_DLPF_256HZ -#define ASPIRIN_2_SMPLRT_DIV 1 -//PRINT_CONFIG_MSG("Gyro/Accel output rate is 500Hz") +#define ASPIRIN_2_SMPLRT_DIV 3 +PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") +#else +#error Non-default PERIODIC_FREQUENCY: please define ASPIRIN_2_LOWPASS_FILTER and ASPIRIN_2_SMPLRT_DIV. +#endif #endif PRINT_CONFIG_VAR(ASPIRIN_2_LOWPASS_FILTER) PRINT_CONFIG_VAR(ASPIRIN_2_SMPLRT_DIV) From 9ab3c2bd0da11259d263542ee3a2706a9c8354aa Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 30 Jul 2013 18:19:32 +0200 Subject: [PATCH 028/309] 20s timeout and max 2 retries when trying to update_google_version --- data/maps/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/maps/Makefile b/data/maps/Makefile index 03e3fcb5ef..f20aff033b 100644 --- a/data/maps/Makefile +++ b/data/maps/Makefile @@ -21,7 +21,7 @@ $(DATADIR): $(DATADIR)/maps.google.com: $(DATADIR) FORCE @echo "-----------------------------------------------" @echo "DOWNLOAD: google maps version code"; - $(Q)wget -q -O $(@) http://maps.google.com/ || \ + $(Q)wget -q -t 2 -T 20 -O $(@) http://maps.google.com/ || \ (rm -f $(@) && \ echo "Could not download google maps version code" && \ echo "-----------------------------------------------" && \ From 80477d0b1cc9a391e91eeb67881753f92ff03556 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 31 Jul 2013 00:20:40 +0200 Subject: [PATCH 029/309] [lpc21][uart] fix some unused arg warnings --- sw/airborne/arch/lpc21/mcu_periph/uart_arch.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c index f209085ce2..5d594566c3 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.c @@ -68,7 +68,7 @@ void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { uart_enable_interrupts(p); } -void uart_periph_set_bits_stop_parity(struct uart_periph* __attribute__((unused)) p, uint8_t __attribute__((unused)) bits, uint8_t __attribute__((unused)) stop, uint8_t __attribute__((unused)) parity) { +void uart_periph_set_bits_stop_parity(struct uart_periph* p __attribute__((unused)), uint8_t bits __attribute__((unused)), uint8_t stop __attribute__((unused)), uint8_t __attribute__((unused)) parity) { // TBD } From f5c391f4149ba3ea2bb3030f41f028f8f786c4b6 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 31 Jul 2013 00:33:49 +0200 Subject: [PATCH 030/309] [modules] silence some warnings in imu_chimu --- sw/airborne/modules/ins/imu_chimu.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/modules/ins/imu_chimu.c b/sw/airborne/modules/ins/imu_chimu.c index 4699a4f6d7..bc2400c460 100644 --- a/sw/airborne/modules/ins/imu_chimu.c +++ b/sw/airborne/modules/ins/imu_chimu.c @@ -149,7 +149,7 @@ void CHIMU_Init(CHIMU_PARSER_DATA *pstData) unsigned char CHIMU_Parse( unsigned char btData, /* input byte stream buffer */ - unsigned char bInputType, /* for future use if special builds of CHIMU data are performed */ + unsigned char bInputType __attribute__((unused)), /* for future use if special builds of CHIMU data are performed */ CHIMU_PARSER_DATA *pstData) /* resulting data */ { @@ -287,7 +287,7 @@ static unsigned char BitTest (unsigned char input, unsigned char n) //Test a bit in n and return TRUE or FALSE if ( input & (1 << n)) return TRUE; else return FALSE; } -unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID, unsigned char *pPayloadData, CHIMU_PARSER_DATA *pstData) +unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID __attribute__((unused)), unsigned char *pPayloadData, CHIMU_PARSER_DATA *pstData) { //Msgs from CHIMU are off limits (i.e.any CHIMU messages sent up the uplink should go to //CHIMU). From 93372df379284ebba4059e4331bc98f58def6b6a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 31 Jul 2013 00:35:01 +0200 Subject: [PATCH 031/309] [fix][lpc21] workaround for init of spi_slave_hs --- conf/firmwares/subsystems/fixedwing/spi_slave_hs.makefile | 2 +- sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c | 3 +-- sw/airborne/mcu.c | 4 ++++ sw/airborne/mcu_periph/spi.h | 4 ++++ 4 files changed, 10 insertions(+), 3 deletions(-) diff --git a/conf/firmwares/subsystems/fixedwing/spi_slave_hs.makefile b/conf/firmwares/subsystems/fixedwing/spi_slave_hs.makefile index c1d03e2aa6..af019ea9a3 100644 --- a/conf/firmwares/subsystems/fixedwing/spi_slave_hs.makefile +++ b/conf/firmwares/subsystems/fixedwing/spi_slave_hs.makefile @@ -1,7 +1,7 @@ # Hey Emacs, this is a -*- makefile -*- #generic spi driver -$(TARGET).CFLAGS += -DUSE_SPI +$(TARGET).CFLAGS += -DUSE_SPI -DSPI_SLAVE_HS ifeq ($(TARGET), sim) else diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c index c58302d997..18a2a6549d 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c @@ -47,7 +47,6 @@ uint8_t spi_slave_hs_tx_insert_idx, spi_slave_hs_tx_extract_idx; uint8_t spi_slave_hs_tx_buffer[SPI_SLAVE_HS_TX_BUFFER_SIZE]; /* Prototypes */ -// void spi_init( void ); // -> declared in spi.h static void SSP_ISR(void) __attribute__((naked)); /* SSPCR0 settings */ @@ -105,7 +104,7 @@ static void SSP_ISR(void) __attribute__((naked)); #endif -void spi_init(void) { +void spi_slave_hs_init(void) { /* setup pins for SSP (SCK, MISO, MOSI) */ PINSEL1 |= SSP_PINSEL1_SCK | SSP_PINSEL1_MISO | SSP_PINSEL1_MOSI | SSP_PINSEL1_SSEL; diff --git a/sw/airborne/mcu.c b/sw/airborne/mcu.c index 1757c1f889..53c99dc2e1 100644 --- a/sw/airborne/mcu.c +++ b/sw/airborne/mcu.c @@ -143,6 +143,10 @@ void mcu_init(void) { spi3_slave_init(); #endif #endif // SPI_SLAVE + +#if SPI_SLAVE_HS + spi_slave_hs_init(); +#endif #endif // USE_SPI #ifdef USE_DAC diff --git a/sw/airborne/mcu_periph/spi.h b/sw/airborne/mcu_periph/spi.h index fb5c1fe011..60769eaeb4 100644 --- a/sw/airborne/mcu_periph/spi.h +++ b/sw/airborne/mcu_periph/spi.h @@ -359,4 +359,8 @@ extern bool_t spi_slave_wait(struct spi_periph* p); /** @}*/ /** @}*/ +#if SPI_SLAVE_HS +extern void spi_slave_hs_init(void); +#endif + #endif /* SPI_H */ From 4ce078880a57cc9caa9e38c8b4bc99e27d0ae2b4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 31 Jul 2013 01:47:34 +0200 Subject: [PATCH 032/309] [boards] correct include guard for apogee 1.0 --- sw/airborne/boards/apogee_1.0.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sw/airborne/boards/apogee_1.0.h b/sw/airborne/boards/apogee_1.0.h index 78ff267397..a9ca6af6c5 100644 --- a/sw/airborne/boards/apogee_1.0.h +++ b/sw/airborne/boards/apogee_1.0.h @@ -1,5 +1,5 @@ -#ifndef CONFIG_APOGEE_0_99_H -#define CONFIG_APOGEE_0_99_H +#ifndef CONFIG_APOGEE_1_00_H +#define CONFIG_APOGEE_1_00_H #define BOARD_APOGEE @@ -396,4 +396,4 @@ #define SPEKTRUM_UART2_ISR usart2_isr #define SPEKTRUM_UART2_DEV USART2 -#endif /* CONFIG_APOGEE_0_99_H */ +#endif /* CONFIG_APOGEE_1_00_H */ From 733728b61ce7310027cdc0f663e4868ab6653c45 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 31 Jul 2013 20:24:54 +0200 Subject: [PATCH 033/309] [conf] configurable spi for aspirin_2 --- .../shared/imu_aspirin_v2_common.makefile | 30 +++++++++++++++---- 1 file changed, 24 insertions(+), 6 deletions(-) diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile index 150a6f0bac..a85f2e5e1f 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile @@ -50,17 +50,35 @@ IMU_ASPIRIN_2_SRCS += peripherals/mpu60x0_spi.c include $(CFG_SHARED)/spi_master.makefile +# +# SPI device and slave select defaults +# ifeq ($(ARCH), lpc21) -IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE0 -IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_SLAVE_IDX=SPI_SLAVE0 -IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_DEV=spi1 -IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI1 +ifndef ASPIRIN_2_SPI_DEV +ASPIRIN_2_SPI_DEV = spi1 +endif +ifndef ASPIRIN_2_SPI_SLAVE_IDX +ASPIRIN_2_SPI_SLAVE_IDX = SPI_SLAVE0 +endif else ifeq ($(ARCH), stm32) -IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI2 # Slave select configuration # SLAVE2 is on PB12 (NSS) (MPU600 CS) -IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE2 +ifndef ASPIRIN_2_SPI_DEV +ASPIRIN_2_SPI_DEV = spi2 endif +ifndef ASPIRIN_2_SPI_SLAVE_IDX +ASPIRIN_2_SPI_SLAVE_IDX = SPI_SLAVE2 +endif +endif + +ASPIRIN_2_SPI_DEV_UPPER=$(shell echo $(ASPIRIN_2_SPI_DEV) | tr a-z A-Z) +ASPIRIN_2_SPI_DEV_LOWER=$(shell echo $(ASPIRIN_2_SPI_DEV) | tr A-Z a-z) + +IMU_ASPIRIN_2_CFLAGS += -DUSE_$(ASPIRIN_2_SPI_DEV_UPPER) +IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_DEV=$(ASPIRIN_2_SPI_DEV_LOWER) + +IMU_ASPIRIN_2_CFLAGS += -DUSE_$(ASPIRIN_2_SPI_SLAVE_IDX) +IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_SLAVE_IDX=$(ASPIRIN_2_SPI_SLAVE_IDX) # Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets # and re-use that in the imu_aspirin_v2.1 and imu_aspirin_v2.2 makefiles From df2297f4d6408498ff2db0db9e1b0fb46ffebb4a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 2 Aug 2013 01:00:29 +0200 Subject: [PATCH 034/309] [lisa] comments for the tunnel --- sw/airborne/lisa/tunnel_hw.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/lisa/tunnel_hw.c b/sw/airborne/lisa/tunnel_hw.c index 9f624f7f0b..510a48314f 100644 --- a/sw/airborne/lisa/tunnel_hw.c +++ b/sw/airborne/lisa/tunnel_hw.c @@ -27,6 +27,7 @@ #include "mcu_periph/sys_time.h" #include "led.h" +/* UART1 */ #define A_PERIPH RCC_APB2ENR_IOPAEN #define A_PORT GPIOA #define A_RX_PIN GPIO10 @@ -34,6 +35,7 @@ #define A_TX_PIN GPIO9 #define A_TX_PORT A_PORT +/* UART2 */ #define B_PERIPH RCC_APB2ENR_IOPAEN #define B_PORT GPIOA #define B_RX_PIN GPIO3 From f59d32b799ba08f52f3ac0f7ecfbefed97fcb768 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 2 Aug 2013 01:03:54 +0200 Subject: [PATCH 035/309] [rotorcraft] ins_int_extended without sonar --- sw/airborne/subsystems/ins/ins_int_extended.c | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/sw/airborne/subsystems/ins/ins_int_extended.c b/sw/airborne/subsystems/ins/ins_int_extended.c index 04c0befdb3..3215f44d70 100644 --- a/sw/airborne/subsystems/ins/ins_int_extended.c +++ b/sw/airborne/subsystems/ins/ins_int_extended.c @@ -82,6 +82,7 @@ int32_t ins_baro_alt; #include "filters/median_filter.h" struct MedianFilterInt baro_median; +#if USE_SONAR /* sonar */ bool_t ins_update_on_agl; int32_t ins_sonar_alt; @@ -92,6 +93,7 @@ struct MedianFilterInt sonar_median; #endif #define VFF_R_SONAR_0 0.1 #define VFF_R_SONAR_OF_M 0.2 +#endif // USE_SONAR /* output */ struct NedCoor_i ins_ltp_pos; @@ -122,9 +124,13 @@ void ins_init() { ins_baro_initialised = FALSE; init_median_filter(&baro_median); + +#if USE_SONAR ins_update_on_agl = FALSE; init_median_filter(&sonar_median); ins_sonar_offset = INS_SONAR_OFFSET; +#endif + vff_init(0., 0., 0., 0.); ins.vf_realign = FALSE; ins.hf_realign = FALSE; @@ -203,6 +209,7 @@ void ins_update_baro() { vff_update_baro(alt_float); } } + INS_NED_TO_STATE(); } @@ -244,6 +251,7 @@ void ins_update_gps(void) { #endif /* hff not used */ } + INS_NED_TO_STATE(); #endif /* USE_GPS */ } @@ -261,6 +269,8 @@ float var_err[VAR_ERR_MAX]; uint8_t var_idx = 0; #endif + +#if USE_SONAR void ins_update_sonar() { static float last_offset = 0.; // new value filtered with median_filter @@ -309,3 +319,4 @@ void ins_update_sonar() { vff_update_offset(last_offset); } } +#endif // USE_SONAR From 192cf13dc39b6916c8d760c6731b0b5c0c813890 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 2 Aug 2013 11:53:14 +0200 Subject: [PATCH 036/309] [rotorcraft] AHRS_FLOAT flag for float_cmpl_quat --- .../subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile index 4e1cf5090d..0e0b595620 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile @@ -7,7 +7,7 @@ USE_MAGNETOMETER ?= 1 -AHRS_CFLAGS = -DUSE_AHRS +AHRS_CFLAGS = -DUSE_AHRS -DAHRS_FLOAT AHRS_CFLAGS += -DUSE_AHRS_ALIGNER ifneq ($(USE_MAGNETOMETER),0) From 80193d109f9a00bb9a53599491e5761464658e19 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 2 Aug 2013 21:48:04 +0200 Subject: [PATCH 037/309] [rotorcraft][stabilization] move some macros --- .../stabilization/stabilization_attitude_ref_euler_int.c | 8 ++++++++ .../stabilization/stabilization_attitude_ref_int.h | 7 ------- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.c index 60d24517b8..d7e8566a8b 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.c @@ -74,6 +74,14 @@ void stabilization_attitude_ref_init(void) { #define OMEGA_2_R BFP_OF_REAL((OMEGA_R*OMEGA_R), OMEGA_2_R_RES) +#define REF_ANGLE_PI BFP_OF_REAL(3.1415926535897932384626433832795029, REF_ANGLE_FRAC) +#define REF_ANGLE_TWO_PI BFP_OF_REAL(2.*3.1415926535897932384626433832795029, REF_ANGLE_FRAC) +#define ANGLE_REF_NORMALIZE(_a) { \ + while (_a > REF_ANGLE_PI) _a -= REF_ANGLE_TWO_PI; \ + while (_a < -REF_ANGLE_PI) _a += REF_ANGLE_TWO_PI; \ + } + + /** explicitly define to zero to disable attitude reference generation */ #ifndef USE_ATTITUDE_REF #define USE_ATTITUDE_REF 1 diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_int.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_int.h index cbaf015206..c0ef65a2b8 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_int.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_int.h @@ -47,13 +47,6 @@ extern struct Int32RefModel stab_att_ref_model; #define REF_RATE_FRAC 16 #define REF_ANGLE_FRAC 20 -#define REF_ANGLE_PI BFP_OF_REAL(3.1415926535897932384626433832795029, REF_ANGLE_FRAC) -#define REF_ANGLE_TWO_PI BFP_OF_REAL(2.*3.1415926535897932384626433832795029, REF_ANGLE_FRAC) -#define ANGLE_REF_NORMALIZE(_a) { \ - while (_a > REF_ANGLE_PI) _a -= REF_ANGLE_TWO_PI; \ - while (_a < -REF_ANGLE_PI) _a += REF_ANGLE_TWO_PI; \ - } - extern void stabilization_attitude_ref_init(void); extern void stabilization_attitude_ref_update(void); From 8bce6d4df26f9632fb78e816972e5368978ce2f4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 3 Aug 2013 11:48:19 +0200 Subject: [PATCH 038/309] [rotorcraft] CAUTION! stabilization int_quat ref model scaling fixes Now the attitude reference should finally have the correct scaling. For end users that means it is not so sluggish on RC input anymore and you should get a snappy reference. CAUTION! Test fly carefully, you might need to lower the gains. --- .../stabilization_attitude_quat_int.c | 6 ++++- .../stabilization_attitude_ref_quat_int.c | 24 ++++++++++++------- 2 files changed, 20 insertions(+), 10 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c index 773bd481e8..1bff46cd25 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c @@ -152,9 +152,13 @@ void stabilization_attitude_run(bool_t enable_integrator) { INT32_QUAT_NORMALIZE(att_err); /* rate error */ + const struct Int32Rates rate_ref_scaled = { + OFFSET_AND_ROUND(stab_att_ref_rate.p, (REF_RATE_FRAC - INT32_RATE_FRAC)), + OFFSET_AND_ROUND(stab_att_ref_rate.q, (REF_RATE_FRAC - INT32_RATE_FRAC)), + OFFSET_AND_ROUND(stab_att_ref_rate.r, (REF_RATE_FRAC - INT32_RATE_FRAC)) }; struct Int32Rates rate_err; struct Int32Rates* body_rate = stateGetBodyRates_i(); - RATES_DIFF(rate_err, stab_att_ref_rate, *body_rate); + RATES_DIFF(rate_err, rate_ref_scaled, (*body_rate)); /* integrated error */ if (enable_integrator) { diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c index 52d0a131a6..ff4ad30036 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c @@ -122,11 +122,18 @@ void stabilization_attitude_ref_enter(void) // which is equal to >> 9 #define F_UPDATE_RES 9 +#define OFFSET_AND_ROUND(_a, _b) (((_a)+(1<<((_b)-1)))>>(_b)) + + void stabilization_attitude_ref_update(void) { /* integrate reference attitude */ + const struct Int32Rates rate_ref_scaled = { + OFFSET_AND_ROUND(stab_att_ref_rate.p, (REF_RATE_FRAC - INT32_RATE_FRAC)), + OFFSET_AND_ROUND(stab_att_ref_rate.q, (REF_RATE_FRAC - INT32_RATE_FRAC)), + OFFSET_AND_ROUND(stab_att_ref_rate.r, (REF_RATE_FRAC - INT32_RATE_FRAC)) }; struct Int32Quat qdot; - INT32_QUAT_DERIVATIVE(qdot, stab_att_ref_rate, stab_att_ref_quat); + INT32_QUAT_DERIVATIVE(qdot, rate_ref_scaled, stab_att_ref_quat); //QUAT_SMUL(qdot, qdot, DT_UPDATE); qdot.qi = qdot.qi >> F_UPDATE_RES; qdot.qx = qdot.qx >> F_UPDATE_RES; @@ -143,7 +150,6 @@ void stabilization_attitude_ref_update(void) { stab_att_ref_accel.p >> ( F_UPDATE_RES + REF_ACCEL_FRAC - REF_RATE_FRAC), stab_att_ref_accel.q >> ( F_UPDATE_RES + REF_ACCEL_FRAC - REF_RATE_FRAC), stab_att_ref_accel.r >> ( F_UPDATE_RES + REF_ACCEL_FRAC - REF_RATE_FRAC)}; - RATES_ADD(stab_att_ref_rate, delta_rate); /* compute reference angular accelerations */ @@ -160,17 +166,17 @@ void stabilization_attitude_ref_update(void) { ((int32_t)(-2.*ZETA_OMEGA_R) * (stab_att_ref_rate.r >> (REF_RATE_FRAC - REF_ACCEL_FRAC))) >> (ZETA_OMEGA_R_RES) }; const struct Int32Rates accel_angle = { - ((int32_t)(-OMEGA_2_P)* (err.qx >> (REF_ANGLE_FRAC - REF_ACCEL_FRAC))) >> (OMEGA_2_P_RES), - ((int32_t)(-OMEGA_2_Q)* (err.qy >> (REF_ANGLE_FRAC - REF_ACCEL_FRAC))) >> (OMEGA_2_Q_RES), - ((int32_t)(-OMEGA_2_R)* (err.qz >> (REF_ANGLE_FRAC - REF_ACCEL_FRAC))) >> (OMEGA_2_R_RES) }; + ((int32_t)(-OMEGA_2_P) * (err.qx >> (INT32_QUAT_FRAC - REF_ACCEL_FRAC))) >> (OMEGA_2_P_RES), + ((int32_t)(-OMEGA_2_Q) * (err.qy >> (INT32_QUAT_FRAC - REF_ACCEL_FRAC))) >> (OMEGA_2_Q_RES), + ((int32_t)(-OMEGA_2_R) * (err.qz >> (INT32_QUAT_FRAC - REF_ACCEL_FRAC))) >> (OMEGA_2_R_RES) }; RATES_SUM(stab_att_ref_accel, accel_rate, accel_angle); - /* saturate acceleration */ - //const struct Int32Rates MIN_ACCEL = { -REF_ACCEL_MAX_P, -REF_ACCEL_MAX_Q, -REF_ACCEL_MAX_R }; - //const struct Int32Rates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R }; - //RATES_BOUND_BOX(stab_att_ref_accel, MIN_ACCEL, MAX_ACCEL); + /* saturate acceleration */ + const struct Int32Rates MIN_ACCEL = { -REF_ACCEL_MAX_P, -REF_ACCEL_MAX_Q, -REF_ACCEL_MAX_R }; + const struct Int32Rates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R }; + RATES_BOUND_BOX(stab_att_ref_accel, MIN_ACCEL, MAX_ACCEL); /* compute ref_euler for debugging and telemetry */ From 2061fedc26a2d18f94b258b90f99059815c1cb93 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 3 Aug 2013 12:43:25 +0200 Subject: [PATCH 039/309] [rotorcraft][stabilization_ref_quat] saturate rate and trim accel --- ...titude_ref_euler.h => stabilization_attitude_ref.h} | 10 +++++----- .../stabilization_attitude_ref_euler_float.h | 2 +- .../stabilization_attitude_ref_euler_int.h | 2 +- .../stabilization_attitude_ref_quat_float.c | 7 +++++++ .../stabilization_attitude_ref_quat_float.h | 1 + .../stabilization_attitude_ref_quat_int.c | 3 +++ .../stabilization_attitude_ref_quat_int.h | 1 + 7 files changed, 19 insertions(+), 7 deletions(-) rename sw/airborne/firmwares/rotorcraft/stabilization/{stabilization_attitude_ref_euler.h => stabilization_attitude_ref.h} (92%) diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref.h similarity index 92% rename from sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler.h rename to sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref.h index b5076ff7cf..11d41dfb39 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref.h @@ -19,12 +19,12 @@ * Boston, MA 02111-1307, USA. */ -/** @file firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler.h - * Common rotorcraft attitude euler reference generation include. +/** @file firmwares/rotorcraft/stabilization/stabilization_attitude_ref.h + * Common rotorcraft attitude reference generation include. */ -#ifndef STABILIZATION_ATTITUDE_REF_EULER_H -#define STABILIZATION_ATTITUDE_REF_EULER_H +#ifndef STABILIZATION_ATTITUDE_REF_H +#define STABILIZATION_ATTITUDE_REF_H #define SATURATE_SPEED_TRIM_ACCEL() { \ if (stab_att_ref_rate.p >= REF_RATE_MAX_P) { \ @@ -60,4 +60,4 @@ } -#endif /* STABILIZATION_ATTITUDE_REF_EULER_H */ +#endif /* STABILIZATION_ATTITUDE_REF_H */ diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_float.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_float.h index fbb74093de..762e66ed96 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_float.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_float.h @@ -25,7 +25,7 @@ #include "math/pprz_algebra_float.h" #include "stabilization_attitude_ref_float.h" -#include "stabilization_attitude_ref_euler.h" +#include "stabilization_attitude_ref.h" void stabilization_attitude_ref_enter(void); diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.h index e4dee67c49..bf3aacf19c 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_euler_int.h @@ -28,7 +28,7 @@ #define STABILIZATION_ATTITUDE_REF_EULER_INT_H #include "stabilization_attitude_ref_int.h" -#include "stabilization_attitude_ref_euler.h" +#include "stabilization_attitude_ref.h" #endif /* STABILIZATION_ATTITUDE_REF_EULER_INT_H */ diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.c index 8657e30446..da50880f15 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.c @@ -37,6 +37,10 @@ #define REF_ACCEL_MAX_Q STABILIZATION_ATTITUDE_REF_MAX_QDOT #define REF_ACCEL_MAX_R STABILIZATION_ATTITUDE_REF_MAX_RDOT +#define REF_RATE_MAX_P STABILIZATION_ATTITUDE_REF_MAX_P +#define REF_RATE_MAX_Q STABILIZATION_ATTITUDE_REF_MAX_Q +#define REF_RATE_MAX_R STABILIZATION_ATTITUDE_REF_MAX_R + struct FloatEulers stab_att_sp_euler; struct FloatQuat stab_att_sp_quat; struct FloatEulers stab_att_ref_euler; @@ -146,6 +150,9 @@ void stabilization_attitude_ref_update(void) { const struct FloatRates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R }; RATES_BOUND_BOX(stab_att_ref_accel, MIN_ACCEL, MAX_ACCEL); + /* saturate angular speed and trim accel accordingly */ + SATURATE_SPEED_TRIM_ACCEL(); + /* compute ref_euler */ FLOAT_EULERS_OF_QUAT(stab_att_ref_euler, stab_att_ref_quat); } diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.h index 83323d06dd..0424fbf820 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_float.h @@ -34,6 +34,7 @@ #include "math/pprz_algebra_float.h" #include "stabilization_attitude_ref_float.h" +#include "stabilization_attitude_ref.h" #define DEADBAND_EXCEEDED(VARIABLE, VALUE) ((VARIABLE > VALUE) || (VARIABLE < -VALUE)) #define APPLY_DEADBAND(VARIABLE, VALUE) (DEADBAND_EXCEEDED(VARIABLE, VALUE) ? VARIABLE : 0.0) diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c index ff4ad30036..b0202847dd 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.c @@ -178,6 +178,9 @@ void stabilization_attitude_ref_update(void) { const struct Int32Rates MAX_ACCEL = { REF_ACCEL_MAX_P, REF_ACCEL_MAX_Q, REF_ACCEL_MAX_R }; RATES_BOUND_BOX(stab_att_ref_accel, MIN_ACCEL, MAX_ACCEL); + /* saturate angular speed and trim accel accordingly */ + SATURATE_SPEED_TRIM_ACCEL(); + /* compute ref_euler for debugging and telemetry */ struct Int32Eulers ref_eul; diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.h index 4fe03f3218..3b1cbaa3e8 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_ref_quat_int.h @@ -31,6 +31,7 @@ #define STABILIZATION_ATTITUDE_INT_REF_QUAT_INT_H #include "stabilization_attitude_ref_int.h" +#include "stabilization_attitude_ref.h" void stabilization_attitude_ref_enter(void); From ad44b5d0c9b1dabf4c2fb1847640e3e5b04a3ad8 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 3 Aug 2013 17:00:22 +0200 Subject: [PATCH 040/309] [conf] stm32f4 discovery test board files --- .../examples/stm32f4_discovery_test.xml | 214 ++++++++++++++++++ conf/boards/stm32f4_discovery.makefile | 57 +++++ 2 files changed, 271 insertions(+) create mode 100644 conf/airframes/examples/stm32f4_discovery_test.xml create mode 100644 conf/boards/stm32f4_discovery.makefile diff --git a/conf/airframes/examples/stm32f4_discovery_test.xml b/conf/airframes/examples/stm32f4_discovery_test.xml new file mode 100644 index 0000000000..8957d373cd --- /dev/null +++ b/conf/airframes/examples/stm32f4_discovery_test.xml @@ -0,0 +1,214 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + +
+ + + + + + + + + +
+ + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + +
+ +
+ + + + + +
+ +
+ + + +
+ +
+ + + + +
+ +
diff --git a/conf/boards/stm32f4_discovery.makefile b/conf/boards/stm32f4_discovery.makefile new file mode 100644 index 0000000000..f00700c783 --- /dev/null +++ b/conf/boards/stm32f4_discovery.makefile @@ -0,0 +1,57 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# stm32f4_discovery.makefile +# +# + +BOARD=stm32f4_discovery +BOARD_VERSION= +BOARD_CFG=\"boards/$(BOARD).h\" + +ARCH=stm32 +ARCH_L=f4 +ARCH_DIR=stm32 +SRC_ARCH=arch/$(ARCH_DIR) +$(TARGET).ARCHDIR = $(ARCH) +$(TARGET).LDSCRIPT=$(SRC_ARCH)/apogee.ld + +HARD_FLOAT=yes + +# default flash mode is via usb dfu bootloader +# possibilities: DFU, SWD +FLASH_MODE ?= DFU +STLINK ?= n +DFU_UTIL ?= y + +# +# default LED configuration +# +RADIO_CONTROL_LED ?= 4 +BARO_LED ?= none +AHRS_ALIGNER_LED ?= none +GPS_LED ?= none +SYS_TIME_LED ?= 3 + +# +# default UART configuration (modem, gps, spektrum) +# + +MODEM_PORT ?= UART6 +MODEM_BAUD ?= B57600 + +GPS_PORT ?= UART4 +GPS_BAUD ?= B38400 + +RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2 + + +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# e.g. +# +ACTUATORS ?= actuators_pwm + From e5012834d405f95d121d02d5a6c7e8a9168fb25d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 3 Aug 2013 17:02:28 +0200 Subject: [PATCH 041/309] [conf] updates for fraser quad with spektrum --- conf/airframes/fraser_lisa_m_rotorcraft.xml | 26 +++++++++++++-------- 1 file changed, 16 insertions(+), 10 deletions(-) diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index a232a41767..877f496e66 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -8,14 +8,18 @@ - + + + + + + - @@ -28,12 +32,13 @@ - + - +
+ @@ -64,6 +69,7 @@ + @@ -163,8 +169,8 @@
- - + + @@ -211,19 +217,19 @@ - - + + - +
- + From d0c75fe3d09e5dcebbea800f9234cf8c50de4b96 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 4 Aug 2013 22:57:08 +0200 Subject: [PATCH 042/309] [rotorcraft] PRINT_CONFIG_VAR for GUIDANCE_V_NOMINAL_HOVER_THROTTLE --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 6 +++--- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index 2287d88252..c8cd29d6e1 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -44,11 +44,11 @@ #if (GUIDANCE_V_HOVER_KP < 0) || \ (GUIDANCE_V_HOVER_KD < 0) || \ (GUIDANCE_V_HOVER_KI < 0) -#warning "ALL control gains are now positive!!!" +#error "ALL control gains are now positive!!!" #endif -#if defined GUIDANCE_V_INV_M -#warning "GUIDANCE_V_INV_M has been removed. If you don't want to use adaptive hover, please define GUIDANCE_V_NOMINAL_HOVER_THROTTLE" +#ifdef GUIDANCE_V_NOMINAL_HOVER_THROTTLE +PRINT_CONFIG_VAR(GUIDANCE_V_NOMINAL_HOVER_THROTTLE) #endif uint8_t guidance_v_mode; diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h index 56c2437215..a9c2f86403 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h @@ -84,7 +84,7 @@ extern int32_t guidance_v_fb_cmd; ///< feed-back command extern int32_t guidance_v_delta_t; /** nominal throttle for hover. - * This is only used if #"GUIDANCE_V_NOMINAL_HOVER_THROTTLE is defined! + * This is only used if #GUIDANCE_V_NOMINAL_HOVER_THROTTLE is defined! * Unit: factor of #MAX_PPRZ with range 0.1 : 0.9 */ extern float guidance_v_nominal_throttle; From 2ba9d5de39bfb40d9d2d743fa5ff090bde3ddea7 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 6 Aug 2013 16:03:02 +0200 Subject: [PATCH 043/309] [lpc21] only indentation cleanup --- .../subsystems/actuators/servos_ppm_hw.h | 58 +++++++++---------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/sw/airborne/arch/lpc21/subsystems/actuators/servos_ppm_hw.h b/sw/airborne/arch/lpc21/subsystems/actuators/servos_ppm_hw.h index 6281a5dbd0..86fe9af00a 100644 --- a/sw/airborne/arch/lpc21/subsystems/actuators/servos_ppm_hw.h +++ b/sw/airborne/arch/lpc21/subsystems/actuators/servos_ppm_hw.h @@ -57,33 +57,33 @@ extern uint8_t ppm_pulse; /* 1=start of pulse, 0=end of pulse */ #define PPM_WIDTH SERVOS_TICS_OF_USEC(550) #define ACTUATORS_IT TIR_MR1I -#define ServosPPMMat_ISR() { \ - if (servos_PPM_idx == 0) { \ - servos_delay = SERVO_REFRESH_TICS; \ - } \ - if (servos_PPM_idx < _PPM_NB_CHANNELS ) { \ - if (ppm_pulse) { \ - T0MR1 += PPM_WIDTH; \ - servos_delay -= PPM_WIDTH; \ - } else { \ - T0MR1 += servos_values[servos_PPM_idx] - PPM_WIDTH; \ - servos_delay -= servos_values[servos_PPM_idx] - PPM_WIDTH; \ - servos_PPM_idx++; \ - } \ - } else { /* servos_PPM_idx=_PPM_NB_CHANNELS */ \ - if (ppm_pulse) { \ - T0MR1 += PPM_WIDTH; \ - servos_delay -= PPM_WIDTH; \ - } else { \ - servos_PPM_idx = 0; \ - T0MR1 += servos_delay - PPM_WIDTH; \ - } \ - } \ - if (!ppm_pulse) { \ - /* lower clock pin */ \ - T0EMR &= ~TEMR_EM1; \ - } \ - /* toggle ppm_pulse flag */ \ - ppm_pulse ^= 1; \ -} +#define ServosPPMMat_ISR() { \ + if (servos_PPM_idx == 0) { \ + servos_delay = SERVO_REFRESH_TICS; \ + } \ + if (servos_PPM_idx < _PPM_NB_CHANNELS ) { \ + if (ppm_pulse) { \ + T0MR1 += PPM_WIDTH; \ + servos_delay -= PPM_WIDTH; \ + } else { \ + T0MR1 += servos_values[servos_PPM_idx] - PPM_WIDTH; \ + servos_delay -= servos_values[servos_PPM_idx] - PPM_WIDTH; \ + servos_PPM_idx++; \ + } \ + } else { /* servos_PPM_idx=_PPM_NB_CHANNELS */ \ + if (ppm_pulse) { \ + T0MR1 += PPM_WIDTH; \ + servos_delay -= PPM_WIDTH; \ + } else { \ + servos_PPM_idx = 0; \ + T0MR1 += servos_delay - PPM_WIDTH; \ + } \ + } \ + if (!ppm_pulse) { \ + /* lower clock pin */ \ + T0EMR &= ~TEMR_EM1; \ + } \ + /* toggle ppm_pulse flag */ \ + ppm_pulse ^= 1; \ + } #endif /* SERVOS_PPM_HW_H */ From 55c3ad045d6de5c61ff8dd8d1453ad6b1aab15bc Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 6 Aug 2013 18:34:36 +0200 Subject: [PATCH 044/309] [rotorcraft] set guidance_v_zd_sp to zero in altitude hold for visualization --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index c8cd29d6e1..71882d1935 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -202,6 +202,7 @@ void guidance_v_run(bool_t in_flight) { if (fms.enabled && fms.input.v_mode == GUIDANCE_V_MODE_HOVER) guidance_v_z_sp = fms.input.v_sp.height; #endif + guidance_v_zd_sp = 0; gv_update_ref_from_z_sp(guidance_v_z_sp); run_hover_loop(in_flight); #if NO_RC_THRUST_LIMIT @@ -216,6 +217,7 @@ void guidance_v_run(bool_t in_flight) { { if (vertical_mode == VERTICAL_MODE_ALT) { guidance_v_z_sp = -nav_flight_altitude; + guidance_v_zd_sp = 0; gv_update_ref_from_z_sp(guidance_v_z_sp); run_hover_loop(in_flight); } From 3951bd7f27cfe48cc3e3e0f7d3ade925202b0297 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 7 Aug 2013 00:04:35 +0200 Subject: [PATCH 045/309] [math] add FLOAT_QUAT_OF_ORIENTATION_VECT --- sw/airborne/math/pprz_algebra_float.h | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/sw/airborne/math/pprz_algebra_float.h b/sw/airborne/math/pprz_algebra_float.h index e48aca10dd..e787b961e3 100644 --- a/sw/airborne/math/pprz_algebra_float.h +++ b/sw/airborne/math/pprz_algebra_float.h @@ -701,6 +701,22 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { _q.qz = san * _uv.z; \ } +#define FLOAT_QUAT_OF_ORIENTATION_VECT(_q, _ov) { \ + const float ov_norm = sqrtf((_ov).x*(_ov).x + (_ov).y*(_ov).y + (_ov).z*(_ov).z); \ + if (ov_norm < 1e-8) { \ + (_q).qi = 1; \ + (_q).qx = 0; \ + (_q).qy = 0; \ + (_q).qz = 0; \ + } else { \ + const float s2_normalized = sinf(ov_norm/2.0) / ov_norm; \ + (_q).qi = cosf(ov_norm/2.0); \ + (_q).qx = (_ov).x * s2_normalized; \ + (_q).qy = (_ov).y * s2_normalized; \ + (_q).qz = (_ov).z * s2_normalized; \ + } \ + } + #define FLOAT_QUAT_OF_RMAT(_q, _r) { \ const float tr = RMAT_TRACE(_r); \ if (tr > 0) { \ From 104acd276754eef8850826d00f0dfb6f5fb5bf70 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 7 Aug 2013 13:46:08 +0200 Subject: [PATCH 046/309] [rotorcraft][guidance][stabilization] quat setpoint fixes Don't pretend that the commands from guidance_h are actually real euler angles. Compose a roll/pitch quaternion from simultaneous rotation of roll/pitch, then rotate around resulting body z-axis to align the heading. This should "fix" the setpoint passed to the attitude stabilization if in HOVER or NAV at large angles. Only tested quickly in simulation... --- .../rotorcraft/guidance/guidance_h.c | 14 ++++----- .../stabilization/stabilization_attitude.h | 2 +- .../stabilization_attitude_euler_float.c | 4 +-- .../stabilization_attitude_euler_int.c | 4 +-- .../stabilization_attitude_passthrough.c | 4 +-- .../stabilization_attitude_quat_float.c | 22 ++++++++++++-- .../stabilization_attitude_quat_int.c | 30 ++++++++++++++++--- 7 files changed, 59 insertions(+), 21 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index 39995aad2f..e609a89624 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -253,12 +253,12 @@ void guidance_h_run(bool_t in_flight) { guidance_h_nav_enter(); if (horizontal_mode == HORIZONTAL_MODE_ATTITUDE) { - struct Int32Eulers sp_euler_i; - sp_euler_i.phi = nav_roll; - sp_euler_i.theta = nav_pitch; + struct Int32Eulers sp_cmd_i; + sp_cmd_i.phi = nav_roll; + sp_cmd_i.theta = nav_pitch; /* FIXME: heading can't be set via attitude block yet, use current heading for now */ - sp_euler_i.psi = stateGetNedToBodyEulers_i()->psi; - stabilization_attitude_set_from_eulers_i(&sp_euler_i); + sp_cmd_i.psi = stateGetNedToBodyEulers_i()->psi; + stabilization_attitude_set_cmd_i(&sp_cmd_i); } else { INT32_VECT2_NED_OF_ENU(guidance_h_pos_sp, navigation_carrot); @@ -362,8 +362,8 @@ static void guidance_h_traj_run(bool_t in_flight) { guidance_h_command_body.phi += guidance_h_rc_sp.phi; guidance_h_command_body.theta += guidance_h_rc_sp.theta; - /* Set attitude setpoint from pseudo-eulers */ - stabilization_attitude_set_from_eulers_i(&guidance_h_command_body); + /* Set attitude setpoint from pseudo-euler commands */ + stabilization_attitude_set_cmd_i(&guidance_h_command_body); } static void guidance_h_hover_enter(void) { diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h index 7a0572f69e..94b47466e4 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h @@ -34,7 +34,7 @@ extern void stabilization_attitude_init(void); extern void stabilization_attitude_read_rc(bool_t in_flight); extern void stabilization_attitude_enter(void); extern void stabilization_attitude_set_failsafe_setpoint(void); -extern void stabilization_attitude_set_from_eulers_i(struct Int32Eulers *sp_euler); +extern void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd); extern void stabilization_attitude_run(bool_t in_flight); diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c index b2f9f24178..3a5df19417 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c @@ -86,8 +86,8 @@ void stabilization_attitude_set_failsafe_setpoint(void) { stab_att_sp_euler.psi = stateGetNedToBodyEulers_f()->psi; } -void stabilization_attitude_set_from_eulers_i(struct Int32Eulers *sp_euler) { - EULERS_FLOAT_OF_BFP(stab_att_sp_euler, *sp_euler); +void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { + EULERS_FLOAT_OF_BFP(stab_att_sp_euler, *sp_cmd); } diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c index f435e97a1f..a86f9c4c80 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c @@ -102,8 +102,8 @@ void stabilization_attitude_set_failsafe_setpoint(void) { stab_att_sp_euler.psi = stateGetNedToBodyEulers_i()->psi; } -void stabilization_attitude_set_from_eulers_i(struct Int32Eulers *sp_euler) { - memcpy(&stab_att_sp_euler, sp_euler, sizeof(struct Int32Eulers)); +void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { + memcpy(&stab_att_sp_euler, sp_cmd, sizeof(struct Int32Eulers)); } diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c index 69f7004aca..5ddcb0e7c3 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c @@ -78,7 +78,7 @@ void stabilization_attitude_set_failsafe_setpoint(void) { stab_att_sp_euler.psi = stateGetNedToBodyEulers_i()->psi; } -void stabilization_attitude_set_from_eulers_i(struct Int32Eulers *sp_euler) { - memcpy(&stab_att_sp_euler, sp_euler, sizeof(struct Int32Eulers)); +void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { + memcpy(&stab_att_sp_euler, sp_cmd, sizeof(struct Int32Eulers)); } diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c index e546692a87..b99400c492 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c @@ -142,9 +142,25 @@ void stabilization_attitude_set_failsafe_setpoint(void) { stab_att_sp_quat.qz = sinf(heading2); } -void stabilization_attitude_set_from_eulers_i(struct Int32Eulers *sp_euler) { - EULERS_FLOAT_OF_BFP(stab_att_sp_euler, *sp_euler); - FLOAT_QUAT_OF_EULERS(stab_att_sp_quat, stab_att_sp_euler); +void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { + EULERS_FLOAT_OF_BFP(stab_att_sp_euler, *sp_cmd); + + /* orientation vector describing simultaneous rotation of roll/pitch */ + struct FloatVect3 ov; + ov.x = stab_att_sp_euler.phi; + ov.y = stab_att_sp_euler.theta; + ov.z = 0.0; + /* quaternion from that orientation vector */ + struct FloatQuat q_rp; + FLOAT_QUAT_OF_ORIENTATION_VECT(q_rp, ov); + + /* quaternion with only heading setpoint */ + const float yaw2 = stab_att_sp_euler.psi / 2.0; + struct FloatQuat q_yaw; + QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); + + /* final setpoint: apply roll/pitch, then yaw around resulting body z-axis */ + FLOAT_QUAT_COMP(stab_att_sp_quat, q_yaw, q_rp); FLOAT_QUAT_WRAP_SHORTEST(stab_att_sp_quat); } diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c index 1bff46cd25..1c889af5d0 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c @@ -92,11 +92,33 @@ void stabilization_attitude_set_failsafe_setpoint(void) { PPRZ_ITRIG_SIN(stab_att_sp_quat.qz, heading2); } -void stabilization_attitude_set_from_eulers_i(struct Int32Eulers *sp_euler) { +void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { // copy euler setpoint for debugging - memcpy(&stab_att_sp_euler, sp_euler, sizeof(struct Int32Eulers)); - INT32_QUAT_OF_EULERS(stab_att_sp_quat, *sp_euler); - INT32_QUAT_WRAP_SHORTEST(stab_att_sp_quat); + memcpy(&stab_att_sp_euler, sp_cmd, sizeof(struct Int32Eulers)); + + /// @todo calc sp_quat in fixed-point + + /* orientation vector describing simultaneous rotation of roll/pitch */ + struct FloatVect3 ov; + ov.x = ANGLE_FLOAT_OF_BFP(sp_cmd->phi); + ov.y = ANGLE_FLOAT_OF_BFP(sp_cmd->theta); + ov.z = 0.0; + /* quaternion from that orientation vector */ + struct FloatQuat q_rp; + FLOAT_QUAT_OF_ORIENTATION_VECT(q_rp, ov); + + /* quaternion with only heading setpoint */ + const float yaw2 = ANGLE_FLOAT_OF_BFP(sp_cmd->psi) / 2.0; + struct FloatQuat q_yaw; + QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); + + /* final setpoint: apply roll/pitch, then yaw around resulting body z-axis */ + struct FloatQuat q_sp; + FLOAT_QUAT_COMP(q_sp, q_yaw, q_rp); + FLOAT_QUAT_WRAP_SHORTEST(q_sp); + + /* convert to fixed point */ + QUAT_BFP_OF_REAL(stab_att_sp_quat, q_sp); } #define OFFSET_AND_ROUND(_a, _b) (((_a)+(1<<((_b)-1)))>>(_b)) From 8efc24099c42d58d455dded7ec9a2978807e2146 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 7 Aug 2013 17:03:47 +0200 Subject: [PATCH 047/309] [boards] stm32f4_discovery board file for some testing --- sw/airborne/boards/stm32f4_discovery.h | 236 +++++++++++++++++++++++++ 1 file changed, 236 insertions(+) create mode 100755 sw/airborne/boards/stm32f4_discovery.h diff --git a/sw/airborne/boards/stm32f4_discovery.h b/sw/airborne/boards/stm32f4_discovery.h new file mode 100755 index 0000000000..288385d132 --- /dev/null +++ b/sw/airborne/boards/stm32f4_discovery.h @@ -0,0 +1,236 @@ +#ifndef CONFIG_STM32F4_DISCOVERY_H +#define CONFIG_STM32F4_DISCOVERY_H + +#define BOARD_STM32F4_DISCOVERY + +/* STM32F4_DISCOVERY has a 8MHz external clock and 168MHz internal. */ +#define EXT_CLK 8000000 +#define AHB_CLK 168000000 + +/* + * Onboard LEDs + */ + +/* orange, on PD13 */ +#ifndef USE_LED_3 +#define USE_LED_3 1 +#endif +#define LED_3_GPIO GPIOD +#define LED_3_GPIO_CLK RCC_AHB1ENR_IOPDEN +#define LED_3_GPIO_PIN GPIO13 +#define LED_3_AFIO_REMAP ((void)0) +#define LED_3_GPIO_ON gpio_set +#define LED_3_GPIO_OFF gpio_clear + +/* green, on PD12 */ +#ifndef USE_LED_4 +#define USE_LED_4 1 +#endif +#define LED_4_GPIO GPIOD +#define LED_4_GPIO_CLK RCC_AHB1ENR_IOPDEN +#define LED_4_GPIO_PIN GPIO12 +#define LED_4_AFIO_REMAP ((void)0) +#define LED_4_GPIO_ON gpio_set +#define LED_4_GPIO_OFF gpio_clear + +/* red, PD14 */ +#ifndef USE_LED_5 +#define USE_LED_5 1 +#endif +#define LED_5_GPIO GPIOD +#define LED_5_GPIO_CLK RCC_AHB1ENR_IOPDEN +#define LED_5_GPIO_PIN GPIO14 +#define LED_5_AFIO_REMAP ((void)0) +#define LED_5_GPIO_ON gpio_set +#define LED_5_GPIO_OFF gpio_clear + +/* blue, PD15 */ +#ifndef USE_LED_6 +#define USE_LED_6 1 +#endif +#define LED_6_GPIO GPIOD +#define LED_6_GPIO_CLK RCC_AHB1ENR_IOPDEN +#define LED_6_GPIO_PIN GPIO15 +#define LED_6_AFIO_REMAP ((void)0) +#define LED_6_GPIO_ON gpio_set +#define LED_6_GPIO_OFF gpio_clear + + +/* UART */ +#define UART1_GPIO_AF GPIO_AF7 +#define UART1_GPIO_PORT_RX GPIOA +#define UART1_GPIO_RX GPIO10 +#define UART1_GPIO_PORT_TX GPIOB +#define UART1_GPIO_TX GPIO6 + +#define UART2_GPIO_AF GPIO_AF7 +#define UART2_GPIO_PORT_RX GPIOA +#define UART2_GPIO_RX GPIO3 +#define UART2_GPIO_PORT_TX GPIOA +#define UART2_GPIO_TX GPIO2 + +#define UART4_GPIO_AF GPIO_AF8 +#define UART4_GPIO_PORT_RX GPIOA +#define UART4_GPIO_RX GPIO1 +#define UART4_GPIO_PORT_TX GPIOA +#define UART4_GPIO_TX GPIO0 + +#define UART6_GPIO_AF GPIO_AF8 +#define UART6_GPIO_PORT_RX GPIOC +#define UART6_GPIO_RX GPIO7 +#define UART6_GPIO_PORT_TX GPIOC +#define UART6_GPIO_TX GPIO6 + + +/* SPI */ +#define SPI1_GPIO_AF GPIO_AF5 +#define SPI1_GPIO_PORT_MISO GPIOA +#define SPI1_GPIO_MISO GPIO6 +#define SPI1_GPIO_PORT_MOSI GPIOA +#define SPI1_GPIO_MOSI GPIO7 +#define SPI1_GPIO_PORT_SCK GPIOA +#define SPI1_GPIO_SCK GPIO5 + +#define SPI_SELECT_SLAVE0_PORT GPIOB +#define SPI_SELECT_SLAVE0_PIN GPIO9 + + +/* I2C mapping */ +#define I2C1_GPIO_PORT GPIOB +#define I2C1_GPIO_SCL GPIO8 +#define I2C1_GPIO_SDA GPIO9 + +#define I2C2_GPIO_PORT GPIOB +#define I2C2_GPIO_SCL GPIO10 +#define I2C2_GPIO_SDA GPIO11 + +#define I2C3_GPIO_PORT_SCL GPIOA +#define I2C3_GPIO_PORT_SDA GPIOC +#define I2C3_GPIO_SCL GPIO8 +#define I2C3_GPIO_SDA GPIO9 + + +/* + * PPM + */ +#define USE_PPM_TIM1 1 + +#define PPM_CHANNEL TIM_IC1 +#define PPM_TIMER_INPUT TIM_IC_IN_TI1 +#define PPM_IRQ NVIC_TIM1_CC_IRQ +#define PPM_IRQ2 NVIC_TIM1_UP_TIM10_IRQ +// Capture/Compare InteruptEnable and InterruptFlag +#define PPM_CC_IE TIM_DIER_CC1IE +#define PPM_CC_IF TIM_SR_CC1IF +#define PPM_GPIO_PORT GPIOA +#define PPM_GPIO_PIN GPIO8 +#define PPM_GPIO_AF GPIO_AF1 + + +/* + * Spektrum + */ +/* The line that is pulled low at power up to initiate the bind process */ +#define SPEKTRUM_BIND_PIN GPIO8 +#define SPEKTRUM_BIND_PIN_PORT GPIOA + +#define SPEKTRUM_UART2_RCC_REG &RCC_APB2ENR +#define SPEKTRUM_UART2_RCC_DEV RCC_APB2ENR_USART1EN +#define SPEKTRUM_UART2_BANK GPIOA +#define SPEKTRUM_UART2_PIN GPIO10 +#define SPEKTRUM_UART2_AF GPIO_AF7 +#define SPEKTRUM_UART2_IRQ NVIC_USART1_IRQ +#define SPEKTRUM_UART2_ISR usart1_isr +#define SPEKTRUM_UART2_DEV USART1 + + +/* Onboard ADCs */ +#define USE_AD_TIM4 1 + +#define BOARD_ADC_CHANNEL_1 9 +#define BOARD_ADC_CHANNEL_2 15 +#define BOARD_ADC_CHANNEL_3 14 +#define BOARD_ADC_CHANNEL_4 4 + +#ifndef USE_AD1 +#define USE_AD1 1 +#endif +/* provide defines that can be used to access the ADC_x in the code or airframe file + * these directly map to the index number of the 4 adc channels defined above + * 4th (index 3) is used for bat monitoring by default + */ +// AUX 1 +#define ADC_1 ADC1_C1 +#ifdef USE_ADC_1 +#ifndef ADC_1_GPIO_CLOCK_PORT +#define ADC_1_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPBEN +#define ADC_1_INIT() gpio_mode_setup(GPIOB, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO1) +#endif +#define USE_AD1_1 1 +#else +#define ADC_1_GPIO_CLOCK_PORT 0 +#define ADC_1_INIT() {} +#endif + +// AUX 2 +#define ADC_2 ADC1_C2 +#ifdef USE_ADC_2 +#ifndef ADC_2_GPIO_CLOCK_PORT +#define ADC_2_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPCEN +#define ADC_2_INIT() gpio_mode_setup(GPIOC, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO5) +#endif +#define USE_AD1_2 1 +#else +#define ADC_2_GPIO_CLOCK_PORT 0 +#define ADC_2_INIT() {} +#endif + +// AUX 3 +#define ADC_3 ADC1_C3 +#ifdef USE_ADC_3 +#ifndef ADC_3_GPIO_CLOCK_PORT +#define ADC_3_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPCEN +#define ADC_3_INIT() gpio_mode_setup(GPIOC, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO4) +#endif +#define USE_AD1_3 1 +#else +#define ADC_3_GPIO_CLOCK_PORT 0 +#define ADC_3_INIT() {} +#endif + +// BAT +#define ADC_4 ADC1_C4 +#ifndef ADC_4_GPIO_CLOCK_PORT +#define ADC_4_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPAEN +#define ADC_4_INIT() gpio_mode_setup(GPIOA, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO4) +#endif +#define USE_AD1_4 1 + +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_4 +#endif + +#define ADC_GPIO_CLOCK_PORT (ADC_1_GPIO_CLOCK_PORT | ADC_2_GPIO_CLOCK_PORT | ADC_3_GPIO_CLOCK_PORT | ADC_4_GPIO_CLOCK_PORT) + +/* GPIO mapping for ADC1 pins, overwrites the default in arch/stm32/mcu_periph/adc_arch.c */ +#ifdef USE_AD1 +#define ADC1_GPIO_INIT(gpio) { \ + ADC_1_INIT(); \ + ADC_2_INIT(); \ + ADC_3_INIT(); \ + ADC_4_INIT(); \ + } +#endif // USE_AD1 + +#define DefaultVoltageOfAdc(adc) (0.00485*adc) + + +/* Default actuators driver */ +#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" +#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y) +#define ActuatorsDefaultInit() ActuatorsPwmInit() +#define ActuatorsDefaultCommit() ActuatorsPwmCommit() + + +#endif /* CONFIG_STM32F4_DISCOVERY_H */ From e9ca4d4f1f11f88c82087bf8270397834f4a914c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 7 Aug 2013 22:58:12 +0200 Subject: [PATCH 048/309] [rotorcraft] v_adapt: limit min/max estimated hover throttle The adaptive vertical filter estimates the ratio of vertical acceleration over thrust command. In effect this will now limit the throttle applied in hover between 20% and 75% of max throttle by default. --- .../rotorcraft/guidance/guidance_v_adpt.h | 63 ++++++++++--------- 1 file changed, 35 insertions(+), 28 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h index b22a8c188b..ba743cb2cd 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h @@ -33,7 +33,7 @@ #include "paparazzi.h" /** Adapt noise factor. - * Smaller values will make the filter to adapter faster. + * Smaller values will make the filter to adapt faster. * Bigger values (slower adaptation) make the filter more robust to external perturbations. * Factor should always be >0 */ @@ -67,6 +67,22 @@ #define GUIDANCE_V_ADAPT_MIN_CMD 0.1 #endif +/** Minimum hover throttle as factor of MAX_PPRZ. + * With the default of 0.2 the nominal hover throttle will + * never go lower than 20%. + */ +#ifndef GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE +#define GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE 0.2 +#endif + +/** Maximum hover throttle as factor of MAX_PPRZ. + * With the default of 0.75 the nominal hover throttle will + * never go over 75% of max throttle. + */ +#ifndef GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE +#define GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE 0.75 +#endif + /** State of the estimator. * fixed point representation with #GV_ADAPT_X_FRAC * Q13.18 @@ -109,27 +125,6 @@ int32_t gv_adapt_Xmeas; #define GV_ADAPT_MEAS_NOISE_HOVER BFP_OF_REAL(GV_ADAPT_MEAS_NOISE_HOVER_F, GV_ADAPT_P_FRAC) #define GV_ADAPT_MEAS_NOISE_OF_ZD (100.0*GUIDANCE_V_ADAPT_NOISE_FACTOR) -/* Max accel */ -#define GV_ADAPT_MAX_ACCEL ACCEL_BFP_OF_REAL(GUIDANCE_V_ADAPT_MAX_ACCEL) - -/* Command bounds */ -#define GV_ADAPT_MAX_CMD ((int32_t)(GUIDANCE_V_ADAPT_MAX_CMD*MAX_PPRZ)) -#define GV_ADAPT_MIN_CMD ((int32_t)(GUIDANCE_V_ADAPT_MIN_CMD*MAX_PPRZ)) - -/* Output bounds. - * Don't let it climb over a value that would - * give less than zero throttle and don't let it down to zero. - * Worst cases: - * MIN_ACCEL / MAX_THROTTLE - * MAX_ACCEL / MIN_THROTTLE - * ex: - * 9.81*2^18/255 = 10084 - * 9.81*2^18/1 = 2571632 - */ -// TODO Check this properly -#define GV_ADAPT_MAX_OUT (BFP_OF_REAL(9.81, GV_ADAPT_X_FRAC)) -#define GV_ADAPT_MIN_OUT (BFP_OF_REAL(9.81, GV_ADAPT_X_FRAC) / MAX_PPRZ) - static inline void gv_adapt_init(void) { gv_adapt_X = GV_ADAPT_X0; @@ -145,10 +140,14 @@ static inline void gv_adapt_init(void) { */ static inline void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_t zd_ref) { + static const int32_t gv_adapt_min_cmd = GUIDANCE_V_ADAPT_MIN_CMD * MAX_PPRZ; + static const int32_t gv_adapt_max_cmd = GUIDANCE_V_ADAPT_MAX_CMD * MAX_PPRZ; + static const int32_t gv_adapt_max_accel = ACCEL_BFP_OF_REAL(GUIDANCE_V_ADAPT_MAX_ACCEL); + /* Update only if accel and commands are in a valid range */ /* This also ensures we don't divide by zero */ - if (thrust_applied < GV_ADAPT_MIN_CMD || thrust_applied > GV_ADAPT_MAX_CMD - || zdd_meas < -GV_ADAPT_MAX_ACCEL || zdd_meas > GV_ADAPT_MAX_ACCEL) { + if (thrust_applied < gv_adapt_min_cmd || thrust_applied > gv_adapt_max_cmd + || zdd_meas < -gv_adapt_max_accel || zdd_meas > gv_adapt_max_accel) { return; } @@ -178,15 +177,23 @@ static inline void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_ /* Update Covariance Pnew = P - K * P */ gv_adapt_P = gv_adapt_P - ((K * gv_adapt_P)>>K_FRAC); /* Don't let covariance climb over initial value */ - if (gv_adapt_P > GV_ADAPT_P0) gv_adapt_P = GV_ADAPT_P0; + if (gv_adapt_P > GV_ADAPT_P0) { + gv_adapt_P = GV_ADAPT_P0; + } /* Update State */ gv_adapt_X = gv_adapt_X + (((int64_t)(K * residual))>>K_FRAC); - /* Again don't let it climb over a value that would - * give less than zero throttle and don't let it down to zero. + /* Output bounds. + * Don't let it climb over a value that would + * give less than #GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE % throttle + * or more than #GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE % throttle. */ - Bound(gv_adapt_X, GV_ADAPT_MIN_OUT, GV_ADAPT_MAX_OUT); + static const int32_t max_out = BFP_OF_REAL(9.81, GV_ADAPT_X_FRAC) / + (GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE * MAX_PPRZ); + static const int32_t min_out = BFP_OF_REAL(9.81, GV_ADAPT_X_FRAC) / + (GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE * MAX_PPRZ); + Bound(gv_adapt_X, min_out, max_out); } From d1ceba79ea1eba046312f9eb34b2a313272757ef Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Wed, 7 Aug 2013 15:35:54 -0600 Subject: [PATCH 049/309] [nps] Detect nans and exit in JSBSim FDM --- sw/simulator/nps/nps_fdm.h | 1 + sw/simulator/nps/nps_fdm_jsbsim.c | 94 +++++++++++++++++++++++++++++++ 2 files changed, 95 insertions(+) diff --git a/sw/simulator/nps/nps_fdm.h b/sw/simulator/nps/nps_fdm.h index 022364c0ce..4332fe0104 100644 --- a/sw/simulator/nps/nps_fdm.h +++ b/sw/simulator/nps/nps_fdm.h @@ -43,6 +43,7 @@ struct NpsFdm { double init_dt; double curr_dt; bool_t on_ground; + int nan_count; /* position */ struct EcefCoor_d ecef_pos; diff --git a/sw/simulator/nps/nps_fdm_jsbsim.c b/sw/simulator/nps/nps_fdm_jsbsim.c index efee3a8b19..4fccf4e4ea 100644 --- a/sw/simulator/nps/nps_fdm_jsbsim.c +++ b/sw/simulator/nps/nps_fdm_jsbsim.c @@ -52,6 +52,7 @@ using namespace JSBSim; static void feed_jsbsim(double* commands); static void fetch_state(void); +static int check_for_nan(void); static void jsbsimvec_to_vec(DoubleVect3* fdm_vector, const FGColumnVector3* jsb_vector); static void jsbsimloc_to_loc(EcefCoor_d* fdm_location, const FGLocation* jsb_location); @@ -86,6 +87,8 @@ void nps_fdm_init(double dt) { for (min_dt = (1.0/dt); min_dt < (1/MIN_DT); min_dt += (1/dt)){} min_dt = (1/min_dt); + fdm.nan_count = 0; + init_jsbsim(dt); FDMExec->RunIC(); @@ -146,6 +149,14 @@ void nps_fdm_run_step(double* commands) { fetch_state(); + /* Check the current state to make sure it is valid (no NaNs) */ + if (check_for_nan()) { + printf("Error: FDM simulation encountered a total of %i NaN values at simulation time %f.\n", fdm.nan_count, fdm.time); + printf("It is likely the simulation diverged and gave non-physical results. If you did\n"); + printf("not crash, check your model and/or initial conditions. Exiting with status 1.\n"); + exit(1); + } + } /** @@ -471,3 +482,86 @@ void lla_from_jsbsim_geodetic(LlaCoor_d* fdm_lla, FGPropagate* propagate) { fdm_lla->alt = MetersOfFeet(propagate->GetGeodeticAltitude()); } + +/* Why isn't this there when we include math.h? */ +/// Check if a double is NaN. +static int isnan(double f) { return (f != f); } + +/** + * Checks NpsFdm struct for NaNs. + * + * Increments the NaN count on each new NaN + * + * @return Count of new NaNs. 0 for no new NaNs. + */ +static int check_for_nan(void) { + int orig_nan_count = fdm.nan_count; + /* Check all elements for nans */ + if (isnan(fdm.ecef_pos.x)) fdm.nan_count++; + if (isnan(fdm.ecef_pos.y)) fdm.nan_count++; + if (isnan(fdm.ecef_pos.z)) fdm.nan_count++; + if (isnan(fdm.ltpprz_pos.x)) fdm.nan_count++; + if (isnan(fdm.ltpprz_pos.y)) fdm.nan_count++; + if (isnan(fdm.ltpprz_pos.z)) fdm.nan_count++; + if (isnan(fdm.lla_pos.lon)) fdm.nan_count++; + if (isnan(fdm.lla_pos.lat)) fdm.nan_count++; + if (isnan(fdm.lla_pos.alt)) fdm.nan_count++; + if (isnan(fdm.hmsl)) fdm.nan_count++; + // Skip debugging elements + if (isnan(fdm.ecef_ecef_vel.x)) fdm.nan_count++; + if (isnan(fdm.ecef_ecef_vel.y)) fdm.nan_count++; + if (isnan(fdm.ecef_ecef_vel.z)) fdm.nan_count++; + if (isnan(fdm.ecef_ecef_accel.x)) fdm.nan_count++; + if (isnan(fdm.ecef_ecef_accel.y)) fdm.nan_count++; + if (isnan(fdm.ecef_ecef_accel.z)) fdm.nan_count++; + if (isnan(fdm.body_ecef_vel.x)) fdm.nan_count++; + if (isnan(fdm.body_ecef_vel.y)) fdm.nan_count++; + if (isnan(fdm.body_ecef_vel.z)) fdm.nan_count++; + if (isnan(fdm.body_ecef_accel.x)) fdm.nan_count++; + if (isnan(fdm.body_ecef_accel.y)) fdm.nan_count++; + if (isnan(fdm.body_ecef_accel.z)) fdm.nan_count++; + if (isnan(fdm.ltp_ecef_vel.x)) fdm.nan_count++; + if (isnan(fdm.ltp_ecef_vel.y)) fdm.nan_count++; + if (isnan(fdm.ltp_ecef_vel.z)) fdm.nan_count++; + if (isnan(fdm.ltp_ecef_accel.x)) fdm.nan_count++; + if (isnan(fdm.ltp_ecef_accel.y)) fdm.nan_count++; + if (isnan(fdm.ltp_ecef_accel.z)) fdm.nan_count++; + if (isnan(fdm.ltpprz_ecef_vel.x)) fdm.nan_count++; + if (isnan(fdm.ltpprz_ecef_vel.y)) fdm.nan_count++; + if (isnan(fdm.ltpprz_ecef_vel.z)) fdm.nan_count++; + if (isnan(fdm.ltpprz_ecef_accel.x)) fdm.nan_count++; + if (isnan(fdm.ltpprz_ecef_accel.y)) fdm.nan_count++; + if (isnan(fdm.ltpprz_ecef_accel.z)) fdm.nan_count++; + if (isnan(fdm.ecef_to_body_quat.qi)) fdm.nan_count++; + if (isnan(fdm.ecef_to_body_quat.qx)) fdm.nan_count++; + if (isnan(fdm.ecef_to_body_quat.qy)) fdm.nan_count++; + if (isnan(fdm.ecef_to_body_quat.qz)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_quat.qi)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_quat.qx)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_quat.qy)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_quat.qz)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_eulers.phi)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_eulers.theta)) fdm.nan_count++; + if (isnan(fdm.ltp_to_body_eulers.psi)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_quat.qi)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_quat.qx)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_quat.qy)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_quat.qz)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_eulers.phi)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_eulers.theta)) fdm.nan_count++; + if (isnan(fdm.ltpprz_to_body_eulers.psi)) fdm.nan_count++; + if (isnan(fdm.body_ecef_rotvel.p)) fdm.nan_count++; + if (isnan(fdm.body_ecef_rotvel.q)) fdm.nan_count++; + if (isnan(fdm.body_ecef_rotvel.r)) fdm.nan_count++; + if (isnan(fdm.body_ecef_rotaccel.p)) fdm.nan_count++; + if (isnan(fdm.body_ecef_rotaccel.q)) fdm.nan_count++; + if (isnan(fdm.body_ecef_rotaccel.r)) fdm.nan_count++; + if (isnan(fdm.ltp_g.x)) fdm.nan_count++; + if (isnan(fdm.ltp_g.y)) fdm.nan_count++; + if (isnan(fdm.ltp_g.z)) fdm.nan_count++; + if (isnan(fdm.ltp_h.x)) fdm.nan_count++; + if (isnan(fdm.ltp_h.y)) fdm.nan_count++; + if (isnan(fdm.ltp_h.z)) fdm.nan_count++; + + return (fdm.nan_count - orig_nan_count); +} From d1a4ccc9bb024623a48cadebe94356b141bf8c29 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 7 Aug 2013 23:35:42 +0200 Subject: [PATCH 050/309] [rotorcraft] call ahrs_update_gps This makes AHRS_USE_GPS_HEADING usable on rotorcraft firmware as well. Thanks Pranay. --- sw/airborne/firmwares/rotorcraft/main.c | 1 + sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c | 3 +++ 2 files changed, 4 insertions(+) diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 092015fc25..5d5ac26398 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -300,6 +300,7 @@ static inline void on_baro_dif_event( void ) { } static inline void on_gps_event(void) { + ahrs_update_gps(); ins_update_gps(); #ifdef USE_VEHICLE_INTERFACE if (gps.fix == GPS_FIX_3D) diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c index 2ad5bc5d43..3b6203273a 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c @@ -119,6 +119,9 @@ void ahrs_propagate(void) { set_body_state_from_quat(); } +void ahrs_update_gps(void) { +} + void ahrs_update_accel(void) { struct FloatVect3 imu_g; ACCELS_FLOAT_OF_BFP(imu_g, imu.accel); From 9d52cfa9211743da2cdb2c1a8c9b82cea5aff2ab Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 00:22:13 +0200 Subject: [PATCH 051/309] [nps] only declare isnan on osx --- sw/simulator/nps/nps_fdm_jsbsim.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/sw/simulator/nps/nps_fdm_jsbsim.c b/sw/simulator/nps/nps_fdm_jsbsim.c index 4fccf4e4ea..c33307c82d 100644 --- a/sw/simulator/nps/nps_fdm_jsbsim.c +++ b/sw/simulator/nps/nps_fdm_jsbsim.c @@ -483,9 +483,11 @@ void lla_from_jsbsim_geodetic(LlaCoor_d* fdm_lla, FGPropagate* propagate) { } -/* Why isn't this there when we include math.h? */ +#ifdef __APPLE__ +/* Why isn't this there when we include math.h (on osx with clang)? */ /// Check if a double is NaN. static int isnan(double f) { return (f != f); } +#endif /** * Checks NpsFdm struct for NaNs. From 6acdf25b96be7fd443f3300a4b330be0a32034ab Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Wed, 7 Aug 2013 16:23:32 -0600 Subject: [PATCH 052/309] [conf][nps] Temporary addition of fw jsbsim models --- .../jsbsim/aircraft/Engines/18x8.xml | 51 ++ .../jsbsim/aircraft/Engines/Zenoah_G-26A.xml | 8 + .../jsbsim/aircraft/LisaAspirin2.xml | 546 ++++++++++++++++++ 3 files changed, 605 insertions(+) create mode 100644 conf/simulator/jsbsim/aircraft/Engines/18x8.xml create mode 100644 conf/simulator/jsbsim/aircraft/Engines/Zenoah_G-26A.xml create mode 100644 conf/simulator/jsbsim/aircraft/LisaAspirin2.xml diff --git a/conf/simulator/jsbsim/aircraft/Engines/18x8.xml b/conf/simulator/jsbsim/aircraft/Engines/18x8.xml new file mode 100644 index 0000000000..3dd84ebec3 --- /dev/null +++ b/conf/simulator/jsbsim/aircraft/Engines/18x8.xml @@ -0,0 +1,51 @@ + + + + + + 0.00085 + 18.0 + 2 + 30 + 30 + + + + 0.0 0.0776 + 0.1 0.0744 + 0.2 0.0712 + 0.3 0.0655 + 0.4 0.0588 + 0.5 0.0518 + 0.6 0.0419 + 0.7 0.0318 + 0.8 0.0172 + 1.0 -0.0058 + 1.4 -0.0549 + +
+ + + + 0.0 0.0902 + 0.1 0.0893 + 0.2 0.0880 + 0.3 0.0860 + 0.4 0.0810 + 0.5 0.0742 + 0.6 0.0681 + 0.7 0.0572 + 0.8 0.0467 + 1.0 0.0167 + 1.4 -0.0803 + +
+ +
diff --git a/conf/simulator/jsbsim/aircraft/Engines/Zenoah_G-26A.xml b/conf/simulator/jsbsim/aircraft/Engines/Zenoah_G-26A.xml new file mode 100644 index 0000000000..86d43a827e --- /dev/null +++ b/conf/simulator/jsbsim/aircraft/Engines/Zenoah_G-26A.xml @@ -0,0 +1,8 @@ + + + + + + + 2207.27 + diff --git a/conf/simulator/jsbsim/aircraft/LisaAspirin2.xml b/conf/simulator/jsbsim/aircraft/LisaAspirin2.xml new file mode 100644 index 0000000000..b3dafa86fc --- /dev/null +++ b/conf/simulator/jsbsim/aircraft/LisaAspirin2.xml @@ -0,0 +1,546 @@ + + + + + + Author Name + Creation Date + Version + Models a Malolo + + + + 10.57 + 9.17 + 1.15 + 1.69 + 3.28 + 1.06 + 0 + + 37.4 + 0 + 0 + + + 20 + 0 + 5 + + + 0 + 0 + 0 + + + + + 1 + 1 + 2 + 0 + 0 + 0 + 12 + + 36.4 + 0 + 4 + + + 1 + + 0 + 0 + 0 + + + + + + + + 40.1 + -9.9 + -10.1 + + 0.8 + 0.5 + 0.02 + 120 + 20 + 0.0 + LEFT + 0 + + + + 40.1 + 9.9 + -10.1 + + 0.8 + 0.5 + 0.02 + 120 + 20 + 0.0 + RIGHT + 0 + + + + 68.9 + 0 + -4.3 + + 0.8 + 0.5 + 0.02 + 24 + 20 + 360.0 + NONE + 0 + + + + 10 + 0 + -8.3 + + 0.8 + 0.5 + 0.02 + 24 + 20 + 360.0 + NONE + 0 + + + + + + + + 36 + 0 + 0 + + + 0.0 + 0 + 0 + + 0 + + + 1 + 0 + 0 + + + 0.0 + 0.0 + 0.0 + + 1.0 + + + + + 36.36 + 0 + -1.89375 + + 1.5 + 1.5 + + + + + + + + fcs/elevator-cmd-norm + fcs/pitch-trim-cmd-norm + + -1 + 1 + + + + + fcs/pitch-trim-sum + + -0.35 + 0.3 + + fcs/elevator-pos-rad + + + + fcs/elevator-pos-rad + + -0.3 + 0.3 + + + -1 + 1 + + fcs/elevator-pos-norm + + + + fcs/aileron-cmd-norm + fcs/roll-trim-cmd-norm + + -1 + 1 + + + + + fcs/roll-trim-sum + + -0.35 + 0.35 + + fcs/left-aileron-pos-rad + + + + -fcs/roll-trim-sum + + -0.35 + 0.35 + + fcs/right-aileron-pos-rad + + + + fcs/left-aileron-pos-rad + + -0.35 + 0.35 + + + -1 + 1 + + fcs/left-aileron-pos-norm + + + + fcs/right-aileron-pos-rad + + -0.35 + 0.35 + + + -1 + 1 + + fcs/right-aileron-pos-norm + + + + fcs/rudder-cmd-norm + fcs/yaw-trim-cmd-norm + + -1 + 1 + + + + + fcs/rudder-command-sum + + -0.35 + 0.35 + + fcs/rudder-pos-rad + + + + fcs/rudder-pos-rad + + -0.35 + 0.35 + + + -1 + 1 + + fcs/rudder-pos-norm + + + + + + + + Drag_at_zero_lift + + aero/qbar-psf + metrics/Sw-sqft + + aero/alpha-rad + + -1.5700 1.5000 + -0.2600 0.0560 + 0.0000 0.0280 + 0.2600 0.0560 + 1.5700 1.5000 + +
+
+
+ + Induced_drag + + aero/qbar-psf + metrics/Sw-sqft + aero/cl-squared + 0.0400 + + + + Drag_due_to_sideslip + + aero/qbar-psf + metrics/Sw-sqft + + aero/beta-rad + + -1.5700 1.2300 + -0.2600 0.0500 + 0.0000 0.0000 + 0.2600 0.0500 + 1.5700 1.2300 + +
+
+
+ + Drag_due_to_Elevator_Deflection + + aero/qbar-psf + metrics/Sw-sqft + fcs/elevator-pos-norm + 0.0300 + + +
+ + + + Side_force_due_to_beta + + aero/qbar-psf + metrics/Sw-sqft + aero/beta-rad + -1.0000 + + + + + + + Lift_due_to_alpha + + aero/qbar-psf + metrics/Sw-sqft + + aero/alpha-rad + + -0.2000 -0.7500 + 0.0000 0.2500 + 0.2300 1.4000 + 0.6000 0.7100 + +
+
+
+ + Lift_due_to_Elevator_Deflection + + aero/qbar-psf + metrics/Sw-sqft + fcs/elevator-pos-rad + 0.2000 + + +
+ + + + Roll_moment_due_to_beta + + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + aero/beta-rad + -0.1000 + + + + Roll_moment_due_to_roll_rate + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + aero/bi2vel + velocities/p-aero-rad_sec + -0.4000 + + + + Roll_moment_due_to_yaw_rate + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + aero/bi2vel + velocities/r-aero-rad_sec + 0.1500 + + + + Roll_moment_due_to_aileron + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + fcs/left-aileron-pos-rad + + velocities/mach + + 0.0000 0.1300 + 2.0000 0.0570 + +
+
+
+ + Roll_moment_due_to_rudder + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + fcs/rudder-pos-rad + 0.0100 + + +
+ + + + Pitch_moment_due_to_alpha + + aero/qbar-psf + metrics/Sw-sqft + metrics/cbarw-ft + aero/alpha-rad + -0.5000 + + + + Pitch_moment_due_to_elevator + + aero/qbar-psf + metrics/Sw-sqft + metrics/cbarw-ft + fcs/elevator-pos-rad + + velocities/mach + + 0.0000 -0.5000 + 2.0000 -0.2750 + +
+
+
+ + Pitch_moment_due_to_pitch_rate + + aero/qbar-psf + metrics/Sw-sqft + metrics/cbarw-ft + aero/ci2vel + velocities/q-aero-rad_sec + -12.0000 + + + + Pitch_moment_due_to_alpha_rate + + aero/qbar-psf + metrics/Sw-sqft + metrics/cbarw-ft + aero/ci2vel + aero/alphadot-rad_sec + -7.0000 + + +
+ + + + Yaw_moment_due_to_beta + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + aero/beta-rad + 0.1200 + + + + Yaw_moment_due_to_yaw_rate + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + aero/bi2vel + velocities/r-aero-rad_sec + -0.1500 + + + + Yaw_moment_due_to_rudder + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + fcs/rudder-pos-rad + -0.0500 + + + + Adverse_yaw + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + fcs/left-aileron-pos-rad + -0.0300 + + + + Yaw_moment_due_to_tail_incidence + + aero/qbar-psf + metrics/Sw-sqft + metrics/bw-ft + 0.0007 + + + +
+
From 1827ed12a9aea72dedba2b0c043befb424882e62 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 13:41:38 +0200 Subject: [PATCH 053/309] [nps][gps] calc utm, ned_vel, gspeed, course --- conf/airframes/examples/MentorEnergy.xml | 1 + .../fixedwing/gps_mediatek_diy.makefile | 2 +- .../subsystems/fixedwing/gps_nmea.makefile | 2 +- .../subsystems/fixedwing/gps_skytraq.makefile | 2 +- .../subsystems/fixedwing/gps_ublox.makefile | 2 +- .../fixedwing/gps_ublox_utm.makefile | 2 +- sw/airborne/subsystems/gps/gps_sim_nps.c | 39 +++++++++++++++++++ 7 files changed, 45 insertions(+), 5 deletions(-) diff --git a/conf/airframes/examples/MentorEnergy.xml b/conf/airframes/examples/MentorEnergy.xml index 5be694de14..20861aca00 100644 --- a/conf/airframes/examples/MentorEnergy.xml +++ b/conf/airframes/examples/MentorEnergy.xml @@ -260,6 +260,7 @@ +
diff --git a/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile b/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile index 54683c318d..931c35fed0 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile @@ -24,7 +24,7 @@ sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c -nps.CFLAGS += -DUSE_GPS +nps.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG nps.srcs += $(SRC_SUBSYSTEMS)/gps.c nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\" nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c diff --git a/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile b/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile index 9ef644bd63..cf03afedac 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile @@ -24,7 +24,7 @@ sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c -nps.CFLAGS += -DUSE_GPS +nps.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG nps.srcs += $(SRC_SUBSYSTEMS)/gps.c nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\" nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c diff --git a/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile b/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile index 5bc8ebfd47..2e04091ffc 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile @@ -21,7 +21,7 @@ sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim. -nps.CFLAGS += -DUSE_GPS +nps.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG nps.srcs += $(SRC_SUBSYSTEMS)/gps.c nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\" nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c diff --git a/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile b/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile index f12fa83792..5860741b4c 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile @@ -23,7 +23,7 @@ sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c -nps.CFLAGS += -DUSE_GPS +nps.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG nps.srcs += $(SRC_SUBSYSTEMS)/gps.c nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\" nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c diff --git a/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile b/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile index 9423d0eaf5..0865b4f8c7 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile @@ -22,7 +22,7 @@ sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c -nps.CFLAGS += -DUSE_GPS +nps.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG nps.srcs += $(SRC_SUBSYSTEMS)/gps.c nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\" nps.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c diff --git a/sw/airborne/subsystems/gps/gps_sim_nps.c b/sw/airborne/subsystems/gps/gps_sim_nps.c index 55c935af60..549630a8d5 100644 --- a/sw/airborne/subsystems/gps/gps_sim_nps.c +++ b/sw/airborne/subsystems/gps/gps_sim_nps.c @@ -22,6 +22,12 @@ #include "subsystems/gps/gps_sim_nps.h" #include "subsystems/gps.h" +#if GPS_USE_LATLONG +/* currently needed to get nav_utm_zone0 */ +#include "subsystems/navigation/common_nav.h" +#include "math/pprz_geodetic_float.h" +#endif + bool_t gps_available; void gps_feed_value() { @@ -36,6 +42,39 @@ void gps_feed_value() { gps.lla_pos.lon = sensors.gps.lla_pos.lon * 1e7; gps.lla_pos.alt = sensors.gps.lla_pos.alt * 1000.; gps.hmsl = sensors.gps.hmsl * 1000.; + + /* calc NED speed from ECEF */ + struct LtpDef_d ref_ltp; + ltp_def_from_ecef_d(&ref_ltp, &sensors.gps.ecef_pos); + struct NedCoor_d ned_vel_d; + ned_of_ecef_vect_d(&ned_vel_d, &ref_ltp, &sensors.gps.ecef_vel); + gps.ned_vel.x = ned_vel_d.x * 100; + gps.ned_vel.y = ned_vel_d.y * 100; + gps.ned_vel.z = ned_vel_d.z * 100; + + /* horizontal and 3d ground speed in cm/s */ + gps.gspeed = sqrt(ned_vel_d.x * ned_vel_d.x + ned_vel_d.y * ned_vel_d.y) * 100; + gps.speed_3d = sqrt(ned_vel_d.x * ned_vel_d.x + ned_vel_d.y * ned_vel_d.y + ned_vel_d.z * ned_vel_d.z) * 100; + + /* ground course in radians * 1e7 */ + gps.course = atan2(ned_vel_d.y, ned_vel_d.x) * 1e7; + +#if GPS_USE_LATLONG + /* Computes from (lat, long) in the referenced UTM zone */ + struct LlaCoor_f lla_f; + lla_f.lat = ((float) gps.lla_pos.lat) / 1e7; + lla_f.lon = ((float) gps.lla_pos.lon) / 1e7; + struct UtmCoor_f utm_f; + utm_f.zone = nav_utm_zone0; + /* convert to utm */ + utm_of_lla_f(&utm_f, &lla_f); + /* copy results of utm conversion */ + gps.utm_pos.east = utm_f.east*100; + gps.utm_pos.north = utm_f.north*100; + gps.utm_pos.alt = gps.lla_pos.alt; + gps.utm_pos.zone = nav_utm_zone0; +#endif + gps.fix = GPS_FIX_3D; gps_available = TRUE; } From e8dbf9b03661a3ae86d49de0c106188fb450d49b Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Sat, 8 Jun 2013 17:58:37 +0200 Subject: [PATCH 054/309] [fixedwing] additonals for energy ctrl better handling for engine out and max_acc can be set in airframe closes #497 --- .../firmwares/fixedwing/guidance/energy_ctrl.c | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c b/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c index 3f07c7b0ac..27095c67eb 100644 --- a/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c +++ b/sw/airborne/firmwares/fixedwing/guidance/energy_ctrl.c @@ -95,7 +95,7 @@ float v_ctl_airspeed_pgain; float v_ctl_altitude_error; ///< in meters, (setpoint - alt) -> positive = too low float v_ctl_max_climb; -float v_ctl_max_acceleration = 0.5; +float v_ctl_max_acceleration; /* inner loop */ float v_ctl_climb_setpoint; @@ -145,10 +145,16 @@ float v_ctl_pitch_setpoint; #warning "No STALL_AIRSPEED defined. Using NOMINAL_AIRSPEED" #define STALL_AIRSPEED NOMINAL_AIRSPEED #endif +#ifndef V_CTL_GLIDE_RATIO +#define V_CTL_GLIDE_RATIO 8. +#warning "V_CTL_GLIDE_RATIO not defined - default is 8." +#endif #ifndef AIRSPEED_SETPOINT_SLEW #define AIRSPEED_SETPOINT_SLEW 1 #endif - +#ifndef V_CTL_MAX_ACCELERATION +#define V_CTL_MAX_ACCELERATION 0.5 +#endif ///////////////////////////////////////////////// // Automatically found airplane characteristics @@ -212,6 +218,8 @@ void v_ctl_init( void ) { v_ctl_auto_airspeed_setpoint_slew = v_ctl_auto_airspeed_setpoint; v_ctl_airspeed_pgain = V_CTL_AIRSPEED_PGAIN; + v_ctl_max_acceleration = V_CTL_MAX_ACCELERATION; + /* inner loops */ v_ctl_climb_setpoint = 0.; @@ -345,7 +353,7 @@ void v_ctl_climb_loop( void ) float vdot_err = low_pass_vdot( v_ctl_desired_acceleration - vdot ); // Flight Path Outerloop: positive means needs to climb more: needs extra energy - float gamma_err = (v_ctl_climb_setpoint - stateGetSpeedEnu_f()->z) / v_ctl_auto_airspeed_setpoint; + float gamma_err = (v_ctl_climb_setpoint - stateGetSpeedEnu_f()->z) / v_ctl_auto_airspeed_controlled; // Total Energy Error: positive means energy should be added float en_tot_err = gamma_err + vdot_err; @@ -392,6 +400,7 @@ void v_ctl_climb_loop( void ) + v_ctl_auto_pitch_of_airspeed_dgain * vdot + v_ctl_energy_diff_pgain * en_dis_err + v_ctl_auto_throttle_nominal_cruise_pitch; +if(kill_throttle) v_ctl_pitch_of_vz = v_ctl_pitch_of_vz - 1/V_CTL_GLIDE_RATIO; v_ctl_pitch_setpoint = v_ctl_pitch_of_vz + nav_pitch; Bound(v_ctl_pitch_setpoint,H_CTL_PITCH_MIN_SETPOINT,H_CTL_PITCH_MAX_SETPOINT) From 80051d8666a15e28e1a61cc11775a436496000e6 Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Mon, 29 Jul 2013 02:32:15 +0200 Subject: [PATCH 055/309] [modules] fix to use amsys airspeed for control --- sw/airborne/modules/sensors/airspeed_amsys.c | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/sw/airborne/modules/sensors/airspeed_amsys.c b/sw/airborne/modules/sensors/airspeed_amsys.c index b97bfdd413..af8ed58fee 100644 --- a/sw/airborne/modules/sensors/airspeed_amsys.c +++ b/sw/airborne/modules/sensors/airspeed_amsys.c @@ -111,10 +111,6 @@ void airspeed_amsys_read_periodic( void ) { i2c_receive(&AIRSPEED_AMSYS_I2C_DEV, &airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 4); #endif -#if USE_AIRSPEED - stateSetAirspeed_f(&airspeed_amsys); -#endif - #else // SITL extern float sim_air_speed; stateSetAirspeed_f(&sim_air_speed); @@ -179,6 +175,9 @@ void airspeed_amsys_read_event( void ) { airspeed_amsys = airspeed_filter * airspeed_old + (1 - airspeed_filter) * airspeed_amsys_tmp; airspeed_old = airspeed_amsys; //New value available +#if USE_AIRSPEED + stateSetAirspeed_f(&airspeed_amsys); +#endif } } /*else { From d86f3d23cb1decd6b0044c81f714ec2dd94fac32 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 9 Aug 2013 12:36:39 +0200 Subject: [PATCH 056/309] [modules] a little airspeed_amsys cleanup --- sw/airborne/modules/sensors/airspeed_amsys.c | 173 ++++++++++--------- 1 file changed, 95 insertions(+), 78 deletions(-) diff --git a/sw/airborne/modules/sensors/airspeed_amsys.c b/sw/airborne/modules/sensors/airspeed_amsys.c index af8ed58fee..9d92ebac7f 100644 --- a/sw/airborne/modules/sensors/airspeed_amsys.c +++ b/sw/airborne/modules/sensors/airspeed_amsys.c @@ -31,12 +31,6 @@ #include //#include -#if !USE_AIRSPEED -// Just a Warning --> We do't use it. -//#ifndef SENSOR_SYNC_SEND -//#warning either set USE_AIRSPEED or SENSOR_SYNC_SEND to use amsys_airspeed -//#endif -#endif #define AIRSPEED_AMSYS_ADDR 0xE8 // original F0 #ifndef AIRSPEED_AMSYS_SCALE @@ -87,107 +81,130 @@ bool_t airspeed_amsys_offset_init; double airspeed_amsys_offset_tmp; uint16_t airspeed_amsys_cnt; +void airspeed_amsys_downlink(void); + void airspeed_amsys_init( void ) { - airspeed_amsys_raw = 0; - airspeed_amsys = 0.0; - airspeed_amsys_p = 0.0; - airspeed_amsys_offset = 0; - airspeed_amsys_offset_tmp = 0; - airspeed_amsys_i2c_done = TRUE; - airspeed_amsys_valid = TRUE; - airspeed_amsys_offset_init = FALSE; - airspeed_scale = AIRSPEED_AMSYS_SCALE; - airspeed_filter = AIRSPEED_AMSYS_FILTER; - airspeed_amsys_i2c_trans.status = I2CTransDone; - airspeed_amsys_cnt = AIRSPEED_AMSYS_OFFSET_NBSAMPLES_INIT + AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG; + airspeed_amsys_raw = 0; + airspeed_amsys = 0.0; + airspeed_amsys_p = 0.0; + airspeed_amsys_offset = 0; + airspeed_amsys_offset_tmp = 0; + airspeed_amsys_i2c_done = TRUE; + airspeed_amsys_valid = TRUE; + airspeed_amsys_offset_init = FALSE; + airspeed_scale = AIRSPEED_AMSYS_SCALE; + airspeed_filter = AIRSPEED_AMSYS_FILTER; + airspeed_amsys_i2c_trans.status = I2CTransDone; + airspeed_amsys_cnt = AIRSPEED_AMSYS_OFFSET_NBSAMPLES_INIT + + AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG; } void airspeed_amsys_read_periodic( void ) { #ifndef SITL - if (airspeed_amsys_i2c_trans.status == I2CTransDone) + if (airspeed_amsys_i2c_trans.status == I2CTransDone) { #ifndef MEASURE_AMSYS_TEMPERATURE - i2c_receive(&AIRSPEED_AMSYS_I2C_DEV, &airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 2); + i2c_receive(&AIRSPEED_AMSYS_I2C_DEV, &airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 2); #else - i2c_receive(&AIRSPEED_AMSYS_I2C_DEV, &airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 4); + i2c_receive(&AIRSPEED_AMSYS_I2C_DEV, &airspeed_amsys_i2c_trans, AIRSPEED_AMSYS_ADDR, 4); #endif + } -#else // SITL - extern float sim_air_speed; - stateSetAirspeed_f(&sim_air_speed); +#elif !USE_NPS + extern float sim_air_speed; + stateSetAirspeed_f(&sim_air_speed); #endif //SITL -#ifdef AIRSPEED_AMSYS_SYNC_SEND - DOWNLINK_SEND_AMSYS_AIRSPEED(DefaultChannel, DefaultDevice, &airspeed_amsys_raw, &airspeed_amsys_p, &airspeed_amsys_tmp, &airspeed_amsys, &airspeed_amsys_offset); -#else - RunOnceEvery(10, DOWNLINK_SEND_AMSYS_AIRSPEED(DefaultChannel, DefaultDevice, &airspeed_amsys_raw, &airspeed_amsys_p, &airspeed_amsys_tmp, &airspeed_amsys, &airspeed_temperature)); +#ifndef AIRSPEED_AMSYS_SYNC_SEND + RunOnceEvery(10, airspeed_amsys_downlink()); #endif } +void airspeed_amsys_downlink(void) { + DOWNLINK_SEND_AMSYS_AIRSPEED(DefaultChannel, DefaultDevice, + &airspeed_amsys_raw, &airspeed_amsys_p, + &airspeed_amsys_tmp, &airspeed_amsys, + &airspeed_temperature); +} + void airspeed_amsys_read_event( void ) { - // Get raw airspeed from buffer - airspeed_amsys_raw = 0; - airspeed_amsys_raw = (airspeed_amsys_i2c_trans.buf[0]<<8) | airspeed_amsys_i2c_trans.buf[1]; + // Get raw airspeed from buffer + airspeed_amsys_raw = 0; + airspeed_amsys_raw = (airspeed_amsys_i2c_trans.buf[0]<<8) | airspeed_amsys_i2c_trans.buf[1]; #ifdef MEASURE_AMSYS_TEMPERATURE - tempAS_amsys_raw = (airspeed_amsys_i2c_trans.buf[2]<<8) | airspeed_amsys_i2c_trans.buf[3]; - airspeed_temperature = (float)((float)(tempAS_amsys_raw-TEMPERATURE_AMSYS_OFFSET_MIN)/((float)(TEMPERATURE_AMSYS_OFFSET_MAX-TEMPERATURE_AMSYS_OFFSET_MIN)/TEMPERATURE_AMSYS_MAX)+TEMPERATURE_AMSYS_MIN);// Tmin=-25, Tmax=85 + tempAS_amsys_raw = (airspeed_amsys_i2c_trans.buf[2]<<8) | airspeed_amsys_i2c_trans.buf[3]; + const float temp_off_scale = (float)(TEMPERATURE_AMSYS_MAX) / + (TEMPERATURE_AMSYS_OFFSET_MAX - TEMPERATURE_AMSYS_OFFSET_MIN); + // Tmin=-25, Tmax=85 + airspeed_temperature = temp_off_scale * (tempAS_amsys_raw - TEMPERATURE_AMSYS_OFFSET_MIN) + + TEMPERATURE_AMSYS_MIN; #endif - // Check if this is valid airspeed - if (airspeed_amsys_raw == 0) - airspeed_amsys_valid = FALSE; - else - airspeed_amsys_valid = TRUE; + // Check if this is valid airspeed + if (airspeed_amsys_raw == 0) + airspeed_amsys_valid = FALSE; + else + airspeed_amsys_valid = TRUE; - // Continue only if a new airspeed value was received - if (airspeed_amsys_valid) { + // Continue only if a new airspeed value was received + if (airspeed_amsys_valid) { - // raw not under offest min - if (airspeed_amsys_rawAIRSPEED_AMSYS_OFFSET_MAX) - airspeed_amsys_raw = AIRSPEED_AMSYS_OFFSET_MAX; + // raw not under offest min + if (airspeed_amsys_raw < AIRSPEED_AMSYS_OFFSET_MIN) + airspeed_amsys_raw = AIRSPEED_AMSYS_OFFSET_MIN; + // raw not over offest max + if (airspeed_amsys_raw > AIRSPEED_AMSYS_OFFSET_MAX) + airspeed_amsys_raw = AIRSPEED_AMSYS_OFFSET_MAX; - // calculate raw to pressure - airspeed_amsys_p = (float)(airspeed_amsys_raw-AIRSPEED_AMSYS_OFFSET_MIN)*AIRSPEED_AMSYS_MAXPRESURE/(float)(AIRSPEED_AMSYS_OFFSET_MAX-AIRSPEED_AMSYS_OFFSET_MIN); - if (!airspeed_amsys_offset_init) { - --airspeed_amsys_cnt; - // Check if averaging completed - if (airspeed_amsys_cnt == 0) { - // Calculate average - airspeed_amsys_offset = (float)(airspeed_amsys_offset_tmp / AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG); - airspeed_amsys_offset_init = TRUE; - } - // Check if averaging needs to continue - else if (airspeed_amsys_cnt <= AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG) - airspeed_amsys_offset_tmp += airspeed_amsys_p; + // calculate raw to pressure + const float p_off_scale = (float)(AIRSPEED_AMSYS_MAXPRESURE) / + (AIRSPEED_AMSYS_OFFSET_MAX - AIRSPEED_AMSYS_OFFSET_MIN); + airspeed_amsys_p = p_off_scale * (airspeed_amsys_raw - AIRSPEED_AMSYS_OFFSET_MIN); - airspeed_amsys = 0.; + if (!airspeed_amsys_offset_init) { + --airspeed_amsys_cnt; + // Check if averaging completed + if (airspeed_amsys_cnt == 0) { + // Calculate average + airspeed_amsys_offset = airspeed_amsys_offset_tmp / AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG; + airspeed_amsys_offset_init = TRUE; + } + // Check if averaging needs to continue + else if (airspeed_amsys_cnt <= AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG) { + airspeed_amsys_offset_tmp += airspeed_amsys_p; + } - } - else { - airspeed_amsys_p = airspeed_amsys_p - airspeed_amsys_offset; - if (airspeed_amsys_p <= 0) airspeed_amsys_p=0.000000001; - airspeed_amsys_tmp = sqrtf(2*(airspeed_amsys_p)*airspeed_scale/1.2041); // convert pressure to airspeed - // Lowpassfiltering - airspeed_amsys = airspeed_filter * airspeed_old + (1 - airspeed_filter) * airspeed_amsys_tmp; - airspeed_old = airspeed_amsys; - //New value available + airspeed_amsys = 0.; + + } + else { + airspeed_amsys_p = airspeed_amsys_p - airspeed_amsys_offset; + if (airspeed_amsys_p <= 0) + airspeed_amsys_p = 0.000000001; + // convert pressure to airspeed + airspeed_amsys_tmp = sqrtf(2 * airspeed_amsys_p * airspeed_scale / 1.2041); + // Lowpassfiltering + airspeed_amsys = airspeed_filter * airspeed_old + + (1.0 - airspeed_filter) * airspeed_amsys_tmp; + airspeed_old = airspeed_amsys; + + //New value available #if USE_AIRSPEED - stateSetAirspeed_f(&airspeed_amsys); + stateSetAirspeed_f(&airspeed_amsys); #endif - } +#ifdef AIRSPEED_AMSYS_SYNC_SEND + airspeed_amsys_downlink(); +#endif + } - } /*else { - airspeed_amsys = 0.0; - }*/ + } + /*else { + airspeed_amsys = 0.0; + }*/ - - - // Transaction has been read - airspeed_amsys_i2c_trans.status = I2CTransDone; + // Transaction has been read + airspeed_amsys_i2c_trans.status = I2CTransDone; } From 96e2b7bd2c48ea48613a1cac7649deb25c32dc19 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 9 Aug 2013 15:03:24 +0200 Subject: [PATCH 057/309] [mcu_periph] replace gpio_output_[high|low] with gpio_[set|clear] That means using the already existing gpio_set and gpio_clear from libopencm3 for stm32. And defining these for the lpc. --- sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h | 4 ++-- sw/airborne/arch/stm32/mcu_periph/gpio_arch.h | 16 ++-------------- sw/airborne/subsystems/imu/imu_aspirin_i2c.c | 2 +- sw/airborne/subsystems/radio_control/sbus.c | 2 +- 4 files changed, 6 insertions(+), 18 deletions(-) diff --git a/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h b/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h index 8ccad960df..10ebdced39 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h +++ b/sw/airborne/arch/lpc21/mcu_periph/gpio_arch.h @@ -34,7 +34,7 @@ /** * Set a gpio output to high level. */ -static inline void gpio_output_high(uint32_t port, uint16_t pin) { +static inline void gpio_set(uint32_t port, uint16_t pin) { if (port == 0) IO0SET = _BV(pin); else if (port == 1) @@ -44,7 +44,7 @@ static inline void gpio_output_high(uint32_t port, uint16_t pin) { /** * Clear a gpio output to low level. */ -static inline void gpio_output_low(uint32_t port, uint16_t pin) { +static inline void gpio_clear(uint32_t port, uint16_t pin) { if (port == 0) IO0CLR = _BV(pin); else if (port == 1) diff --git a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h index 9d62af5e76..b9c27eebfe 100644 --- a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h +++ b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h @@ -24,6 +24,8 @@ * @ingroup stm32_arch * * GPIO helper functions for STM32F1 and STM32F4. + * + * The gpio_set and gpio_clear functions are already available from libopencm3. */ #ifndef GPIO_ARCH_H @@ -31,20 +33,6 @@ #include -/** - * Set a gpio output to high level. - */ -static inline void gpio_output_high(uint32_t port, uint16_t pin) { - gpio_set(port, pin); -} - -/** - * Clear a gpio output to low level. - */ -static inline void gpio_output_low(uint32_t port, uint16_t pin) { - gpio_clear(port, pin); -} - /** * Setup a gpio for input or output with alternate function. */ diff --git a/sw/airborne/subsystems/imu/imu_aspirin_i2c.c b/sw/airborne/subsystems/imu/imu_aspirin_i2c.c index 31b09932f9..a94ce32a77 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_i2c.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_i2c.c @@ -96,7 +96,7 @@ void imu_impl_init(void) // With CS tied high to VDD I/O, the ADXL345 is in I2C mode #ifdef ASPIRIN_I2C_CS_PORT gpio_setup_output(ASPIRIN_I2C_CS_PORT, ASPIRIN_I2C_CS_PIN); - gpio_output_high(ASPIRIN_I2C_CS_PORT, ASPIRIN_I2C_CS_PIN); + gpio_set(ASPIRIN_I2C_CS_PORT, ASPIRIN_I2C_CS_PIN); #endif /* Gyro configuration and initalization */ diff --git a/sw/airborne/subsystems/radio_control/sbus.c b/sw/airborne/subsystems/radio_control/sbus.c index 726e0781c5..184ad03400 100644 --- a/sw/airborne/subsystems/radio_control/sbus.c +++ b/sw/airborne/subsystems/radio_control/sbus.c @@ -52,7 +52,7 @@ * output low sets it to normal polarity. */ #ifndef RC_SET_POLARITY -#define RC_SET_POLARITY gpio_output_high +#define RC_SET_POLARITY gpio_set #endif From d1bb29394197bddb8a477b20bc67310fd5268acb Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 9 Aug 2013 16:15:58 +0200 Subject: [PATCH 058/309] set paparazzi_version to v5.1_devel --- paparazzi_version | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/paparazzi_version b/paparazzi_version index 0fde2c0289..f137c8e33c 100755 --- a/paparazzi_version +++ b/paparazzi_version @@ -1,6 +1,6 @@ #!/bin/sh -DEF_VER=v5.0.0_stable +DEF_VER=v5.1_devel # First try git describe (if running on a git repo), # then use default version from above (for release tarballs). From 732bdcde90fd57ae407cbd295a480a0b907cd681 Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Fri, 9 Aug 2013 16:26:31 +0200 Subject: [PATCH 059/309] fix to use ins_alt_dot with baro wen USE_BAROMETER is defined --- sw/airborne/subsystems/ins/ins_alt_float.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/ins/ins_alt_float.c b/sw/airborne/subsystems/ins/ins_alt_float.c index 317499318f..8f0004ffd1 100644 --- a/sw/airborne/subsystems/ins/ins_alt_float.c +++ b/sw/airborne/subsystems/ins/ins_alt_float.c @@ -105,6 +105,10 @@ void ins_update_baro() { UTM_COPY(utm, *stateGetPositionUtm_f()); utm.alt = ins_alt; stateSetPositionUtm_f(&utm); + struct NedCoor_f ned_vel; + memcpy(&ned_vel, stateGetSpeedNed_f(), sizeof(struct NedCoor_f)); + ned_vel.z = -ins_alt_dot; + stateSetSpeedNed_f(&ned_vel); } } #endif @@ -129,7 +133,7 @@ void ins_update_gps(void) { struct NedCoor_f ned_vel = { gps.ned_vel.x / 100., gps.ned_vel.y / 100., - gps.ned_vel.z / 100. + -ins_alt_dot }; // set velocity stateSetSpeedNed_f(&ned_vel); From 4fb1149bc1b9bba9a2ac790f10ca2e30461f965b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 9 Aug 2013 17:50:48 +0200 Subject: [PATCH 060/309] [modules] angle of attack sensor fix and cleanup --- conf/messages.xml | 8 +-- conf/modules/AOA_adc.xml | 10 ++-- .../modules/sensors/{AOA_adc.c => aoa_adc.c} | 55 ++++++++----------- .../modules/sensors/{AOA_adc.h => aoa_adc.h} | 33 ++++++----- 4 files changed, 50 insertions(+), 56 deletions(-) rename sw/airborne/modules/sensors/{AOA_adc.c => aoa_adc.c} (62%) rename sw/airborne/modules/sensors/{AOA_adc.h => aoa_adc.h} (64%) diff --git a/conf/messages.xml b/conf/messages.xml index 2ddf6a8999..5789a130bf 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -578,10 +578,10 @@ - - - - + + + + diff --git a/conf/modules/AOA_adc.xml b/conf/modules/AOA_adc.xml index fd42c505be..b9338b2f67 100644 --- a/conf/modules/AOA_adc.xml +++ b/conf/modules/AOA_adc.xml @@ -10,15 +10,13 @@
- +
- - + + - - - + diff --git a/sw/airborne/modules/sensors/AOA_adc.c b/sw/airborne/modules/sensors/aoa_adc.c similarity index 62% rename from sw/airborne/modules/sensors/AOA_adc.c rename to sw/airborne/modules/sensors/aoa_adc.c index bebcbe02fb..2cb7aeb284 100644 --- a/sw/airborne/modules/sensors/AOA_adc.c +++ b/sw/airborne/modules/sensors/aoa_adc.c @@ -21,14 +21,14 @@ */ /** - * @file modules/sensors/AOA_adc.c + * @file modules/sensors/aoa_adc.c * @brief Angle of Attack sensor on ADC * Autor: Bruzzlee * * ex: US DIGITAL MA3-A10-236-N */ -#include "modules/sensors/AOA_adc.h" +#include "modules/sensors/aoa_adc.h" #include "generated/airframe.h" #include "state.h" @@ -37,34 +37,25 @@ #include "messages.h" #include "subsystems/datalink/downlink.h" -// Default offset value (assuming 0 AOA is in the middle of the range) +/// Default offset value (assuming 0 AOA is in the middle of the range) #ifndef AOA_OFFSET #define AOA_OFFSET M_PI #endif -// Default filter value +/// Default filter value #ifndef AOA_FILTER #define AOA_FILTER 0.5 #endif -// Default sensitivity (2*pi on a 10 bit ADC) +/// Default sensitivity (2*pi on a 10 bit ADC) #ifndef AOA_SENS #define AOA_SENS ((2.0*M_PI)/1024) #endif -uint16_t adc_AOA_val; -float AOA_offset, AOA_filter; - -// Internal values -float AOA, AOA_old; // Downlink #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE #endif -#ifndef SITL // Use ADC if not in simulation - -#include "mcu_periph/adc.h" - #ifndef ADC_CHANNEL_AOA #error "ADC_CHANNEL_AOA needs to be defined to use AOA_adc module" #endif @@ -73,32 +64,30 @@ float AOA, AOA_old; #define ADC_CHANNEL_AOA_NB_SAMPLES DEFAULT_AV_NB_SAMPLE #endif -struct adc_buf buf_AOA; -#endif +struct Aoa_Adc aoa_adc; - -void AOA_adc_init( void ) { - AOA_offset = AOA_OFFSET; - AOA_filter = AOA_FILTER; - AOA_old = 0.0; - AOA = 0.0; -#ifndef SITL - adc_buf_channel(ADC_CHANNEL_AOA, &buf_AOA, ADC_CHANNEL_AOA_NB_SAMPLES); -#endif +void aoa_adc_init(void) { + aoa_adc.offset = AOA_OFFSET; + aoa_adc.filter = AOA_FILTER; + aoa_adc.sens = AOA_SENS; + aoa_adc.angle = 0.0; + adc_buf_channel(ADC_CHANNEL_AOA, &aoa_adc.buf, ADC_CHANNEL_AOA_NB_SAMPLES); } -void AOA_adc_update( void ) { -#ifndef SITL - adc_AOA_val = buf_AOA.sum / buf_AOA.av_nb_sample; +void aoa_adc_update(void) { + static float prev_aoa = 0.0; + + aoa_adc.raw = aoa_adc.buf.sum / aoa_adc.buf.av_nb_sample; // PT1 filter and convert to rad - AOA = AOA_filter * AOA_old + (1 - AOA_filter) * (adc_AOA_val*AOA_SENS - AOA_offset); - AOA_old = AOA; -#endif - RunOnceEvery(30, DOWNLINK_SEND_AOA_adc(DefaultChannel, DefaultDevice, &adc_AOA_val, &AOA)); + aoa_adc.angle = aoa_adc.filter * prev_aoa + + (1.0 - aoa_adc.filter) * (aoa_adc.raw * aoa_adc.sens - aoa_adc.offset); + prev_aoa = aoa_adc.angle; #ifdef USE_AOA - stateSetAngleOfAttack_f(AOA); + stateSetAngleOfAttack_f(&aoa_adc.angle); #endif + + RunOnceEvery(30, DOWNLINK_SEND_AOA_ADC(DefaultChannel, DefaultDevice, &aoa_adc.raw, &aoa_adc.angle)); } diff --git a/sw/airborne/modules/sensors/AOA_adc.h b/sw/airborne/modules/sensors/aoa_adc.h similarity index 64% rename from sw/airborne/modules/sensors/AOA_adc.h rename to sw/airborne/modules/sensors/aoa_adc.h index 8ab1741173..02c429c52d 100644 --- a/sw/airborne/modules/sensors/AOA_adc.h +++ b/sw/airborne/modules/sensors/aoa_adc.h @@ -21,7 +21,7 @@ */ /** - * @file modules/sensors/AOA_adc.c + * @file modules/sensors/aoa_adc.c * @brief Angle of Attack sensor on ADC * Autor: Bruzzlee * @@ -32,20 +32,27 @@ #define AOA_ADC_H #include "std.h" +#include "mcu_periph/adc.h" -/** Raw ADC value */ -extern uint16_t adc_AOA_val; - -/** Angle of Attack offset */ -extern float AOA_offset; - -/** Filtering value [0-1[ - * 0: no filtering - * 1: output is a constant value +/** Angle of Attack sensor via ADC. */ -extern float AOA_filter; +struct Aoa_Adc { + struct adc_buf buf; + uint16_t raw; ///< raw ADC value + float angle; ///< Angle of attack in radians + float offset; ///< Angle of attack offset in radians + float sens; ///< sensitiviy, i.e. scale to conver raw to angle -void AOA_adc_init( void ); -void AOA_adc_update( void ); + /** Filtering value [0-1] + * 0: no filtering + * 1: output is a constant value + */ + float filter; +}; + +extern struct Aoa_Adc aoa_adc; + +void aoa_adc_init(void); +void aoa_adc_update(void); #endif /* AOA_ADC_H */ From 996837195b4acff3a32b6b74f6222354ab446ee2 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 9 Aug 2013 18:07:49 +0200 Subject: [PATCH 061/309] [dox] update comment in state inteface --- sw/airborne/state.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/state.h b/sw/airborne/state.h index b64ac2d95c..9818c0fafd 100644 --- a/sw/airborne/state.h +++ b/sw/airborne/state.h @@ -1156,7 +1156,7 @@ static inline void stateSetAirspeed_f(float* airspeed) { SetBit(state.wind_air_status, AIRSPEED_F); } -/// Set angle of attack (float). +/// Set angle of attack in radians (float). static inline void stateSetAngleOfAttack_f(float* aoa) { state.angle_of_attack_f = *aoa; /* clear bits for all AOA representations and only set the new one */ @@ -1164,7 +1164,7 @@ static inline void stateSetAngleOfAttack_f(float* aoa) { SetBit(state.wind_air_status, AOA_F); } -/// Set angle of attack (float). +/// Set sideslip angle in radians (float). static inline void stateSetSideslip_f(float* sideslip) { state.sideslip_f = *sideslip; /* clear bits for all sideslip representations and only set the new one */ From 66e8644fa1ae1f94e90ee1879700e53fd31bc904 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 9 Aug 2013 18:35:20 +0200 Subject: [PATCH 062/309] improve paparazzi_version if git tags are not found --- paparazzi_version | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/paparazzi_version b/paparazzi_version index f137c8e33c..6b01cf7563 100755 --- a/paparazzi_version +++ b/paparazzi_version @@ -6,7 +6,13 @@ DEF_VER=v5.1_devel # then use default version from above (for release tarballs). if test -d .git -o -f .git then - VN=$(git describe --match "v[0-9].[0-9]*" --dirty --always --long) + GIT_VN=$(git describe --match "v[0-9].[0-9]*" --dirty --always --long) + if echo "$GIT_VN" | grep -Eq "^v[0-9].[0-9]" + then + VN="$GIT_VN" + else + VN="$DEF_VER"-none-g"$GIT_VN" + fi else VN="$DEF_VER" fi From 446292761be57077dd68f35540a1ab2fe34e4853 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 19:13:28 +0200 Subject: [PATCH 063/309] [modules] baro_board: only call event handler if there is new data --- sw/airborne/modules/sensors/baro_MS5534A.h | 2 +- sw/airborne/modules/sensors/baro_amsys.h | 2 +- sw/airborne/modules/sensors/baro_bmp.h | 2 +- sw/airborne/modules/sensors/baro_board_module.h | 6 ++---- sw/airborne/modules/sensors/baro_ets.h | 2 +- sw/airborne/modules/sensors/baro_ms5611_i2c.h | 2 +- sw/airborne/modules/sensors/baro_scp.h | 2 +- 7 files changed, 8 insertions(+), 10 deletions(-) diff --git a/sw/airborne/modules/sensors/baro_MS5534A.h b/sw/airborne/modules/sensors/baro_MS5534A.h index 94568c892d..7e98fa1c34 100644 --- a/sw/airborne/modules/sensors/baro_MS5534A.h +++ b/sw/airborne/modules/sensors/baro_MS5534A.h @@ -54,7 +54,7 @@ void baro_MS5534A_event_task( void ); void baro_MS5534A_event( void ); -#define BaroMS5534AUpdate(_b) { if (baro_MS5534A_available) { _b = baro_MS5534A_pressure; baro_MS5534A_available = FALSE; } } +#define BaroMS5534AUpdate(_b, _h) { if (baro_MS5534A_available) { _b = baro_MS5534A_pressure; _h(); baro_MS5534A_available = FALSE; } } #endif // USE_BARO_MS5534A diff --git a/sw/airborne/modules/sensors/baro_amsys.h b/sw/airborne/modules/sensors/baro_amsys.h index 94429a402e..287f0c3e5f 100644 --- a/sw/airborne/modules/sensors/baro_amsys.h +++ b/sw/airborne/modules/sensors/baro_amsys.h @@ -47,6 +47,6 @@ extern void baro_amsys_read_event( void ); #define BaroAmsysEvent() { if (baro_amsys_i2c_trans.status == I2CTransSuccess) baro_amsys_read_event(); } -#define BaroAmsysUpdate(_b) { if (baro_amsys_valid) { _b = baro_amsys_adc; baro_amsys_valid = FALSE; } } +#define BaroAmsysUpdate(_b, _h) { if (baro_amsys_valid) { _b = baro_amsys_adc; _h(); baro_amsys_valid = FALSE; } } #endif // BARO_AMSYS_H diff --git a/sw/airborne/modules/sensors/baro_bmp.h b/sw/airborne/modules/sensors/baro_bmp.h index 53adeb184d..7db2fa66a2 100644 --- a/sw/airborne/modules/sensors/baro_bmp.h +++ b/sw/airborne/modules/sensors/baro_bmp.h @@ -51,6 +51,6 @@ void baro_bmp_init(void); void baro_bmp_periodic(void); void baro_bmp_event(void); -#define BaroBmpUpdate(_b) { if (baro_bmp_valid) { _b = baro_bmp_pressure; baro_bmp_valid = FALSE; } } +#define BaroBmpUpdate(_b, _h) { if (baro_bmp_valid) { _b = baro_bmp_pressure; _h(); baro_bmp_valid = FALSE; } } #endif diff --git a/sw/airborne/modules/sensors/baro_board_module.h b/sw/airborne/modules/sensors/baro_board_module.h index 3ea1e5682a..149e923f10 100644 --- a/sw/airborne/modules/sensors/baro_board_module.h +++ b/sw/airborne/modules/sensors/baro_board_module.h @@ -56,10 +56,8 @@ * Need to be maped to one the external baro running has a module */ #define BaroEvent(_b_abs_handler, _b_diff_handler) { \ - BARO_ABS_EVENT(baro.absolute); \ - BARO_DIFF_EVENT(baro.differential); \ - _b_abs_handler(); \ - _b_diff_handler(); \ + BARO_ABS_EVENT(baro.absolute, _b_abs_handler); \ + BARO_DIFF_EVENT(baro.differential, _b_diff_handler); \ } diff --git a/sw/airborne/modules/sensors/baro_ets.h b/sw/airborne/modules/sensors/baro_ets.h index c492ef8fc4..832280f60a 100644 --- a/sw/airborne/modules/sensors/baro_ets.h +++ b/sw/airborne/modules/sensors/baro_ets.h @@ -63,6 +63,6 @@ extern void baro_ets_read_event( void ); #define BaroEtsEvent() { if (baro_ets_i2c_trans.status == I2CTransSuccess) baro_ets_read_event(); } -#define BaroEtsUpdate(_b) { if (baro_ets_valid) { _b = baro_ets_adc; baro_ets_valid = FALSE; } } +#define BaroEtsUpdate(_b, _h) { if (baro_ets_valid) { _b = baro_ets_adc; _h(); baro_ets_valid = FALSE; } } #endif // BARO_ETS_H diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h index cad37d60db..2f575e8a37 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.h +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.h @@ -42,6 +42,6 @@ extern void baro_ms5611_d1(void); extern void baro_ms5611_d2(void); extern void baro_ms5611_event(void); -#define BaroMs5611Update(_b) { if (baro_ms5611_valid) { _b = baro_ms5611_alt; baro_ms5611_valid = FALSE; } } +#define BaroMs5611Update(_b, _h) { if (baro_ms5611_valid) { _b = baro_ms5611_alt; _h(); baro_ms5611_valid = FALSE; } } #endif diff --git a/sw/airborne/modules/sensors/baro_scp.h b/sw/airborne/modules/sensors/baro_scp.h index 2619adb96d..77aeb504d1 100644 --- a/sw/airborne/modules/sensors/baro_scp.h +++ b/sw/airborne/modules/sensors/baro_scp.h @@ -20,6 +20,6 @@ void baro_scp_init(void); void baro_scp_periodic(void); void baro_scp_event(void); -#define BaroScpUpdate(_b) { if (baro_scp_available) { _b = baro_scp_pressure; baro_scp_available = FALSE; } } +#define BaroScpUpdate(_b, _h) { if (baro_scp_available) { _b = baro_scp_pressure; _h(); baro_scp_available = FALSE; } } #endif From 3e1d23df45947f9a0e79be9b1ec77f776c95494d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 19:45:18 +0200 Subject: [PATCH 064/309] [modules] fix warning in baro_board --- sw/airborne/modules/sensors/baro_board_module.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/modules/sensors/baro_board_module.h b/sw/airborne/modules/sensors/baro_board_module.h index 149e923f10..57ae9dd4af 100644 --- a/sw/airborne/modules/sensors/baro_board_module.h +++ b/sw/airborne/modules/sensors/baro_board_module.h @@ -50,7 +50,7 @@ #define BARO_DIFF_EVENT NoBaro #endif -#define NoBaro(_b) {} +#define NoBaro(_b, _h) {} /** BaroEvent macro. * Need to be maped to one the external baro running has a module From 80bfc56629940991f57a4578c8a7110ba31b502a Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Fri, 9 Aug 2013 23:16:57 +0200 Subject: [PATCH 065/309] [modules] baro_amsys: fix for DT to match BARO_READ_PERIODIC_PERIOD --- sw/airborne/modules/sensors/baro_amsys.h | 2 +- sw/airborne/subsystems/ins/ins_alt_float.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/modules/sensors/baro_amsys.h b/sw/airborne/modules/sensors/baro_amsys.h index 287f0c3e5f..1a22747b4d 100644 --- a/sw/airborne/modules/sensors/baro_amsys.h +++ b/sw/airborne/modules/sensors/baro_amsys.h @@ -28,7 +28,7 @@ #include "std.h" #include "mcu_periph/i2c.h" -#define BARO_AMSYS_DT 0.05 +#define BARO_AMSYS_DT BARO_AMSYS_READ_PERIODIC_PERIOD extern uint16_t baro_amsys_adc; // extern float baro_amsys_offset; diff --git a/sw/airborne/subsystems/ins/ins_alt_float.h b/sw/airborne/subsystems/ins/ins_alt_float.h index 2797e679c7..613ebc5281 100644 --- a/sw/airborne/subsystems/ins/ins_alt_float.h +++ b/sw/airborne/subsystems/ins/ins_alt_float.h @@ -33,7 +33,7 @@ #include #include "std.h" #include "state.h" - +#include "generated/modules.h" #if USE_BAROMETER #ifdef BARO_MS5534A From 2ff4e9d68d90a755bfdd7118db7f45d8c90b8c81 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 20:01:59 +0200 Subject: [PATCH 066/309] [modules] BARO_x_DT from generated BARO_x_PERIODIC_PERIOD --- sw/airborne/modules/sensors/baro_bmp.h | 8 +++++++- sw/airborne/modules/sensors/baro_ets.h | 3 ++- sw/airborne/modules/sensors/baro_ms5611_i2c.h | 4 +++- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/sw/airborne/modules/sensors/baro_bmp.h b/sw/airborne/modules/sensors/baro_bmp.h index 7db2fa66a2..860937bfe6 100644 --- a/sw/airborne/modules/sensors/baro_bmp.h +++ b/sw/airborne/modules/sensors/baro_bmp.h @@ -34,7 +34,13 @@ #define BARO_BMP_START_PRESS 4 #define BARO_BMP_READ_PRESS 5 -#define BARO_BMP_DT 0.05 +/// new measurement every 3rd baro_bmp_periodic +#ifndef SITL +#define BARO_BMP_DT (BARO_BMP_PERIODIC_PERIOID / 3) +#else +#define BARO_BMP_DT BARO_BMP_PERIODIC_PERIOID +#endif + extern bool_t baro_bmp_enabled; extern float baro_bmp_r; extern float baro_bmp_sigma2; diff --git a/sw/airborne/modules/sensors/baro_ets.h b/sw/airborne/modules/sensors/baro_ets.h index 832280f60a..33f7bbd592 100644 --- a/sw/airborne/modules/sensors/baro_ets.h +++ b/sw/airborne/modules/sensors/baro_ets.h @@ -45,7 +45,8 @@ #include "std.h" #include "mcu_periph/i2c.h" -#define BARO_ETS_DT 0.05 +/// new measurement every baro_ets_read_periodic +#define BARO_ETS_DT BARO_ETS_READ_PERIODIC_PERIOD extern uint16_t baro_ets_adc; extern uint16_t baro_ets_offset; diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h index 2f575e8a37..2f34e8fcff 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.h +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.h @@ -12,7 +12,9 @@ #define PROM_NB 8 -#define BARO_MS5611_DT 0.05 +/// new measurement every baro_ms5611_periodic +#define BARO_MS5611_DT BARO_MS5611_PERIODIC_PERIOID + #define BARO_MS5611_R 20 #define BARO_MS5611_SIGMA2 1 extern float baro_ms5611_alt; From 8fad7203dfcf8c51b016d3fdf896922d02d05867 Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Fri, 9 Aug 2013 23:33:03 +0200 Subject: [PATCH 067/309] [modules] baro_amsys: comment to match the other baro sensors --- sw/airborne/modules/sensors/baro_amsys.h | 1 + 1 file changed, 1 insertion(+) diff --git a/sw/airborne/modules/sensors/baro_amsys.h b/sw/airborne/modules/sensors/baro_amsys.h index 1a22747b4d..a6852dab58 100644 --- a/sw/airborne/modules/sensors/baro_amsys.h +++ b/sw/airborne/modules/sensors/baro_amsys.h @@ -28,6 +28,7 @@ #include "std.h" #include "mcu_periph/i2c.h" +/// new measurement every baro_amsys_read_periodic #define BARO_AMSYS_DT BARO_AMSYS_READ_PERIODIC_PERIOD extern uint16_t baro_amsys_adc; From 47d272d9ae9fb49e56b562fa959e2fd0af85abb5 Mon Sep 17 00:00:00 2001 From: softsr Date: Sun, 11 Aug 2013 03:52:58 -0700 Subject: [PATCH 068/309] KroozSD imu driver improvements Fixed magnetometer axes. Accel median filter disabled by default. closes #501 --- .../examples/krooz_sd/krooz_sd_hexa_mkk.xml | 30 +++++++------- .../examples/krooz_sd/krooz_sd_okto_mkk.xml | 26 ++++++------- .../examples/krooz_sd/krooz_sd_quad_mkk.xml | 38 ++++++++---------- .../examples/krooz_sd/krooz_sd_quad_pwm.xml | 37 ++++++++---------- sw/airborne/boards/krooz/imu_krooz.c | 39 +++++++++++++------ sw/airborne/boards/krooz/imu_krooz.h | 13 ++++++- 6 files changed, 96 insertions(+), 87 deletions(-) diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml b/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml index 36e979ea40..428fa2fe44 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml @@ -28,10 +28,11 @@ - - + + @@ -80,11 +81,6 @@ -
- - -
-
@@ -178,16 +174,16 @@ - - - + + + - - - + + + - + @@ -218,7 +214,7 @@
- + diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml b/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml index 40786c6218..ff2a2c3510 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml @@ -32,8 +32,9 @@ - + + --> + @@ -83,11 +84,6 @@ -
- - -
-
@@ -181,16 +177,16 @@ - - - + + + - - - + + + - + @@ -221,7 +217,7 @@
- + diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml b/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml index 0b31cd058e..9166f503b2 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml @@ -32,6 +32,7 @@ +
@@ -61,11 +62,6 @@ -
- - -
-
@@ -95,12 +91,12 @@ - - - - - - + + + + + + @@ -167,20 +163,20 @@ - - + + - - - + + + - - - + + + - + @@ -210,7 +206,7 @@
- + diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml b/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml index 9f3d371545..df4334d751 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml @@ -29,9 +29,11 @@ - - + + @@ -56,11 +58,6 @@ -
- - -
-
@@ -162,21 +159,21 @@ - - + + - - - + + + - - - + + + - - - + + + @@ -205,7 +202,7 @@
- + diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index 3aad6a7803..01fb83e3d2 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -33,6 +33,7 @@ #include "subsystems/imu/imu_krooz_sd_arch.h" #include "mcu_periph/i2c.h" #include "led.h" +#include "filters/median_filter.h" // Downlink #include "mcu_periph/uart.h" @@ -63,10 +64,13 @@ PRINT_CONFIG_VAR(KROOZ_ACCEL_RANGE) struct ImuKrooz imu_krooz; -#if KROOZ_USE_MEDIAN_FILTER -#include "filters/median_filter.h" -struct MedianFilter3Int median_gyro, median_accel, median_mag; +#if IMU_KROOZ_USE_GYRO_MEDIAN_FILTER +struct MedianFilter3Int median_gyro; #endif +#if IMU_KROOZ_USE_ACCEL_MEDIAN_FILTER +struct MedianFilter3Int median_accel; +#endif +struct MedianFilter3Int median_mag; void imu_impl_init( void ) { @@ -82,12 +86,14 @@ void imu_impl_init( void ) hmc58xx_init(&imu_krooz.hmc, &(IMU_KROOZ_I2C_DEV), HMC58XX_ADDR); -#if KROOZ_USE_MEDIAN_FILTER // Init median filters +#if IMU_KROOZ_USE_GYRO_MEDIAN_FILTER InitMedianFilterRatesInt(median_gyro); +#endif +#if IMU_KROOZ_USE_ACCEL_MEDIAN_FILTER InitMedianFilterVect3Int(median_accel); - InitMedianFilterVect3Int(median_mag); #endif + InitMedianFilterVect3Int(median_mag); RATES_ASSIGN(imu_krooz.rates_sum, 0, 0, 0); VECT3_ASSIGN(imu_krooz.accel_sum, 0, 0, 0); @@ -110,14 +116,25 @@ void imu_periodic( void ) hmc58xx_start_configure(&imu_krooz.hmc); if (imu_krooz.meas_nb) { - RATES_ASSIGN(imu.gyro_unscaled, imu_krooz.rates_sum.q / imu_krooz.meas_nb, imu_krooz.rates_sum.p / imu_krooz.meas_nb, imu_krooz.rates_sum.r / imu_krooz.meas_nb); -#if KROOZ_USE_MEDIAN_FILTER + RATES_ASSIGN(imu.gyro_unscaled, -imu_krooz.rates_sum.q / imu_krooz.meas_nb, imu_krooz.rates_sum.p / imu_krooz.meas_nb, imu_krooz.rates_sum.r / imu_krooz.meas_nb); +#if IMU_KROOZ_USE_GYRO_MEDIAN_FILTER UpdateMedianFilterRatesInt(median_gyro, imu.gyro_unscaled); #endif - VECT3_ASSIGN(imu.accel_unscaled, imu_krooz.accel_sum.y / imu_krooz.meas_nb, imu_krooz.accel_sum.x / imu_krooz.meas_nb, imu_krooz.accel_sum.z / imu_krooz.meas_nb); -#if KROOZ_USE_MEDIAN_FILTER + VECT3_ASSIGN(imu.accel_unscaled, -imu_krooz.accel_sum.y / imu_krooz.meas_nb, imu_krooz.accel_sum.x / imu_krooz.meas_nb, imu_krooz.accel_sum.z / imu_krooz.meas_nb); +#if IMU_KROOZ_USE_ACCEL_MEDIAN_FILTER UpdateMedianFilterVect3Int(median_accel, imu.accel_unscaled); #endif + + RATES_SMUL(imu_krooz.gyro_filtered, imu_krooz.gyro_filtered, IMU_KROOZ_GYRO_AVG_FILTER); + RATES_ADD(imu_krooz.gyro_filtered, imu.gyro_unscaled); + RATES_SDIV(imu_krooz.gyro_filtered, imu_krooz.gyro_filtered, (IMU_KROOZ_GYRO_AVG_FILTER + 1)); + RATES_COPY(imu.gyro_unscaled, imu_krooz.gyro_filtered); + + VECT3_SMUL(imu_krooz.accel_filtered, imu_krooz.accel_filtered, IMU_KROOZ_ACCEL_AVG_FILTER); + VECT3_ADD(imu_krooz.accel_filtered, imu.accel_unscaled); + VECT3_SDIV(imu_krooz.accel_filtered, imu_krooz.accel_filtered, (IMU_KROOZ_ACCEL_AVG_FILTER + 1)); + VECT3_COPY(imu.accel_unscaled, imu_krooz.accel_filtered); + RATES_ASSIGN(imu_krooz.rates_sum, 0, 0, 0); VECT3_ASSIGN(imu_krooz.accel_sum, 0, 0, 0); imu_krooz.meas_nb = 0; @@ -150,10 +167,8 @@ void imu_krooz_event( void ) // If the HMC5883 I2C transaction has succeeded: convert the data hmc58xx_event(&imu_krooz.hmc); if (imu_krooz.hmc.data_available) { - VECT3_COPY(imu.mag_unscaled, imu_krooz.hmc.data.vect); -#if KROOZ_USE_MEDIAN_FILTER + VECT3_ASSIGN(imu.mag_unscaled, imu_krooz.hmc.data.vect.z, -imu_krooz.hmc.data.vect.x, imu_krooz.hmc.data.vect.y); UpdateMedianFilterVect3Int(median_mag, imu.mag_unscaled); -#endif imu_krooz.hmc.data_available = FALSE; imu_krooz.mag_valid = TRUE; } diff --git a/sw/airborne/boards/krooz/imu_krooz.h b/sw/airborne/boards/krooz/imu_krooz.h index 74afaf00f3..543306d225 100644 --- a/sw/airborne/boards/krooz/imu_krooz.h +++ b/sw/airborne/boards/krooz/imu_krooz.h @@ -39,12 +39,12 @@ // Default configuration #if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN -#define IMU_GYRO_P_SIGN -1 +#define IMU_GYRO_P_SIGN 1 #define IMU_GYRO_Q_SIGN 1 #define IMU_GYRO_R_SIGN 1 #endif #if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN -#define IMU_ACCEL_X_SIGN -1 +#define IMU_ACCEL_X_SIGN 1 #define IMU_ACCEL_Y_SIGN 1 #define IMU_ACCEL_Z_SIGN 1 #endif @@ -100,6 +100,13 @@ #define IMU_ACCEL_Z_NEUTRAL 0 #endif +#ifndef IMU_KROOZ_GYRO_AVG_FILTER +#define IMU_KROOZ_GYRO_AVG_FILTER 5 +#endif +#ifndef IMU_KROOZ_ACCEL_AVG_FILTER +#define IMU_KROOZ_ACCEL_AVG_FILTER 10 +#endif + struct ImuKrooz { volatile bool_t gyr_valid; volatile bool_t acc_valid; @@ -109,6 +116,8 @@ struct ImuKrooz { struct Int32Rates rates_sum; struct Int32Vect3 accel_sum; volatile uint8_t meas_nb; + struct Int32Vect3 accel_filtered; + struct Int32Rates gyro_filtered; }; extern struct ImuKrooz imu_krooz; From e9762a6e48255d50168447e3aef1498212a70ccf Mon Sep 17 00:00:00 2001 From: Dirk Dokter Date: Sat, 10 Aug 2013 15:48:02 +0200 Subject: [PATCH 069/309] [STM32] Very limited simple SPI1 slave driver closes #500 --- conf/modules/gumstix_qr_code_spi_link.xml | 19 ++ sw/airborne/arch/stm32/mcu_periph/spi_arch.c | 211 +++++++++++++++++- .../gumstix_interface/qr_code_spi_link.c | 72 ++++++ .../gumstix_interface/qr_code_spi_link.h | 31 +++ 4 files changed, 330 insertions(+), 3 deletions(-) create mode 100644 conf/modules/gumstix_qr_code_spi_link.xml create mode 100644 sw/airborne/modules/gumstix_interface/qr_code_spi_link.c create mode 100644 sw/airborne/modules/gumstix_interface/qr_code_spi_link.h diff --git a/conf/modules/gumstix_qr_code_spi_link.xml b/conf/modules/gumstix_qr_code_spi_link.xml new file mode 100644 index 0000000000..6219c94a66 --- /dev/null +++ b/conf/modules/gumstix_qr_code_spi_link.xml @@ -0,0 +1,19 @@ + + + + + QR code gumstix interface + +
+ +
+ + + + + + + + +
+ diff --git a/sw/airborne/arch/stm32/mcu_periph/spi_arch.c b/sw/airborne/arch/stm32/mcu_periph/spi_arch.c index bb5d82876c..f2b5cc79f4 100644 --- a/sw/airborne/arch/stm32/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/spi_arch.c @@ -1201,12 +1201,217 @@ void process_tx_dma_interrupt(struct spi_periph *periph) { /* * * SPI Slave code - * - * FIXME implement it + * Currently only for F1, SPI1 * */ #ifdef SPI_SLAVE -#warning SPI_SLAVE mode currently not implemented for STM32. +static void process_slave_rx_dma_interrupt(struct spi_periph* periph); + + +// SPI arch slave init +#if USE_SPI1_SLAVE +#warning "SPI1 slave: Untested code!" + +#ifndef STM32F1 +#error "SPI1 slave on STM32 only implemented for STM32F1" +#endif + +#if USE_SPI1 +#error "Using SPI1 as a slave and master at the same time is not possible." +#endif + +static struct spi_periph_dma spi1_dma; + +void spi1_slave_arch_init(void) { + // set dma options + spi1_dma.spidr = (uint32_t)&SPI1_DR; + spi1_dma.dma = DMA1; + spi1_dma.rx_chan = DMA_CHANNEL2; + spi1_dma.tx_chan = DMA_CHANNEL3; + spi1_dma.rx_nvic_irq = NVIC_DMA1_CHANNEL2_IRQ; + spi1_dma.tx_nvic_irq = NVIC_DMA1_CHANNEL3_IRQ; + spi1_dma.tx_dummy_buf = 0; + spi1_dma.tx_extra_dummy_dma = FALSE; + spi1_dma.rx_dummy_buf = 0; + spi1_dma.rx_extra_dummy_dma = FALSE; + + // set the default configuration + set_default_comm_config(&spi1_dma.comm); + spi1_dma.comm_sig = get_comm_signature(&spi1_dma.comm); + + // set init struct, indices and status + spi1.reg_addr = (void *)SPI1; + spi1.init_struct = &spi1_dma; + spi1.trans_insert_idx = 0; + spi1.trans_extract_idx = 0; + spi1.status = SPIIdle; + + // Enable SPI1 Periph and gpio clocks + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_SPI1EN); + + // Configure GPIOs: SCK, MISO and MOSI + // TODO configure lisa board files to use gpio_setup_pin_af function + gpio_set_mode(GPIO_BANK_SPI1_SCK, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_FLOAT, + GPIO_SPI1_SCK | GPIO_SPI1_MOSI); + + gpio_set_mode(GPIO_BANK_SPI1_MISO, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, + GPIO_SPI1_MISO); + + gpio_set_mode(GPIO_BANK_SPI1_NSS, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_FLOAT, + GPIO_SPI1_NSS); + + // reset SPI + spi_reset(SPI1); + + // Disable SPI peripheral + spi_disable(SPI1); + + // Force SPI mode over I2S. + SPI1_I2SCFGR = 0; + + // configure master SPI. + spi_init_master(SPI1, spi1_dma.comm.br, spi1_dma.comm.cpol, spi1_dma.comm.cpha, + spi1_dma.comm.dff, spi1_dma.comm.lsbfirst); + + spi_disable_software_slave_management(SPI1); + + spi_set_slave_mode(SPI1); + + // Enable SPI_1 DMA clock +#ifdef STM32F1 + rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_DMA1EN); +#elif defined STM32F4 + rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_DMA2EN); +#endif + + // Enable SPI1 periph. + spi_enable(SPI1); + + spi_arch_int_enable(&spi1); +} + +/// receive transferred over DMA +void dma1_channel2_isr(void) +{ + if ((DMA1_ISR & DMA_ISR_TCIF2) != 0) { + // clear int pending bit + DMA1_IFCR |= DMA_IFCR_CTCIF2; + } + process_slave_rx_dma_interrupt(&spi1); +} + + +#endif /* USE_SPI1_SLAVE */ + + +static void spi_slave_set_config(struct spi_periph* periph, struct spi_transaction* trans) +{ + struct spi_periph_dma *dma; + + dma = periph->init_struct; + + set_comm_from_transaction(&(dma->comm), trans); + + /* remember the new conf signature */ + //dma->comm_sig = sig; + + /* apply the new configuration */ + spi_disable((uint32_t)periph->reg_addr); + spi_init_master((uint32_t)periph->reg_addr, dma->comm.br, dma->comm.cpol, + dma->comm.cpha, dma->comm.dff, dma->comm.lsbfirst); + spi_disable_software_slave_management((uint32_t)periph->reg_addr); + spi_set_slave_mode((uint32_t)periph->reg_addr); + spi_enable((uint32_t)periph->reg_addr); +} + + + +//static void spi_start_slave_dma_transaction(struct spi_periph* periph, struct spi_transaction* trans) +bool_t spi_slave_register(struct spi_periph* periph, struct spi_transaction* trans) +{ + spi_slave_set_config(periph, trans); + + struct spi_periph_dma *dma; + uint8_t sig = 0x00; + + /* Store local copy to notify of the results */ + trans->status = SPITransRunning; + periph->status = SPIRunning; + + periph->trans_insert_idx = 0; + periph->trans[periph->trans_insert_idx] = trans; + + dma = periph->init_struct; + + /* + * Receive DMA channel configuration ---------------------------------------- + */ + spi_configure_dma(dma->dma, dma->rx_chan, (uint32_t)dma->spidr, + (uint32_t)trans->input_buf, trans->input_length, trans->dss, TRUE); + + dma_set_read_from_peripheral(dma->dma, dma->rx_chan); + dma_set_priority(dma->dma, dma->rx_chan, DMA_CCR_PL_VERY_HIGH); + + + /* + * Transmit DMA channel configuration --------------------------------------- + */ + spi_configure_dma(dma->dma, dma->tx_chan, (uint32_t)dma->spidr, + (uint32_t)trans->output_buf, trans->output_length, trans->dss, TRUE); + + dma_set_read_from_memory(dma->dma, dma->tx_chan); + dma_set_priority(dma->dma, dma->tx_chan, DMA_CCR_PL_MEDIUM); + + /* Enable DMA transfer complete interrupts. */ + dma_enable_transfer_complete_interrupt(dma->dma, dma->rx_chan); + + /* Enable DMA channels */ + dma_enable_channel(dma->dma, dma->rx_chan); + dma_enable_channel(dma->dma, dma->tx_chan); + + /* Enable SPI transfers via DMA */ + spi_enable_rx_dma((uint32_t)periph->reg_addr); + spi_enable_tx_dma((uint32_t)periph->reg_addr); + + return TRUE; +} + +void process_slave_rx_dma_interrupt(struct spi_periph *periph) { + struct spi_periph_dma *dma = periph->init_struct; + struct spi_transaction *trans = periph->trans[periph->trans_extract_idx]; + + /* Disable DMA Channel */ + dma_disable_transfer_complete_interrupt(dma->dma, dma->rx_chan); + + /* Disable SPI Rx request */ + spi_disable_rx_dma((uint32_t)periph->reg_addr); + + /* Disable DMA rx channel */ + dma_disable_channel(dma->dma, dma->rx_chan); + + /* Run the callback */ + trans->status = SPITransSuccess; + //return; + if (trans->after_cb != 0) { + trans->after_cb(trans); + } + + /*dma_enable_transfer_complete_interrupt(dma->dma, dma->rx_chan); + dma_enable_channel(dma->dma, dma->rx_chan); + spi_enable_rx_dma((uint32_t)periph->reg_addr);*/ +} + + +// Slave Select / NSS pin GPIO config + + +// DMA config? + + +// SPI transaction handling #endif /* SPI_SLAVE */ diff --git a/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c new file mode 100644 index 0000000000..c0a1a92526 --- /dev/null +++ b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2005-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#include "qr_code_spi_link.h" + +#include "subsystems/imu.h" +#include "mcu_periph/spi.h" + +#include "mcu_periph/uart.h" +#include "messages.h" +#include "subsystems/datalink/downlink.h" + +//struct qr_code_spi_link_data qr_code_spi_link_data; +struct spi_transaction qr_code_spi_link_transaction; + +static volatile bool_t qr_code_spi_data_available = FALSE; + +uint8_t testDataOut[3] = {1,2,3}; +uint8_t testDataIn[3] = {9,9,9}; + +static void qr_code_spi_link_trans_cb( struct spi_transaction *trans ); + +void qr_code_spi_link_init(void) { + qr_code_spi_link_transaction.cpol = SPICpolIdleHigh; + qr_code_spi_link_transaction.cpha = SPICphaEdge2; + qr_code_spi_link_transaction.dss = SPIDss8bit; + qr_code_spi_link_transaction.bitorder = SPIMSBFirst; + qr_code_spi_link_transaction.output_length = 3; + qr_code_spi_link_transaction.output_buf = testDataOut; + qr_code_spi_link_transaction.input_length = 3; + qr_code_spi_link_transaction.input_buf = testDataIn; + qr_code_spi_link_transaction.after_cb = qr_code_spi_link_trans_cb; + //spi_slave_set_config(&spi1, &qr_code_spi_link_transaction); + spi_slave_register(&spi1, &qr_code_spi_link_transaction); +} + + +void qr_code_spi_link_periodic(void) { + if (qr_code_spi_data_available) { + qr_code_spi_data_available = FALSE; + uint16_t x,y; + memcpy(&x,qr_code_spi_link_transaction.input_buf,2); + memcpy(&y,qr_code_spi_link_transaction.input_buf+2,2); + DOWNLINK_SEND_VISUALTARGET(DefaultChannel, DefaultDevice, &x, &y); + spi_slave_register(&spi1, &qr_code_spi_link_transaction); + } +} + +static void qr_code_spi_link_trans_cb( struct spi_transaction *trans __attribute__ ((unused)) ) { + qr_code_spi_data_available = TRUE; +} + + diff --git a/sw/airborne/modules/gumstix_interface/qr_code_spi_link.h b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.h new file mode 100644 index 0000000000..06aa237943 --- /dev/null +++ b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.h @@ -0,0 +1,31 @@ +/* + * Copyright (C) 2005-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#ifndef QR_CODE_SPI_LINK_H_ +#define QR_CODE_SPI_LINK_H_ + +#include "std.h" + +extern void qr_code_spi_link_init(void); +extern void qr_code_spi_link_periodic(void); + +#endif /* QR_CODE_SPI_LINK_H_ */ From 95871c8d2be0236145143d55bc095f4ba1f93269 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 12 Aug 2013 14:39:04 +0200 Subject: [PATCH 070/309] [rotorcraft] v_adapt: reset while not in_flight --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index c8cd29d6e1..53f74082a7 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -166,6 +166,10 @@ void guidance_v_run(bool_t in_flight) { if (in_flight) { gv_adapt_run(stateGetAccelNed_i()->z, stabilization_cmd[COMMAND_THRUST], guidance_v_zd_ref); } + else { + /* reset estimate while not in_flight */ + gv_adapt_init(); + } switch (guidance_v_mode) { From 6f742e0c17efdc9bf293c0720d52da8e23e595bb Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 12 Aug 2013 15:46:24 +0200 Subject: [PATCH 071/309] [math] brackets for macro arguments... --- sw/airborne/math/pprz_algebra_float.h | 136 +++++++++++++------------- 1 file changed, 68 insertions(+), 68 deletions(-) diff --git a/sw/airborne/math/pprz_algebra_float.h b/sw/airborne/math/pprz_algebra_float.h index e48aca10dd..375907973b 100644 --- a/sw/airborne/math/pprz_algebra_float.h +++ b/sw/airborne/math/pprz_algebra_float.h @@ -588,35 +588,35 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { #define FLOAT_QUAT_INTEGRATE(_q, _omega, _dt) { \ const float no = FLOAT_RATES_NORM(_omega); \ if (no > FLT_MIN) { \ - const float a = 0.5*no*_dt; \ + const float a = 0.5*no*(_dt); \ const float ca = cosf(a); \ const float sa_ov_no = sinf(a)/no; \ - const float dp = sa_ov_no*_omega.p; \ - const float dq = sa_ov_no*_omega.q; \ - const float dr = sa_ov_no*_omega.r; \ - const float qi = _q.qi; \ - const float qx = _q.qx; \ - const float qy = _q.qy; \ - const float qz = _q.qz; \ - _q.qi = ca*qi - dp*qx - dq*qy - dr*qz; \ - _q.qx = dp*qi + ca*qx + dr*qy - dq*qz; \ - _q.qy = dq*qi - dr*qx + ca*qy + dp*qz; \ - _q.qz = dr*qi + dq*qx - dp*qy + ca*qz; \ + const float dp = sa_ov_no*(_omega).p; \ + const float dq = sa_ov_no*(_omega).q; \ + const float dr = sa_ov_no*(_omega).r; \ + const float qi = (_q).qi; \ + const float qx = (_q).qx; \ + const float qy = (_q).qy; \ + const float qz = (_q).qz; \ + (_q).qi = ca*qi - dp*qx - dq*qy - dr*qz; \ + (_q).qx = dp*qi + ca*qx + dr*qy - dq*qz; \ + (_q).qy = dq*qi - dr*qx + ca*qy + dp*qz; \ + (_q).qz = dr*qi + dq*qx - dp*qy + ca*qz; \ } \ } #ifdef ALGEBRA_FLOAT_USE_SLOW_FUNCTIONS #define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ - const float qi2 = q.qi*q.qi; \ - const float qiqx = q.qi*q.qx; \ - const float qiqy = q.qi*q.qy; \ - const float qiqz = q.qi*q.qz; \ - const float qx2 = q.qx*q.qx; \ - const float qxqy = q.qx*q.qy; \ - const float qxqz = q.qx*q.qz; \ - const float qy2 = q.qy*q.qy; \ - const float qyqz = q.qy*q.qz; \ - const float qz2 = q.qz*q.qz; \ + const float qi2 = (q).qi*(q).qi; \ + const float qiqx = (q).qi*(q).qx; \ + const float qiqy = (q).qi*(q).qy; \ + const float qiqz = (q).qi*(q).qz; \ + const float qx2 = (q).qx*(q).qx; \ + const float qxqy = (q).qx*(q).qy; \ + const float qxqz = (q).qx*(q).qz; \ + const float qy2 = (q).qy*(q).qy; \ + const float qyqz = (q).qy*(q).qz; \ + const float qz2 = (q).qz*(q).qz; \ const float m00 = qi2 + qx2 - qy2 - qz2; \ const float m01 = 2 * ( qxqy + qiqz ); \ const float m02 = 2 * ( qxqz - qiqy ); \ @@ -626,32 +626,32 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { const float m20 = 2 * ( qxqz + qiqy ); \ const float m21 = 2 * ( qyqz - qiqx ); \ const float m22 = qi2 - qx2 - qy2 + qz2; \ - v_out.x = m00 * v_in.x + m01 * v_in.y + m02 * v_in.z; \ - v_out.y = m10 * v_in.x + m11 * v_in.y + m12 * v_in.z; \ - v_out.z = m20 * v_in.x + m21 * v_in.y + m22 * v_in.z; \ + (v_out).x = m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z; \ + (v_out).y = m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z; \ + (v_out).z = m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z; \ } #else #define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ - const float qi2_M1_2 = q.qi*q.qi - 0.5; \ - const float qiqx = q.qi*q.qx; \ - const float qiqy = q.qi*q.qy; \ - const float qiqz = q.qi*q.qz; \ - float m01 = q.qx*q.qy; /* aka qxqy */ \ - float m02 = q.qx*q.qz; /* aka qxqz */ \ - float m12 = q.qy*q.qz; /* aka qyqz */ \ + const float qi2_M1_2 = (q).qi*(q).qi - 0.5; \ + const float qiqx = (q).qi*(q).qx; \ + const float qiqy = (q).qi*(q).qy; \ + const float qiqz = (q).qi*(q).qz; \ + float m01 = (q).qx*(q).qy; /* aka qxqy */ \ + float m02 = (q).qx*(q).qz; /* aka qxqz */ \ + float m12 = (q).qy*(q).qz; /* aka qyqz */ \ \ - const float m00 = qi2_M1_2 + q.qx*q.qx; \ + const float m00 = qi2_M1_2 + (q).qx*(q).qx; \ const float m10 = m01 - qiqz; \ const float m20 = m02 + qiqy; \ const float m21 = m12 - qiqx; \ m01 += qiqz; \ m02 -= qiqy; \ m12 += qiqx; \ - const float m11 = qi2_M1_2 + q.qy*q.qy; \ - const float m22 = qi2_M1_2 + q.qz*q.qz; \ - v_out.x = 2*(m00 * v_in.x + m01 * v_in.y + m02 * v_in.z); \ - v_out.y = 2*(m10 * v_in.x + m11 * v_in.y + m12 * v_in.z); \ - v_out.z = 2*(m20 * v_in.x + m21 * v_in.y + m22 * v_in.z); \ + const float m11 = qi2_M1_2 + (q).qy*(q).qy; \ + const float m22 = qi2_M1_2 + (q).qz*(q).qz; \ + (v_out).x = 2*(m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z); \ + (v_out).y = 2*(m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z); \ + (v_out).z = 2*(m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z); \ } #endif @@ -693,55 +693,55 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { \ } -#define FLOAT_QUAT_OF_AXIS_ANGLE(_q, _uv, _an) { \ - const float san = sinf(_an/2.); \ - _q.qi = cosf(_an/2.); \ - _q.qx = san * _uv.x; \ - _q.qy = san * _uv.y; \ - _q.qz = san * _uv.z; \ +#define FLOAT_QUAT_OF_AXIS_ANGLE(_q, _uv, _an) { \ + const float san = sinf((_an)/2.); \ + (_q).qi = cosf((_an)/2.); \ + (_q).qx = san * (_uv).x; \ + (_q).qy = san * (_uv).y; \ + (_q).qz = san * (_uv).z; \ } #define FLOAT_QUAT_OF_RMAT(_q, _r) { \ - const float tr = RMAT_TRACE(_r); \ + const float tr = RMAT_TRACE((_r)); \ if (tr > 0) { \ const float two_qi = sqrtf(1.+tr); \ const float four_qi = 2. * two_qi; \ - _q.qi = 0.5 * two_qi; \ - _q.qx = (RMAT_ELMT(_r, 1, 2)-RMAT_ELMT(_r, 2, 1))/four_qi; \ - _q.qy = (RMAT_ELMT(_r, 2, 0)-RMAT_ELMT(_r, 0, 2))/four_qi; \ - _q.qz = (RMAT_ELMT(_r, 0, 1)-RMAT_ELMT(_r, 1, 0))/four_qi; \ + (_q).qi = 0.5 * two_qi; \ + (_q).qx = (RMAT_ELMT((_r), 1, 2)-RMAT_ELMT((_r), 2, 1))/four_qi; \ + (_q).qy = (RMAT_ELMT((_r), 2, 0)-RMAT_ELMT((_r), 0, 2))/four_qi; \ + (_q).qz = (RMAT_ELMT((_r), 0, 1)-RMAT_ELMT((_r), 1, 0))/four_qi; \ /*printf("tr > 0\n");*/ \ } \ else { \ - if (RMAT_ELMT(_r, 0, 0) > RMAT_ELMT(_r, 1, 1) && \ - RMAT_ELMT(_r, 0, 0) > RMAT_ELMT(_r, 2, 2)) { \ - const float two_qx = sqrtf(RMAT_ELMT(_r, 0, 0) -RMAT_ELMT(_r, 1, 1) \ - -RMAT_ELMT(_r, 2, 2) + 1); \ + if (RMAT_ELMT((_r), 0, 0) > RMAT_ELMT((_r), 1, 1) && \ + RMAT_ELMT((_r), 0, 0) > RMAT_ELMT((_r), 2, 2)) { \ + const float two_qx = sqrtf(RMAT_ELMT((_r), 0, 0) -RMAT_ELMT((_r), 1, 1) \ + -RMAT_ELMT((_r), 2, 2) + 1); \ const float four_qx = 2. * two_qx; \ - _q.qi = (RMAT_ELMT(_r, 1, 2)-RMAT_ELMT(_r, 2, 1))/four_qx; \ - _q.qx = 0.5 * two_qx; \ - _q.qy = (RMAT_ELMT(_r, 0, 1)+RMAT_ELMT(_r, 1, 0))/four_qx; \ - _q.qz = (RMAT_ELMT(_r, 2, 0)+RMAT_ELMT(_r, 0, 2))/four_qx; \ + (_q).qi = (RMAT_ELMT((_r), 1, 2)-RMAT_ELMT((_r), 2, 1))/four_qx; \ + (_q).qx = 0.5 * two_qx; \ + (_q).qy = (RMAT_ELMT((_r), 0, 1)+RMAT_ELMT((_r), 1, 0))/four_qx; \ + (_q).qz = (RMAT_ELMT((_r), 2, 0)+RMAT_ELMT((_r), 0, 2))/four_qx; \ /*printf("m00 largest\n");*/ \ } \ - else if (RMAT_ELMT(_r, 1, 1) > RMAT_ELMT(_r, 2, 2)) { \ + else if (RMAT_ELMT((_r), 1, 1) > RMAT_ELMT((_r), 2, 2)) { \ const float two_qy = \ - sqrtf(RMAT_ELMT(_r, 1, 1) - RMAT_ELMT(_r, 0, 0) - RMAT_ELMT(_r, 2, 2) + 1); \ + sqrtf(RMAT_ELMT((_r), 1, 1) - RMAT_ELMT((_r), 0, 0) - RMAT_ELMT((_r), 2, 2) + 1); \ const float four_qy = 2. * two_qy; \ - _q.qi = (RMAT_ELMT(_r, 2, 0) - RMAT_ELMT(_r, 0, 2))/four_qy; \ - _q.qx = (RMAT_ELMT(_r, 0, 1) + RMAT_ELMT(_r, 1, 0))/four_qy; \ - _q.qy = 0.5 * two_qy; \ - _q.qz = (RMAT_ELMT(_r, 1, 2) + RMAT_ELMT(_r, 2, 1))/four_qy; \ + (_q).qi = (RMAT_ELMT((_r), 2, 0) - RMAT_ELMT((_r), 0, 2))/four_qy; \ + (_q).qx = (RMAT_ELMT((_r), 0, 1) + RMAT_ELMT((_r), 1, 0))/four_qy; \ + (_q).qy = 0.5 * two_qy; \ + (_q).qz = (RMAT_ELMT((_r), 1, 2) + RMAT_ELMT((_r), 2, 1))/four_qy; \ /*printf("m11 largest\n");*/ \ } \ else { \ const float two_qz = \ - sqrtf(RMAT_ELMT(_r, 2, 2) - RMAT_ELMT(_r, 0, 0) - RMAT_ELMT(_r, 1, 1) + 1); \ + sqrtf(RMAT_ELMT((_r), 2, 2) - RMAT_ELMT((_r), 0, 0) - RMAT_ELMT((_r), 1, 1) + 1); \ const float four_qz = 2. * two_qz; \ - _q.qi = (RMAT_ELMT(_r, 0, 1)- RMAT_ELMT(_r, 1, 0))/four_qz; \ - _q.qx = (RMAT_ELMT(_r, 2, 0)+ RMAT_ELMT(_r, 0, 2))/four_qz; \ - _q.qy = (RMAT_ELMT(_r, 1, 2)+ RMAT_ELMT(_r, 2, 1))/four_qz; \ - _q.qz = 0.5 * two_qz; \ + (_q).qi = (RMAT_ELMT((_r), 0, 1)- RMAT_ELMT((_r), 1, 0))/four_qz; \ + (_q).qx = (RMAT_ELMT((_r), 2, 0)+ RMAT_ELMT((_r), 0, 2))/four_qz; \ + (_q).qy = (RMAT_ELMT((_r), 1, 2)+ RMAT_ELMT((_r), 2, 1))/four_qz; \ + (_q).qz = 0.5 * two_qz; \ /*printf("m22 largest\n");*/ \ } \ } \ From 9a9367ccbf542867245de2f4a9f6cc346685d59f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 12 Aug 2013 15:48:11 +0200 Subject: [PATCH 072/309] [ahrs] remove some unneeded vars in float_mlkf --- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c | 9 +-------- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h | 13 +------------ 2 files changed, 2 insertions(+), 20 deletions(-) diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c index 3b6203273a..1c51b34526 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c @@ -74,7 +74,6 @@ void ahrs_init(void) { /* Set ltp_to_imu so that body is zero */ QUAT_COPY(ahrs_impl.ltp_to_imu_quat, ahrs_impl.body_to_imu_quat); - RMAT_COPY(ahrs_impl.ltp_to_imu_rmat, ahrs_impl.body_to_imu_rmat); FLOAT_RATES_ZERO(ahrs_impl.imu_rate); @@ -99,9 +98,6 @@ void ahrs_align(void) { /* Compute an initial orientation from accel and mag directly as quaternion */ ahrs_float_get_quat_from_accel_mag(&ahrs_impl.ltp_to_imu_quat, &ahrs_aligner.lp_accel, &ahrs_aligner.lp_mag); - /* Convert initial orientation from quat to rotation matrix representations. */ - FLOAT_RMAT_OF_QUAT(ahrs_impl.ltp_to_imu_rmat, ahrs_impl.ltp_to_imu_quat); - /* set initial body orientation */ set_body_state_from_quat(); @@ -185,8 +181,6 @@ static inline void propagate_ref(void) { ahrs_impl.ltp_to_imu_quat.qz = dr*qi + dq*qx - dp*qy + ca*qz; // printf("%f\n", ahrs_impl.ltp_to_imu_quat.qi); - - FLOAT_RMAT_OF_QUAT(ahrs_impl.ltp_to_imu_rmat, ahrs_impl.ltp_to_imu_quat); } } @@ -228,7 +222,7 @@ static inline void update_state(const struct FloatVect3 *i_expected, struct Floa /* converted expected measurement from inertial to body frame */ struct FloatVect3 b_expected; - FLOAT_RMAT_VECT3_MUL(b_expected, ahrs_impl.ltp_to_imu_rmat, *i_expected); + FLOAT_QUAT_VMULT(b_expected, ahrs_impl.ltp_to_imu_quat, *i_expected); // S = HPH' + JRJ float H[3][6] = {{ 0., -b_expected.z, b_expected.y, 0., 0., 0.}, @@ -288,7 +282,6 @@ static inline void reset_state(void) { FLOAT_QUAT_NORMALIZE(q_tmp); memcpy(&ahrs_impl.ltp_to_imu_quat, &q_tmp, sizeof(ahrs_impl.ltp_to_imu_quat)); FLOAT_QUAT_ZERO(ahrs_impl.gibbs_cor); - FLOAT_RMAT_OF_QUAT(ahrs_impl.ltp_to_imu_rmat, ahrs_impl.ltp_to_imu_quat); } diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h index a5b6522ee7..d6631d15a0 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h @@ -37,21 +37,10 @@ struct AhrsMlkf { struct FloatQuat ltp_to_imu_quat; ///< Rotation from LocalTangentPlane to IMU frame as unit quaternion - struct FloatEulers ltp_to_imu_euler; ///< Rotation from LocalTangentPlane to IMU frame as Euler angles - struct FloatRMat ltp_to_imu_rmat; ///< Rotation from LocalTangentPlane to IMU frame as Rotation Matrix + struct FloatQuat ltp_to_body_quat; ///< Rotation from LocalTangentPlane to body frame as unit quaternion struct FloatRates imu_rate; ///< Rotational velocity in IMU frame - struct FloatRates imu_rate_previous; - struct FloatRates imu_rate_d; - - struct FloatQuat ltp_to_body_quat; ///< Rotation from LocalTangentPlane to body frame as unit quaternion - struct FloatEulers ltp_to_body_euler; ///< Rotation from LocalTangentPlane to body frame as Euler angles - struct FloatRMat ltp_to_body_rmat; ///< Rotation from LocalTangentPlane to body frame as Rotation Matrix - struct FloatRates body_rate; ///< Rotational velocity in body frame - struct FloatRates body_rate_d; - struct FloatRates gyro_bias; - struct FloatQuat gibbs_cor; float P[6][6]; float lp_accel; From 7302b5cd23e3089195e4ccb035fbd9c931fa5c1d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 12 Aug 2013 16:21:13 +0200 Subject: [PATCH 073/309] [ahrs] geo mag for float ahrs --- sw/airborne/modules/geo_mag/geo_mag.c | 8 ++++++-- sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c | 8 +++----- sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h | 1 + sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c | 5 +++-- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h | 2 ++ 5 files changed, 15 insertions(+), 9 deletions(-) diff --git a/sw/airborne/modules/geo_mag/geo_mag.c b/sw/airborne/modules/geo_mag/geo_mag.c index a615722137..aa5f60a105 100644 --- a/sw/airborne/modules/geo_mag/geo_mag.c +++ b/sw/airborne/modules/geo_mag/geo_mag.c @@ -31,8 +31,7 @@ #include "subsystems/gps.h" #include "autopilot.h" -// in int_cmpl_quat implementation, mag_h is an Int32Vect3 with INT32_MAG_FRAC -#include "subsystems/ahrs/ahrs_int_cmpl_quat.h" +#include "subsystems/ahrs.h" bool_t geo_mag_calc_flag; struct GeoMagVect geo_mag_vect; @@ -71,8 +70,13 @@ void geo_mag_event(void) { IEXT, EXT_COEFF1, EXT_COEFF2, EXT_COEFF3); FLOAT_VECT3_NORMALIZE(geo_mag_vect); + // copy to ahrs +#ifdef AHRS_FLOAT + VECT3_COPY(ahrs_impl.mag_h, geo_mag_vect); +#else // convert to MAG_BFP and copy to ahrs VECT3_ASSIGN(ahrs_impl.mag_h, MAG_BFP_OF_REAL(geo_mag_vect.x), MAG_BFP_OF_REAL(geo_mag_vect.y), MAG_BFP_OF_REAL(geo_mag_vect.z)); +#endif geo_mag_vect.ready = TRUE; } diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c index 0a17453b3a..5db9eca134 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c @@ -107,6 +107,7 @@ void ahrs_init(void) { ahrs_impl.correct_gravity = FALSE; #endif + VECT3_ASSIGN(ahrs_impl.mag_h, AHRS_H_X, AHRS_H_Y, AHRS_H_Z); } void ahrs_align(void) { @@ -240,9 +241,8 @@ void ahrs_update_mag(void) { void ahrs_update_mag_full(void) { - const struct FloatVect3 expected_ltp = {AHRS_H_X, AHRS_H_Y, AHRS_H_Z}; struct FloatVect3 expected_imu; - FLOAT_RMAT_VECT3_MUL(expected_imu, ahrs_impl.ltp_to_imu_rmat, expected_ltp); + FLOAT_RMAT_VECT3_MUL(expected_imu, ahrs_impl.ltp_to_imu_rmat, ahrs_impl.mag_h); struct FloatVect3 measured_imu; MAGS_FLOAT_OF_BFP(measured_imu, imu.mag); @@ -263,8 +263,6 @@ void ahrs_update_mag_full(void) { void ahrs_update_mag_2d(void) { - const struct FloatVect2 expected_ltp = {AHRS_H_X, AHRS_H_Y}; - struct FloatVect3 measured_imu; MAGS_FLOAT_OF_BFP(measured_imu, imu.mag); struct FloatVect3 measured_ltp; @@ -273,7 +271,7 @@ void ahrs_update_mag_2d(void) { const struct FloatVect3 residual_ltp = { 0, 0, - measured_ltp.x * expected_ltp.y - measured_ltp.y * expected_ltp.x }; + measured_ltp.x * ahrs_impl.mag_h.y - measured_ltp.y * ahrs_impl.mag_h.x }; // printf("res : %f\n", residual_ltp.z); diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h index a40d888f08..b14831fa3e 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h @@ -44,6 +44,7 @@ struct AhrsFloatCmpl { bool_t correct_gravity; bool_t heading_aligned; + struct FloatVect3 mag_h; /* Holds float version of IMU alignement diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c index 1c51b34526..39414215ce 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c @@ -77,6 +77,8 @@ void ahrs_init(void) { FLOAT_RATES_ZERO(ahrs_impl.imu_rate); + VECT3_ASSIGN(ahrs_impl.mag_h, AHRS_H_X, AHRS_H_Y, AHRS_H_Z); + /* * Initialises our state */ @@ -136,9 +138,8 @@ void ahrs_update_accel(void) { void ahrs_update_mag(void) { struct FloatVect3 imu_h; MAGS_FLOAT_OF_BFP(imu_h, imu.mag); - const struct FloatVect3 earth_h = { AHRS_H_X , AHRS_H_Y, AHRS_H_Z }; const float h_noise[] = { 0.1610, 0.1771, 0.2659}; - update_state(&earth_h, &imu_h, h_noise); + update_state(&ahrs_impl.mag_h, &imu_h, h_noise); reset_state(); } diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h index d6631d15a0..043b519a64 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h @@ -41,6 +41,8 @@ struct AhrsMlkf { struct FloatRates imu_rate; ///< Rotational velocity in IMU frame struct FloatRates gyro_bias; + struct FloatVect3 mag_h; + struct FloatQuat gibbs_cor; float P[6][6]; float lp_accel; From 9baf8c0596313a5643c1f39500616c9ab66687be Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 12 Aug 2013 16:33:47 +0200 Subject: [PATCH 074/309] [math] untabify --- sw/airborne/math/pprz_algebra_double.h | 138 ++-- sw/airborne/math/pprz_algebra_float.h | 748 ++++++++++----------- sw/airborne/math/pprz_algebra_int.h | 876 ++++++++++++------------- 3 files changed, 881 insertions(+), 881 deletions(-) diff --git a/sw/airborne/math/pprz_algebra_double.h b/sw/airborne/math/pprz_algebra_double.h index cdcc260162..4a5bdda494 100644 --- a/sw/airborne/math/pprz_algebra_double.h +++ b/sw/airborne/math/pprz_algebra_double.h @@ -86,10 +86,10 @@ struct DoubleRates { #define DOUBLE_VECT3_ROUND(_v) DOUBLE_VECT3_RINT(_v, _v) -#define DOUBLE_VECT3_RINT(_vout, _vin) { \ - (_vout).x = rint((_vin).x); \ - (_vout).y = rint((_vin).y); \ - (_vout).z = rint((_vin).z); \ +#define DOUBLE_VECT3_RINT(_vout, _vin) { \ + (_vout).x = rint((_vin).x); \ + (_vout).y = rint((_vin).y); \ + (_vout).z = rint((_vin).z); \ } #define DOUBLE_VECT3_ASSIGN(_a, _x, _y, _z) VECT3_ASSIGN(_a, _x, _y, _z) @@ -97,94 +97,94 @@ struct DoubleRates { #define DOUBLE_VECT3_COPY(_a, _b) VECT3_COPY(_a, _b) #define DOUBLE_VECT3_SUM(_c,_a,_b) { \ - (_c).x = (_a).x + (_b).x; \ - (_c).y = (_a).y + (_b).y; \ - (_c).z = (_a).z + (_b).z; \ + (_c).x = (_a).x + (_b).x; \ + (_c).y = (_a).y + (_b).y; \ + (_c).z = (_a).z + (_b).z; \ } #define DOUBLE_VECT3_CROSS_PRODUCT(vo, v1, v2) FLOAT_VECT3_CROSS_PRODUCT(vo, v1, v2) #define DOUBLE_RMAT_OF_EULERS(_rm, _e) DOUBLE_RMAT_OF_EULERS_321(_rm, _e) -#define DOUBLE_RMAT_OF_EULERS_321(_rm, _e) { \ - \ - const double sphi = sin((_e).phi); \ - const double cphi = cos((_e).phi); \ - const double stheta = sin((_e).theta); \ - const double ctheta = cos((_e).theta); \ - const double spsi = sin((_e).psi); \ - const double cpsi = cos((_e).psi); \ - \ - RMAT_ELMT(_rm, 0, 0) = ctheta*cpsi; \ - RMAT_ELMT(_rm, 0, 1) = ctheta*spsi; \ - RMAT_ELMT(_rm, 0, 2) = -stheta; \ - RMAT_ELMT(_rm, 1, 0) = sphi*stheta*cpsi - cphi*spsi; \ - RMAT_ELMT(_rm, 1, 1) = sphi*stheta*spsi + cphi*cpsi; \ - RMAT_ELMT(_rm, 1, 2) = sphi*ctheta; \ - RMAT_ELMT(_rm, 2, 0) = cphi*stheta*cpsi + sphi*spsi; \ - RMAT_ELMT(_rm, 2, 1) = cphi*stheta*spsi - sphi*cpsi; \ - RMAT_ELMT(_rm, 2, 2) = cphi*ctheta; \ - \ +#define DOUBLE_RMAT_OF_EULERS_321(_rm, _e) { \ + \ + const double sphi = sin((_e).phi); \ + const double cphi = cos((_e).phi); \ + const double stheta = sin((_e).theta); \ + const double ctheta = cos((_e).theta); \ + const double spsi = sin((_e).psi); \ + const double cpsi = cos((_e).psi); \ + \ + RMAT_ELMT(_rm, 0, 0) = ctheta*cpsi; \ + RMAT_ELMT(_rm, 0, 1) = ctheta*spsi; \ + RMAT_ELMT(_rm, 0, 2) = -stheta; \ + RMAT_ELMT(_rm, 1, 0) = sphi*stheta*cpsi - cphi*spsi; \ + RMAT_ELMT(_rm, 1, 1) = sphi*stheta*spsi + cphi*cpsi; \ + RMAT_ELMT(_rm, 1, 2) = sphi*ctheta; \ + RMAT_ELMT(_rm, 2, 0) = cphi*stheta*cpsi + sphi*spsi; \ + RMAT_ELMT(_rm, 2, 1) = cphi*stheta*spsi - sphi*cpsi; \ + RMAT_ELMT(_rm, 2, 2) = cphi*ctheta; \ + \ } /* multiply _vin by _mat, store in _vout */ -#define DOUBLE_MAT33_VECT3_MUL(_vout, _mat, _vin) { \ - (_vout).x = (_mat)[0]*(_vin).x + (_mat)[1]*(_vin).y + (_mat)[2]*(_vin).z; \ - (_vout).y = (_mat)[3]*(_vin).x + (_mat)[4]*(_vin).y + (_mat)[5]*(_vin).z; \ - (_vout).z = (_mat)[6]*(_vin).x + (_mat)[7]*(_vin).y + (_mat)[8]*(_vin).z; \ +#define DOUBLE_MAT33_VECT3_MUL(_vout, _mat, _vin) { \ + (_vout).x = (_mat)[0]*(_vin).x + (_mat)[1]*(_vin).y + (_mat)[2]*(_vin).z; \ + (_vout).y = (_mat)[3]*(_vin).x + (_mat)[4]*(_vin).y + (_mat)[5]*(_vin).z; \ + (_vout).z = (_mat)[6]*(_vin).x + (_mat)[7]*(_vin).y + (_mat)[8]*(_vin).z; \ } /* multiply _vin by the transpose of _mat, store in _vout */ -#define DOUBLE_MAT33_VECT3_TRANSP_MUL(_vout, _mat, _vin) { \ - (_vout).x = (_mat)[0]*(_vin).x + (_mat)[3]*(_vin).y + (_mat)[6]*(_vin).z; \ - (_vout).y = (_mat)[1]*(_vin).x + (_mat)[4]*(_vin).y + (_mat)[7]*(_vin).z; \ - (_vout).z = (_mat)[2]*(_vin).x + (_mat)[5]*(_vin).y + (_mat)[8]*(_vin).z; \ +#define DOUBLE_MAT33_VECT3_TRANSP_MUL(_vout, _mat, _vin) { \ + (_vout).x = (_mat)[0]*(_vin).x + (_mat)[3]*(_vin).y + (_mat)[6]*(_vin).z; \ + (_vout).y = (_mat)[1]*(_vin).x + (_mat)[4]*(_vin).y + (_mat)[7]*(_vin).z; \ + (_vout).z = (_mat)[2]*(_vin).x + (_mat)[5]*(_vin).y + (_mat)[8]*(_vin).z; \ } -#define DOUBLE_QUAT_OF_EULERS(_q, _e) { \ - \ - const double phi2 = (_e).phi/ 2.0; \ - const double theta2 = (_e).theta/2.0; \ - const double psi2 = (_e).psi/2.0; \ - \ - const double s_phi2 = sin( phi2 ); \ - const double c_phi2 = cos( phi2 ); \ - const double s_theta2 = sin( theta2 ); \ - const double c_theta2 = cos( theta2 ); \ - const double s_psi2 = sin( psi2 ); \ - const double c_psi2 = cos( psi2 ); \ - \ +#define DOUBLE_QUAT_OF_EULERS(_q, _e) { \ + \ + const double phi2 = (_e).phi/ 2.0; \ + const double theta2 = (_e).theta/2.0; \ + const double psi2 = (_e).psi/2.0; \ + \ + const double s_phi2 = sin( phi2 ); \ + const double c_phi2 = cos( phi2 ); \ + const double s_theta2 = sin( theta2 ); \ + const double c_theta2 = cos( theta2 ); \ + const double s_psi2 = sin( psi2 ); \ + const double c_psi2 = cos( psi2 ); \ + \ (_q).qi = c_phi2 * c_theta2 * c_psi2 + s_phi2 * s_theta2 * s_psi2; \ (_q).qx = -c_phi2 * s_theta2 * s_psi2 + s_phi2 * c_theta2 * c_psi2; \ (_q).qy = c_phi2 * s_theta2 * c_psi2 + s_phi2 * c_theta2 * s_psi2; \ (_q).qz = c_phi2 * c_theta2 * s_psi2 - s_phi2 * s_theta2 * c_psi2; \ - \ + \ } -#define DOUBLE_EULERS_OF_QUAT(_e, _q) { \ - \ - const double qx2 = (_q).qx*(_q).qx; \ - const double qy2 = (_q).qy*(_q).qy; \ - const double qz2 = (_q).qz*(_q).qz; \ - const double qiqx = (_q).qi*(_q).qx; \ - const double qiqy = (_q).qi*(_q).qy; \ - const double qiqz = (_q).qi*(_q).qz; \ - const double qxqy = (_q).qx*(_q).qy; \ - const double qxqz = (_q).qx*(_q).qz; \ - const double qyqz = (_q).qy*(_q).qz; \ - const double dcm00 = 1.0 - 2.*( qy2 + qz2 ); \ - const double dcm01 = 2.*( qxqy + qiqz ); \ - const double dcm02 = 2.*( qxqz - qiqy ); \ - const double dcm12 = 2.*( qyqz + qiqx ); \ - const double dcm22 = 1.0 - 2.*( qx2 + qy2 ); \ - \ - (_e).phi = atan2( dcm12, dcm22 ); \ - (_e).theta = -asin( dcm02 ); \ - (_e).psi = atan2( dcm01, dcm00 ); \ - \ +#define DOUBLE_EULERS_OF_QUAT(_e, _q) { \ + \ + const double qx2 = (_q).qx*(_q).qx; \ + const double qy2 = (_q).qy*(_q).qy; \ + const double qz2 = (_q).qz*(_q).qz; \ + const double qiqx = (_q).qi*(_q).qx; \ + const double qiqy = (_q).qi*(_q).qy; \ + const double qiqz = (_q).qi*(_q).qz; \ + const double qxqy = (_q).qx*(_q).qy; \ + const double qxqz = (_q).qx*(_q).qz; \ + const double qyqz = (_q).qy*(_q).qz; \ + const double dcm00 = 1.0 - 2.*( qy2 + qz2 ); \ + const double dcm01 = 2.*( qxqy + qiqz ); \ + const double dcm02 = 2.*( qxqz - qiqy ); \ + const double dcm12 = 2.*( qyqz + qiqx ); \ + const double dcm22 = 1.0 - 2.*( qx2 + qy2 ); \ + \ + (_e).phi = atan2( dcm12, dcm22 ); \ + (_e).theta = -asin( dcm02 ); \ + (_e).psi = atan2( dcm01, dcm00 ); \ + \ } #endif /* PPRZ_ALGEBRA_DOUBLE_H */ diff --git a/sw/airborne/math/pprz_algebra_float.h b/sw/airborne/math/pprz_algebra_float.h index 375907973b..06e024150e 100644 --- a/sw/airborne/math/pprz_algebra_float.h +++ b/sw/airborne/math/pprz_algebra_float.h @@ -90,9 +90,9 @@ struct FloatRates { float r; ///< in rad/s^2 }; -#define FLOAT_ANGLE_NORMALIZE(_a) { \ - while (_a > M_PI) _a -= (2.*M_PI); \ - while (_a < -M_PI) _a += (2.*M_PI); \ +#define FLOAT_ANGLE_NORMALIZE(_a) { \ + while (_a > M_PI) _a -= (2.*M_PI); \ + while (_a < -M_PI) _a += (2.*M_PI); \ } @@ -151,58 +151,58 @@ struct FloatRates { #define FLOAT_VECT3_DOT_PRODUCT(_v1, _v2) ((_v1).x*(_v2).x + (_v1).y*(_v2).y + (_v1).z*(_v2).z) -#define FLOAT_VECT3_CROSS_PRODUCT(_vo, _v1, _v2) { \ - (_vo).x = (_v1).y*(_v2).z - (_v1).z*(_v2).y; \ - (_vo).y = (_v1).z*(_v2).x - (_v1).x*(_v2).z; \ - (_vo).z = (_v1).x*(_v2).y - (_v1).y*(_v2).x; \ +#define FLOAT_VECT3_CROSS_PRODUCT(_vo, _v1, _v2) { \ + (_vo).x = (_v1).y*(_v2).z - (_v1).z*(_v2).y; \ + (_vo).y = (_v1).z*(_v2).x - (_v1).x*(_v2).z; \ + (_vo).z = (_v1).x*(_v2).y - (_v1).y*(_v2).x; \ } -#define FLOAT_VECT3_INTEGRATE_FI(_vo, _dv, _dt) { \ - (_vo).x += (_dv).x * (_dt); \ - (_vo).y += (_dv).y * (_dt); \ - (_vo).z += (_dv).z * (_dt); \ +#define FLOAT_VECT3_INTEGRATE_FI(_vo, _dv, _dt) { \ + (_vo).x += (_dv).x * (_dt); \ + (_vo).y += (_dv).y * (_dt); \ + (_vo).z += (_dv).z * (_dt); \ } -#define FLOAT_VECT3_NORMALIZE(_v) { \ - const float n = FLOAT_VECT3_NORM(_v); \ - FLOAT_VECT3_SMUL(_v, _v, 1./n); \ +#define FLOAT_VECT3_NORMALIZE(_v) { \ + const float n = FLOAT_VECT3_NORM(_v); \ + FLOAT_VECT3_SMUL(_v, _v, 1./n); \ } -#define FLOAT_RATES_ZERO(_r) { \ - RATES_ASSIGN(_r, 0., 0., 0.); \ +#define FLOAT_RATES_ZERO(_r) { \ + RATES_ASSIGN(_r, 0., 0., 0.); \ } #define FLOAT_RATES_NORM(_v) (sqrtf((_v).p*(_v).p + (_v).q*(_v).q + (_v).r*(_v).r)) -#define FLOAT_RATES_ADD_SCALED_VECT(_ro, _v, _s) { \ - _ro.p += _v.x * _s; \ - _ro.q += _v.y * _s; \ - _ro.r += _v.z * _s; \ +#define FLOAT_RATES_ADD_SCALED_VECT(_ro, _v, _s) { \ + _ro.p += _v.x * _s; \ + _ro.q += _v.y * _s; \ + _ro.r += _v.z * _s; \ } -#define FLOAT_RATES_LIN_CMB(_ro, _r1, _s1, _r2, _s2) { \ - _ro.p = _s1 * _r1.p + _s2 * _r2.p; \ - _ro.q = _s1 * _r1.q + _s2 * _r2.q; \ - _ro.r = _s1 * _r1.r + _s2 * _r2.r; \ +#define FLOAT_RATES_LIN_CMB(_ro, _r1, _s1, _r2, _s2) { \ + _ro.p = _s1 * _r1.p + _s2 * _r2.p; \ + _ro.q = _s1 * _r1.q + _s2 * _r2.q; \ + _ro.r = _s1 * _r1.r + _s2 * _r2.r; \ } -#define FLOAT_RATES_SCALE(_ro,_s) { \ - _ro.p *= _s; \ - _ro.q *= _s; \ - _ro.r *= _s; \ +#define FLOAT_RATES_SCALE(_ro,_s) { \ + _ro.p *= _s; \ + _ro.q *= _s; \ + _ro.r *= _s; \ } -#define FLOAT_RATES_INTEGRATE_FI(_ra, _racc, _dt) { \ - (_ra).p += (_racc).p * (_dt); \ - (_ra).q += (_racc).q * (_dt); \ - (_ra).r += (_racc).r * (_dt); \ +#define FLOAT_RATES_INTEGRATE_FI(_ra, _racc, _dt) { \ + (_ra).p += (_racc).p * (_dt); \ + (_ra).q += (_racc).q * (_dt); \ + (_ra).r += (_racc).r * (_dt); \ } -#define FLOAT_RATES_OF_EULER_DOT(_ra, _e, _ed) { \ +#define FLOAT_RATES_OF_EULER_DOT(_ra, _e, _ed) { \ _ra.p = _ed.phi - sinf(_e.theta) *_ed.psi; \ _ra.q = cosf(_e.phi)*_ed.theta + sinf(_e.phi)*cosf(_e.theta)*_ed.psi; \ _ra.r = -sinf(_e.phi)*_ed.theta + cosf(_e.phi)*cosf(_e.theta)*_ed.psi; \ @@ -213,28 +213,28 @@ struct FloatRates { /* * 3x3 matrices */ -#define FLOAT_MAT33_ZERO(_m) { \ - MAT33_ELMT(_m, 0, 0) = 0.; \ - MAT33_ELMT(_m, 0, 1) = 0.; \ +#define FLOAT_MAT33_ZERO(_m) { \ + MAT33_ELMT(_m, 0, 0) = 0.; \ + MAT33_ELMT(_m, 0, 1) = 0.; \ MAT33_ELMT(_m, 0, 2) = 0.; \ - MAT33_ELMT(_m, 1, 0) = 0.; \ - MAT33_ELMT(_m, 1, 1) = 0.; \ - MAT33_ELMT(_m, 1, 2) = 0.; \ - MAT33_ELMT(_m, 2, 0) = 0.; \ - MAT33_ELMT(_m, 2, 1) = 0.; \ - MAT33_ELMT(_m, 2, 2) = 0.; \ + MAT33_ELMT(_m, 1, 0) = 0.; \ + MAT33_ELMT(_m, 1, 1) = 0.; \ + MAT33_ELMT(_m, 1, 2) = 0.; \ + MAT33_ELMT(_m, 2, 0) = 0.; \ + MAT33_ELMT(_m, 2, 1) = 0.; \ + MAT33_ELMT(_m, 2, 2) = 0.; \ } -#define FLOAT_MAT33_DIAG(_m, _d00, _d11, _d22) { \ - MAT33_ELMT(_m, 0, 0) = _d00; \ - MAT33_ELMT(_m, 0, 1) = 0.; \ - MAT33_ELMT(_m, 0, 2) = 0.; \ - MAT33_ELMT(_m, 1, 0) = 0.; \ - MAT33_ELMT(_m, 1, 1) = _d11; \ - MAT33_ELMT(_m, 1, 2) = 0.; \ - MAT33_ELMT(_m, 2, 0) = 0.; \ - MAT33_ELMT(_m, 2, 1) = 0.; \ - MAT33_ELMT(_m, 2, 2) = _d22; \ +#define FLOAT_MAT33_DIAG(_m, _d00, _d11, _d22) { \ + MAT33_ELMT(_m, 0, 0) = _d00; \ + MAT33_ELMT(_m, 0, 1) = 0.; \ + MAT33_ELMT(_m, 0, 2) = 0.; \ + MAT33_ELMT(_m, 1, 0) = 0.; \ + MAT33_ELMT(_m, 1, 1) = _d11; \ + MAT33_ELMT(_m, 1, 2) = 0.; \ + MAT33_ELMT(_m, 2, 0) = 0.; \ + MAT33_ELMT(_m, 2, 1) = 0.; \ + MAT33_ELMT(_m, 2, 2) = _d22; \ } @@ -246,48 +246,48 @@ struct FloatRates { #define FLOAT_RMAT_ZERO(_rm) FLOAT_MAT33_DIAG(_rm, 1., 1., 1.) /* initialises a rotation matrix from unit vector axis and angle */ -#define FLOAT_RMAT_OF_AXIS_ANGLE(_rm, _uv, _an) { \ - \ - const float ux2 = _uv.x*_uv.x; \ - const float uy2 = _uv.y*_uv.y; \ - const float uz2 = _uv.z*_uv.z; \ - const float uxuy = _uv.x*_uv.y; \ - const float uyuz = _uv.y*_uv.z; \ - const float uxuz = _uv.x*_uv.z; \ - const float can = cosf(_an); \ - const float san = sinf(_an); \ - const float one_m_can = (1. - can); \ - \ - RMAT_ELMT(_rm, 0, 0) = ux2 + (1.-ux2)*can; \ - RMAT_ELMT(_rm, 0, 1) = uxuy*one_m_can + _uv.z*san; \ - RMAT_ELMT(_rm, 0, 2) = uxuz*one_m_can - _uv.y*san; \ - RMAT_ELMT(_rm, 1, 0) = uxuy*one_m_can - _uv.z*san; \ - RMAT_ELMT(_rm, 1, 1) = uy2 + (1.-uy2)*can; \ - RMAT_ELMT(_rm, 1, 2) = uyuz*one_m_can + _uv.x*san; \ - RMAT_ELMT(_rm, 2, 0) = uxuz*one_m_can + _uv.y*san; \ - RMAT_ELMT(_rm, 2, 1) = uyuz*one_m_can - _uv.x*san; \ - RMAT_ELMT(_rm, 2, 2) = uz2 + (1.-uz2)*can; \ - \ +#define FLOAT_RMAT_OF_AXIS_ANGLE(_rm, _uv, _an) { \ + \ + const float ux2 = _uv.x*_uv.x; \ + const float uy2 = _uv.y*_uv.y; \ + const float uz2 = _uv.z*_uv.z; \ + const float uxuy = _uv.x*_uv.y; \ + const float uyuz = _uv.y*_uv.z; \ + const float uxuz = _uv.x*_uv.z; \ + const float can = cosf(_an); \ + const float san = sinf(_an); \ + const float one_m_can = (1. - can); \ + \ + RMAT_ELMT(_rm, 0, 0) = ux2 + (1.-ux2)*can; \ + RMAT_ELMT(_rm, 0, 1) = uxuy*one_m_can + _uv.z*san; \ + RMAT_ELMT(_rm, 0, 2) = uxuz*one_m_can - _uv.y*san; \ + RMAT_ELMT(_rm, 1, 0) = uxuy*one_m_can - _uv.z*san; \ + RMAT_ELMT(_rm, 1, 1) = uy2 + (1.-uy2)*can; \ + RMAT_ELMT(_rm, 1, 2) = uyuz*one_m_can + _uv.x*san; \ + RMAT_ELMT(_rm, 2, 0) = uxuz*one_m_can + _uv.y*san; \ + RMAT_ELMT(_rm, 2, 1) = uyuz*one_m_can - _uv.x*san; \ + RMAT_ELMT(_rm, 2, 2) = uz2 + (1.-uz2)*can; \ + \ } /* multiply _vin by _rmat, store in _vout */ #define FLOAT_RMAT_VECT3_MUL(_vout, _rmat, _vin) RMAT_VECT3_MUL(_vout, _rmat, _vin) #define FLOAT_RMAT_VECT3_TRANSP_MUL(_vout, _rmat, _vin) RMAT_VECT3_TRANSP_MUL(_vout, _rmat, _vin) -#define FLOAT_RMAT_TRANSP_RATEMULT(_vb, _m_b2a, _va) { \ +#define FLOAT_RMAT_TRANSP_RATEMULT(_vb, _m_b2a, _va) { \ (_vb).p = ( (_m_b2a).m[0]*(_va).p + (_m_b2a).m[3]*(_va).q + (_m_b2a).m[6]*(_va).r); \ (_vb).q = ( (_m_b2a).m[1]*(_va).p + (_m_b2a).m[4]*(_va).q + (_m_b2a).m[7]*(_va).r); \ (_vb).r = ( (_m_b2a).m[2]*(_va).p + (_m_b2a).m[5]*(_va).q + (_m_b2a).m[8]*(_va).r); \ } -#define FLOAT_RMAT_RATEMULT(_vb, _m_a2b, _va) { \ +#define FLOAT_RMAT_RATEMULT(_vb, _m_a2b, _va) { \ (_vb).p = ( (_m_a2b).m[0]*(_va).p + (_m_a2b).m[1]*(_va).q + (_m_a2b).m[2]*(_va).r); \ (_vb).q = ( (_m_a2b).m[3]*(_va).p + (_m_a2b).m[4]*(_va).q + (_m_a2b).m[5]*(_va).r); \ (_vb).r = ( (_m_a2b).m[6]*(_va).p + (_m_a2b).m[7]*(_va).q + (_m_a2b).m[8]*(_va).r); \ } /* _m_a2c = _m_a2b comp _m_b2c , aka _m_a2c = _m_b2c * _m_a2b */ -#define FLOAT_RMAT_COMP(_m_a2c, _m_a2b, _m_b2c) { \ +#define FLOAT_RMAT_COMP(_m_a2c, _m_a2b, _m_b2c) { \ _m_a2c.m[0] = (_m_b2c.m[0]*_m_a2b.m[0] + _m_b2c.m[1]*_m_a2b.m[3] + _m_b2c.m[2]*_m_a2b.m[6]); \ _m_a2c.m[1] = (_m_b2c.m[0]*_m_a2b.m[1] + _m_b2c.m[1]*_m_a2b.m[4] + _m_b2c.m[2]*_m_a2b.m[7]); \ _m_a2c.m[2] = (_m_b2c.m[0]*_m_a2b.m[2] + _m_b2c.m[1]*_m_a2b.m[5] + _m_b2c.m[2]*_m_a2b.m[8]); \ @@ -301,7 +301,7 @@ struct FloatRates { /* _m_a2b = _m_a2c comp_inv _m_b2c , aka _m_a2b = inv(_m_b2c) * _m_a2c */ -#define FLOAT_RMAT_COMP_INV(_m_a2b, _m_a2c, _m_b2c) { \ +#define FLOAT_RMAT_COMP_INV(_m_a2b, _m_a2c, _m_b2c) { \ _m_a2b.m[0] = (_m_b2c.m[0]*_m_a2c.m[0] + _m_b2c.m[3]*_m_a2c.m[3] + _m_b2c.m[6]*_m_a2c.m[6]); \ _m_a2b.m[1] = (_m_b2c.m[0]*_m_a2c.m[1] + _m_b2c.m[3]*_m_a2c.m[4] + _m_b2c.m[6]*_m_a2c.m[7]); \ _m_a2b.m[2] = (_m_b2c.m[0]*_m_a2c.m[2] + _m_b2c.m[3]*_m_a2c.m[5] + _m_b2c.m[6]*_m_a2c.m[8]); \ @@ -315,136 +315,136 @@ struct FloatRates { /* _m_b2a = inv(_m_a2b) = transp(_m_a2b) */ -#define FLOAT_RMAT_INV(_m_b2a, _m_a2b) { \ - RMAT_ELMT(_m_b2a, 0, 0) = RMAT_ELMT(_m_a2b, 0, 0); \ - RMAT_ELMT(_m_b2a, 0, 1) = RMAT_ELMT(_m_a2b, 1, 0); \ - RMAT_ELMT(_m_b2a, 0, 2) = RMAT_ELMT(_m_a2b, 2, 0); \ - RMAT_ELMT(_m_b2a, 1, 0) = RMAT_ELMT(_m_a2b, 0, 1); \ - RMAT_ELMT(_m_b2a, 1, 1) = RMAT_ELMT(_m_a2b, 1, 1); \ - RMAT_ELMT(_m_b2a, 1, 2) = RMAT_ELMT(_m_a2b, 2, 1); \ - RMAT_ELMT(_m_b2a, 2, 0) = RMAT_ELMT(_m_a2b, 0, 2); \ - RMAT_ELMT(_m_b2a, 2, 1) = RMAT_ELMT(_m_a2b, 1, 2); \ - RMAT_ELMT(_m_b2a, 2, 2) = RMAT_ELMT(_m_a2b, 2, 2); \ +#define FLOAT_RMAT_INV(_m_b2a, _m_a2b) { \ + RMAT_ELMT(_m_b2a, 0, 0) = RMAT_ELMT(_m_a2b, 0, 0); \ + RMAT_ELMT(_m_b2a, 0, 1) = RMAT_ELMT(_m_a2b, 1, 0); \ + RMAT_ELMT(_m_b2a, 0, 2) = RMAT_ELMT(_m_a2b, 2, 0); \ + RMAT_ELMT(_m_b2a, 1, 0) = RMAT_ELMT(_m_a2b, 0, 1); \ + RMAT_ELMT(_m_b2a, 1, 1) = RMAT_ELMT(_m_a2b, 1, 1); \ + RMAT_ELMT(_m_b2a, 1, 2) = RMAT_ELMT(_m_a2b, 2, 1); \ + RMAT_ELMT(_m_b2a, 2, 0) = RMAT_ELMT(_m_a2b, 0, 2); \ + RMAT_ELMT(_m_b2a, 2, 1) = RMAT_ELMT(_m_a2b, 1, 2); \ + RMAT_ELMT(_m_b2a, 2, 2) = RMAT_ELMT(_m_a2b, 2, 2); \ } -#define FLOAT_RMAT_NORM(_m) ( \ - sqrtf(SQUARE((_m).m[0])+ SQUARE((_m).m[1])+ SQUARE((_m).m[2])+ \ - SQUARE((_m).m[3])+ SQUARE((_m).m[4])+ SQUARE((_m).m[5])+ \ - SQUARE((_m).m[6])+ SQUARE((_m).m[7])+ SQUARE((_m).m[8])) \ +#define FLOAT_RMAT_NORM(_m) ( \ + sqrtf(SQUARE((_m).m[0])+ SQUARE((_m).m[1])+ SQUARE((_m).m[2])+ \ + SQUARE((_m).m[3])+ SQUARE((_m).m[4])+ SQUARE((_m).m[5])+ \ + SQUARE((_m).m[6])+ SQUARE((_m).m[7])+ SQUARE((_m).m[8])) \ ) #define FLOAT_RMAT_OF_EULERS(_rm, _e) FLOAT_RMAT_OF_EULERS_321(_rm, _e) /* C n->b rotation matrix */ -#define FLOAT_RMAT_OF_EULERS_321(_rm, _e) { \ - \ - const float sphi = sinf((_e).phi); \ - const float cphi = cosf((_e).phi); \ - const float stheta = sinf((_e).theta); \ - const float ctheta = cosf((_e).theta); \ - const float spsi = sinf((_e).psi); \ - const float cpsi = cosf((_e).psi); \ - \ - RMAT_ELMT(_rm, 0, 0) = ctheta*cpsi; \ - RMAT_ELMT(_rm, 0, 1) = ctheta*spsi; \ - RMAT_ELMT(_rm, 0, 2) = -stheta; \ - RMAT_ELMT(_rm, 1, 0) = sphi*stheta*cpsi - cphi*spsi; \ - RMAT_ELMT(_rm, 1, 1) = sphi*stheta*spsi + cphi*cpsi; \ - RMAT_ELMT(_rm, 1, 2) = sphi*ctheta; \ - RMAT_ELMT(_rm, 2, 0) = cphi*stheta*cpsi + sphi*spsi; \ - RMAT_ELMT(_rm, 2, 1) = cphi*stheta*spsi - sphi*cpsi; \ - RMAT_ELMT(_rm, 2, 2) = cphi*ctheta; \ - \ +#define FLOAT_RMAT_OF_EULERS_321(_rm, _e) { \ + \ + const float sphi = sinf((_e).phi); \ + const float cphi = cosf((_e).phi); \ + const float stheta = sinf((_e).theta); \ + const float ctheta = cosf((_e).theta); \ + const float spsi = sinf((_e).psi); \ + const float cpsi = cosf((_e).psi); \ + \ + RMAT_ELMT(_rm, 0, 0) = ctheta*cpsi; \ + RMAT_ELMT(_rm, 0, 1) = ctheta*spsi; \ + RMAT_ELMT(_rm, 0, 2) = -stheta; \ + RMAT_ELMT(_rm, 1, 0) = sphi*stheta*cpsi - cphi*spsi; \ + RMAT_ELMT(_rm, 1, 1) = sphi*stheta*spsi + cphi*cpsi; \ + RMAT_ELMT(_rm, 1, 2) = sphi*ctheta; \ + RMAT_ELMT(_rm, 2, 0) = cphi*stheta*cpsi + sphi*spsi; \ + RMAT_ELMT(_rm, 2, 1) = cphi*stheta*spsi - sphi*cpsi; \ + RMAT_ELMT(_rm, 2, 2) = cphi*ctheta; \ + \ } -#define FLOAT_RMAT_OF_EULERS_312(_rm, _e) { \ - \ - const float sphi = sinf((_e).phi); \ - const float cphi = cosf((_e).phi); \ - const float stheta = sinf((_e).theta); \ - const float ctheta = cosf((_e).theta); \ - const float spsi = sinf((_e).psi); \ - const float cpsi = cosf((_e).psi); \ - \ - RMAT_ELMT(_rm, 0, 0) = ctheta*cpsi - sphi * stheta * spsi; \ - RMAT_ELMT(_rm, 0, 1) = ctheta*spsi + sphi * stheta * cpsi; \ - RMAT_ELMT(_rm, 0, 2) = -cphi * stheta; \ - RMAT_ELMT(_rm, 1, 0) = -cphi * spsi; \ - RMAT_ELMT(_rm, 1, 1) = cphi * cpsi; \ - RMAT_ELMT(_rm, 1, 2) = sphi; \ - RMAT_ELMT(_rm, 2, 0) = stheta*cpsi + sphi*ctheta*spsi; \ - RMAT_ELMT(_rm, 2, 1) = stheta*spsi - sphi*ctheta*cpsi; \ - RMAT_ELMT(_rm, 2, 2) = cphi*ctheta; \ - \ +#define FLOAT_RMAT_OF_EULERS_312(_rm, _e) { \ + \ + const float sphi = sinf((_e).phi); \ + const float cphi = cosf((_e).phi); \ + const float stheta = sinf((_e).theta); \ + const float ctheta = cosf((_e).theta); \ + const float spsi = sinf((_e).psi); \ + const float cpsi = cosf((_e).psi); \ + \ + RMAT_ELMT(_rm, 0, 0) = ctheta*cpsi - sphi * stheta * spsi; \ + RMAT_ELMT(_rm, 0, 1) = ctheta*spsi + sphi * stheta * cpsi; \ + RMAT_ELMT(_rm, 0, 2) = -cphi * stheta; \ + RMAT_ELMT(_rm, 1, 0) = -cphi * spsi; \ + RMAT_ELMT(_rm, 1, 1) = cphi * cpsi; \ + RMAT_ELMT(_rm, 1, 2) = sphi; \ + RMAT_ELMT(_rm, 2, 0) = stheta*cpsi + sphi*ctheta*spsi; \ + RMAT_ELMT(_rm, 2, 1) = stheta*spsi - sphi*ctheta*cpsi; \ + RMAT_ELMT(_rm, 2, 2) = cphi*ctheta; \ + \ } /* C n->b rotation matrix */ #ifdef ALGEBRA_FLOAT_USE_SLOW_FUNCTIONS -#define FLOAT_RMAT_OF_QUAT(_rm, _q) { \ - const float qx2 = (_q).qx*(_q).qx; \ - const float qy2 = (_q).qy*(_q).qy; \ - const float qz2 = (_q).qz*(_q).qz; \ - const float qiqx = (_q).qi*(_q).qx; \ - const float qiqy = (_q).qi*(_q).qy; \ - const float qiqz = (_q).qi*(_q).qz; \ - const float qxqy = (_q).qx*(_q).qy; \ - const float qxqz = (_q).qx*(_q).qz; \ - const float qyqz = (_q).qy*(_q).qz; \ - /* dcm00 = 1.0 - 2.*( qy2 + qz2 ); */ \ - RMAT_ELMT(_rm, 0, 0) = 1. - 2.*( qy2 + qz2 ); \ - /* dcm01 = 2.*( qxqy + qiqz ); */ \ - RMAT_ELMT(_rm, 0, 1) = 2.*( qxqy + qiqz ); \ - /* dcm02 = 2.*( qxqz - qiqy ); */ \ - RMAT_ELMT(_rm, 0, 2) = 2.*( qxqz - qiqy ); \ - /* dcm10 = 2.*( qxqy - qiqz ); */ \ - RMAT_ELMT(_rm, 1, 0) = 2.*( qxqy - qiqz ); \ - /* dcm11 = 1.0 - 2.*(qx2+qz2); */ \ - RMAT_ELMT(_rm, 1, 1) = 1.0 - 2.*(qx2+qz2); \ - /* dcm12 = 2.*( qyqz + qiqx ); */ \ - RMAT_ELMT(_rm, 1, 2) = 2.*( qyqz + qiqx ); \ - /* dcm20 = 2.*( qxqz + qiqy ); */ \ - RMAT_ELMT(_rm, 2, 0) = 2.*( qxqz + qiqy ); \ - /* dcm21 = 2.*( qyqz - qiqx ); */ \ - RMAT_ELMT(_rm, 2, 1) = 2.*( qyqz - qiqx ); \ - /* dcm22 = 1.0 - 2.*( qx2 + qy2 ); */ \ - RMAT_ELMT(_rm, 2, 2) = 1.0 - 2.*( qx2 + qy2 ); \ +#define FLOAT_RMAT_OF_QUAT(_rm, _q) { \ + const float qx2 = (_q).qx*(_q).qx; \ + const float qy2 = (_q).qy*(_q).qy; \ + const float qz2 = (_q).qz*(_q).qz; \ + const float qiqx = (_q).qi*(_q).qx; \ + const float qiqy = (_q).qi*(_q).qy; \ + const float qiqz = (_q).qi*(_q).qz; \ + const float qxqy = (_q).qx*(_q).qy; \ + const float qxqz = (_q).qx*(_q).qz; \ + const float qyqz = (_q).qy*(_q).qz; \ + /* dcm00 = 1.0 - 2.*( qy2 + qz2 ); */ \ + RMAT_ELMT(_rm, 0, 0) = 1. - 2.*( qy2 + qz2 ); \ + /* dcm01 = 2.*( qxqy + qiqz ); */ \ + RMAT_ELMT(_rm, 0, 1) = 2.*( qxqy + qiqz ); \ + /* dcm02 = 2.*( qxqz - qiqy ); */ \ + RMAT_ELMT(_rm, 0, 2) = 2.*( qxqz - qiqy ); \ + /* dcm10 = 2.*( qxqy - qiqz ); */ \ + RMAT_ELMT(_rm, 1, 0) = 2.*( qxqy - qiqz ); \ + /* dcm11 = 1.0 - 2.*(qx2+qz2); */ \ + RMAT_ELMT(_rm, 1, 1) = 1.0 - 2.*(qx2+qz2); \ + /* dcm12 = 2.*( qyqz + qiqx ); */ \ + RMAT_ELMT(_rm, 1, 2) = 2.*( qyqz + qiqx ); \ + /* dcm20 = 2.*( qxqz + qiqy ); */ \ + RMAT_ELMT(_rm, 2, 0) = 2.*( qxqz + qiqy ); \ + /* dcm21 = 2.*( qyqz - qiqx ); */ \ + RMAT_ELMT(_rm, 2, 1) = 2.*( qyqz - qiqx ); \ + /* dcm22 = 1.0 - 2.*( qx2 + qy2 ); */ \ + RMAT_ELMT(_rm, 2, 2) = 1.0 - 2.*( qx2 + qy2 ); \ } #else -#define FLOAT_RMAT_OF_QUAT(_rm, _q) { \ - const float _a = M_SQRT2*(_q).qi; \ - const float _b = M_SQRT2*(_q).qx; \ - const float _c = M_SQRT2*(_q).qy; \ - const float _d = M_SQRT2*(_q).qz; \ - const float a2_1 = _a*_a-1; \ - const float ab = _a*_b; \ - const float ac = _a*_c; \ - const float ad = _a*_d; \ - const float bc = _b*_c; \ - const float bd = _b*_d; \ - const float cd = _c*_d; \ - RMAT_ELMT(_rm, 0, 0) = a2_1+_b*_b; \ - RMAT_ELMT(_rm, 0, 1) = bc+ad; \ - RMAT_ELMT(_rm, 0, 2) = bd-ac; \ - RMAT_ELMT(_rm, 1, 0) = bc-ad; \ - RMAT_ELMT(_rm, 1, 1) = a2_1+_c*_c; \ - RMAT_ELMT(_rm, 1, 2) = cd+ab; \ - RMAT_ELMT(_rm, 2, 0) = bd+ac; \ - RMAT_ELMT(_rm, 2, 1) = cd-ab; \ - RMAT_ELMT(_rm, 2, 2) = a2_1+_d*_d; \ +#define FLOAT_RMAT_OF_QUAT(_rm, _q) { \ + const float _a = M_SQRT2*(_q).qi; \ + const float _b = M_SQRT2*(_q).qx; \ + const float _c = M_SQRT2*(_q).qy; \ + const float _d = M_SQRT2*(_q).qz; \ + const float a2_1 = _a*_a-1; \ + const float ab = _a*_b; \ + const float ac = _a*_c; \ + const float ad = _a*_d; \ + const float bc = _b*_c; \ + const float bd = _b*_d; \ + const float cd = _c*_d; \ + RMAT_ELMT(_rm, 0, 0) = a2_1+_b*_b; \ + RMAT_ELMT(_rm, 0, 1) = bc+ad; \ + RMAT_ELMT(_rm, 0, 2) = bd-ac; \ + RMAT_ELMT(_rm, 1, 0) = bc-ad; \ + RMAT_ELMT(_rm, 1, 1) = a2_1+_c*_c; \ + RMAT_ELMT(_rm, 1, 2) = cd+ab; \ + RMAT_ELMT(_rm, 2, 0) = bd+ac; \ + RMAT_ELMT(_rm, 2, 1) = cd-ab; \ + RMAT_ELMT(_rm, 2, 2) = a2_1+_d*_d; \ } #endif /* in place first order integration of a rotation matrix */ -#define FLOAT_RMAT_INTEGRATE_FI(_rm, _omega, _dt ) { \ - struct FloatRMat exp_omega_dt = { \ - { 1. , dt*omega.r, -dt*omega.q, \ - -dt*omega.r, 1. , dt*omega.p, \ - dt*omega.q, -dt*omega.p, 1. }}; \ - struct FloatRMat R_tdt; \ - FLOAT_RMAT_COMP(R_tdt, _rm, exp_omega_dt); \ - memcpy(&(_rm), &R_tdt, sizeof(R_tdt)); \ +#define FLOAT_RMAT_INTEGRATE_FI(_rm, _omega, _dt ) { \ + struct FloatRMat exp_omega_dt = { \ + { 1. , dt*omega.r, -dt*omega.q, \ + -dt*omega.r, 1. , dt*omega.p, \ + dt*omega.q, -dt*omega.p, 1. }}; \ + struct FloatRMat R_tdt; \ + FLOAT_RMAT_COMP(R_tdt, _rm, exp_omega_dt); \ + memcpy(&(_rm), &R_tdt, sizeof(R_tdt)); \ } @@ -500,10 +500,10 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { #define FLOAT_QUAT_COPY(_qo, _qi) QUAT_COPY(_qo, _qi) -#define FLOAT_QUAT_NORM(_q) (sqrtf(SQUARE((_q).qi) + SQUARE((_q).qx)+ \ +#define FLOAT_QUAT_NORM(_q) (sqrtf(SQUARE((_q).qi) + SQUARE((_q).qx)+ \ SQUARE((_q).qy) + SQUARE((_q).qz))) -#define FLOAT_QUAT_NORMALIZE(_q) { \ +#define FLOAT_QUAT_NORMALIZE(_q) { \ float norm = FLOAT_QUAT_NORM(_q); \ if (norm > FLT_MIN) { \ (_q).qi = (_q).qi / norm; \ @@ -515,20 +515,20 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { #define FLOAT_QUAT_INVERT(_qo, _qi) QUAT_INVERT(_qo, _qi) -#define FLOAT_QUAT_WRAP_SHORTEST(_q) { \ +#define FLOAT_QUAT_WRAP_SHORTEST(_q) { \ if ((_q).qi < 0.) \ - QUAT_EXPLEMENTARY(_q,_q); \ + QUAT_EXPLEMENTARY(_q,_q); \ } /* _a2c = _a2b comp _b2c , aka _a2c = _a2b * _b2c */ -#define FLOAT_QUAT_COMP_NORM_SHORTEST(_a2c, _a2b, _b2c) { \ - FLOAT_QUAT_COMP(_a2c, _a2b, _b2c); \ - FLOAT_QUAT_WRAP_SHORTEST(_a2c); \ - FLOAT_QUAT_NORMALIZE(_a2c); \ +#define FLOAT_QUAT_COMP_NORM_SHORTEST(_a2c, _a2b, _b2c) { \ + FLOAT_QUAT_COMP(_a2c, _a2b, _b2c); \ + FLOAT_QUAT_WRAP_SHORTEST(_a2c); \ + FLOAT_QUAT_NORMALIZE(_a2c); \ } /* _a2c = _a2b comp _b2c , aka _a2c = _a2b * _b2c */ -#define FLOAT_QUAT_COMP(_a2c, _a2b, _b2c) { \ +#define FLOAT_QUAT_COMP(_a2c, _a2b, _b2c) { \ (_a2c).qi = (_a2b).qi*(_b2c).qi - (_a2b).qx*(_b2c).qx - (_a2b).qy*(_b2c).qy - (_a2b).qz*(_b2c).qz; \ (_a2c).qx = (_a2b).qi*(_b2c).qx + (_a2b).qx*(_b2c).qi + (_a2b).qy*(_b2c).qz - (_a2b).qz*(_b2c).qy; \ (_a2c).qy = (_a2b).qi*(_b2c).qy - (_a2b).qx*(_b2c).qz + (_a2b).qy*(_b2c).qi + (_a2b).qz*(_b2c).qx; \ @@ -538,14 +538,14 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { #define FLOAT_QUAT_MULT(_a2c, _a2b, _b2c) FLOAT_QUAT_COMP(_a2c, _a2b, _b2c) /* _a2b = _a2c comp_inv _b2c , aka _a2b = _a2c * inv(_b2c) */ -#define FLOAT_QUAT_COMP_INV_NORM_SHORTEST(_a2b, _a2c, _b2c) { \ - FLOAT_QUAT_COMP_INV(_a2b, _a2c, _b2c); \ - FLOAT_QUAT_WRAP_SHORTEST(_a2b); \ - FLOAT_QUAT_NORMALIZE(_a2b); \ +#define FLOAT_QUAT_COMP_INV_NORM_SHORTEST(_a2b, _a2c, _b2c) { \ + FLOAT_QUAT_COMP_INV(_a2b, _a2c, _b2c); \ + FLOAT_QUAT_WRAP_SHORTEST(_a2b); \ + FLOAT_QUAT_NORMALIZE(_a2b); \ } /* _a2b = _a2c comp_inv _b2c , aka _a2b = _a2c * inv(_b2c) */ -#define FLOAT_QUAT_COMP_INV(_a2b, _a2c, _b2c) { \ +#define FLOAT_QUAT_COMP_INV(_a2b, _a2c, _b2c) { \ (_a2b).qi = (_a2c).qi*(_b2c).qi + (_a2c).qx*(_b2c).qx + (_a2c).qy*(_b2c).qy + (_a2c).qz*(_b2c).qz; \ (_a2b).qx = -(_a2c).qi*(_b2c).qx + (_a2c).qx*(_b2c).qi - (_a2c).qy*(_b2c).qz + (_a2c).qz*(_b2c).qy; \ (_a2b).qy = -(_a2c).qi*(_b2c).qy + (_a2c).qx*(_b2c).qz + (_a2c).qy*(_b2c).qi - (_a2c).qz*(_b2c).qx; \ @@ -553,110 +553,110 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { } /* _b2c = _a2b inv_comp _a2c , aka _b2c = inv(_a2b) * _a2c */ -#define FLOAT_QUAT_INV_COMP_NORM_SHORTEST(_b2c, _a2b, _a2c) { \ - FLOAT_QUAT_INV_COMP(_b2c, _a2b, _a2c); \ - FLOAT_QUAT_WRAP_SHORTEST(_b2c); \ - FLOAT_QUAT_NORMALIZE(_b2c); \ +#define FLOAT_QUAT_INV_COMP_NORM_SHORTEST(_b2c, _a2b, _a2c) { \ + FLOAT_QUAT_INV_COMP(_b2c, _a2b, _a2c); \ + FLOAT_QUAT_WRAP_SHORTEST(_b2c); \ + FLOAT_QUAT_NORMALIZE(_b2c); \ } /* _b2c = _a2b inv_comp _a2c , aka _b2c = inv(_a2b) * _a2c */ -#define FLOAT_QUAT_INV_COMP(_b2c, _a2b, _a2c) { \ +#define FLOAT_QUAT_INV_COMP(_b2c, _a2b, _a2c) { \ (_b2c).qi = (_a2b).qi*(_a2c).qi + (_a2b).qx*(_a2c).qx + (_a2b).qy*(_a2c).qy + (_a2b).qz*(_a2c).qz; \ (_b2c).qx = (_a2b).qi*(_a2c).qx - (_a2b).qx*(_a2c).qi - (_a2b).qy*(_a2c).qz + (_a2b).qz*(_a2c).qy; \ (_b2c).qy = (_a2b).qi*(_a2c).qy + (_a2b).qx*(_a2c).qz - (_a2b).qy*(_a2c).qi - (_a2b).qz*(_a2c).qx; \ (_b2c).qz = (_a2b).qi*(_a2c).qz - (_a2b).qx*(_a2c).qy + (_a2b).qy*(_a2c).qx - (_a2b).qz*(_a2c).qi; \ } -#define FLOAT_QUAT_DIFFERENTIAL(q_out, w, dt) { \ +#define FLOAT_QUAT_DIFFERENTIAL(q_out, w, dt) { \ const float v_norm = sqrt((w).p*(w).p + (w).q*(w).q + (w).r*(w).r); \ - const float c2 = cos(dt*v_norm/2.0); \ - const float s2 = sin(dt*v_norm/2.0); \ - if (v_norm < 1e-8) { \ - (q_out).qi = 1; \ - (q_out).qx = 0; \ - (q_out).qy = 0; \ - (q_out).qz = 0; \ - } else { \ - (q_out).qi = c2; \ - (q_out).qx = (w).p/v_norm * s2; \ - (q_out).qy = (w).q/v_norm * s2; \ - (q_out).qz = (w).r/v_norm * s2; \ - } \ + const float c2 = cos(dt*v_norm/2.0); \ + const float s2 = sin(dt*v_norm/2.0); \ + if (v_norm < 1e-8) { \ + (q_out).qi = 1; \ + (q_out).qx = 0; \ + (q_out).qy = 0; \ + (q_out).qz = 0; \ + } else { \ + (q_out).qi = c2; \ + (q_out).qx = (w).p/v_norm * s2; \ + (q_out).qy = (w).q/v_norm * s2; \ + (q_out).qz = (w).r/v_norm * s2; \ + } \ } /* in place quaternion integration with constante rotational velocity */ -#define FLOAT_QUAT_INTEGRATE(_q, _omega, _dt) { \ - const float no = FLOAT_RATES_NORM(_omega); \ - if (no > FLT_MIN) { \ +#define FLOAT_QUAT_INTEGRATE(_q, _omega, _dt) { \ + const float no = FLOAT_RATES_NORM(_omega); \ + if (no > FLT_MIN) { \ const float a = 0.5*no*(_dt); \ - const float ca = cosf(a); \ - const float sa_ov_no = sinf(a)/no; \ - const float dp = sa_ov_no*(_omega).p; \ - const float dq = sa_ov_no*(_omega).q; \ - const float dr = sa_ov_no*(_omega).r; \ - const float qi = (_q).qi; \ - const float qx = (_q).qx; \ - const float qy = (_q).qy; \ - const float qz = (_q).qz; \ - (_q).qi = ca*qi - dp*qx - dq*qy - dr*qz; \ - (_q).qx = dp*qi + ca*qx + dr*qy - dq*qz; \ - (_q).qy = dq*qi - dr*qx + ca*qy + dp*qz; \ - (_q).qz = dr*qi + dq*qx - dp*qy + ca*qz; \ - } \ + const float ca = cosf(a); \ + const float sa_ov_no = sinf(a)/no; \ + const float dp = sa_ov_no*(_omega).p; \ + const float dq = sa_ov_no*(_omega).q; \ + const float dr = sa_ov_no*(_omega).r; \ + const float qi = (_q).qi; \ + const float qx = (_q).qx; \ + const float qy = (_q).qy; \ + const float qz = (_q).qz; \ + (_q).qi = ca*qi - dp*qx - dq*qy - dr*qz; \ + (_q).qx = dp*qi + ca*qx + dr*qy - dq*qz; \ + (_q).qy = dq*qi - dr*qx + ca*qy + dp*qz; \ + (_q).qz = dr*qi + dq*qx - dp*qy + ca*qz; \ + } \ } #ifdef ALGEBRA_FLOAT_USE_SLOW_FUNCTIONS -#define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ - const float qi2 = (q).qi*(q).qi; \ - const float qiqx = (q).qi*(q).qx; \ - const float qiqy = (q).qi*(q).qy; \ - const float qiqz = (q).qi*(q).qz; \ - const float qx2 = (q).qx*(q).qx; \ - const float qxqy = (q).qx*(q).qy; \ - const float qxqz = (q).qx*(q).qz; \ - const float qy2 = (q).qy*(q).qy; \ - const float qyqz = (q).qy*(q).qz; \ - const float qz2 = (q).qz*(q).qz; \ - const float m00 = qi2 + qx2 - qy2 - qz2; \ - const float m01 = 2 * ( qxqy + qiqz ); \ - const float m02 = 2 * ( qxqz - qiqy ); \ - const float m10 = 2 * ( qxqy - qiqz ); \ - const float m11 = qi2 - qx2 + qy2 - qz2; \ - const float m12 = 2 * ( qyqz + qiqx ); \ - const float m20 = 2 * ( qxqz + qiqy ); \ - const float m21 = 2 * ( qyqz - qiqx ); \ - const float m22 = qi2 - qx2 - qy2 + qz2; \ - (v_out).x = m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z; \ - (v_out).y = m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z; \ - (v_out).z = m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z; \ +#define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ + const float qi2 = (q).qi*(q).qi; \ + const float qiqx = (q).qi*(q).qx; \ + const float qiqy = (q).qi*(q).qy; \ + const float qiqz = (q).qi*(q).qz; \ + const float qx2 = (q).qx*(q).qx; \ + const float qxqy = (q).qx*(q).qy; \ + const float qxqz = (q).qx*(q).qz; \ + const float qy2 = (q).qy*(q).qy; \ + const float qyqz = (q).qy*(q).qz; \ + const float qz2 = (q).qz*(q).qz; \ + const float m00 = qi2 + qx2 - qy2 - qz2; \ + const float m01 = 2 * ( qxqy + qiqz ); \ + const float m02 = 2 * ( qxqz - qiqy ); \ + const float m10 = 2 * ( qxqy - qiqz ); \ + const float m11 = qi2 - qx2 + qy2 - qz2; \ + const float m12 = 2 * ( qyqz + qiqx ); \ + const float m20 = 2 * ( qxqz + qiqy ); \ + const float m21 = 2 * ( qyqz - qiqx ); \ + const float m22 = qi2 - qx2 - qy2 + qz2; \ + (v_out).x = m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z; \ + (v_out).y = m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z; \ + (v_out).z = m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z; \ } #else -#define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ - const float qi2_M1_2 = (q).qi*(q).qi - 0.5; \ - const float qiqx = (q).qi*(q).qx; \ - const float qiqy = (q).qi*(q).qy; \ - const float qiqz = (q).qi*(q).qz; \ - float m01 = (q).qx*(q).qy; /* aka qxqy */ \ - float m02 = (q).qx*(q).qz; /* aka qxqz */ \ - float m12 = (q).qy*(q).qz; /* aka qyqz */ \ +#define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ + const float qi2_M1_2 = (q).qi*(q).qi - 0.5; \ + const float qiqx = (q).qi*(q).qx; \ + const float qiqy = (q).qi*(q).qy; \ + const float qiqz = (q).qi*(q).qz; \ + float m01 = (q).qx*(q).qy; /* aka qxqy */ \ + float m02 = (q).qx*(q).qz; /* aka qxqz */ \ + float m12 = (q).qy*(q).qz; /* aka qyqz */ \ \ - const float m00 = qi2_M1_2 + (q).qx*(q).qx; \ - const float m10 = m01 - qiqz; \ - const float m20 = m02 + qiqy; \ - const float m21 = m12 - qiqx; \ - m01 += qiqz; \ - m02 -= qiqy; \ - m12 += qiqx; \ - const float m11 = qi2_M1_2 + (q).qy*(q).qy; \ - const float m22 = qi2_M1_2 + (q).qz*(q).qz; \ - (v_out).x = 2*(m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z); \ - (v_out).y = 2*(m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z); \ - (v_out).z = 2*(m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z); \ + const float m00 = qi2_M1_2 + (q).qx*(q).qx; \ + const float m10 = m01 - qiqz; \ + const float m20 = m02 + qiqy; \ + const float m21 = m12 - qiqx; \ + m01 += qiqz; \ + m02 -= qiqy; \ + m12 += qiqx; \ + const float m11 = qi2_M1_2 + (q).qy*(q).qy; \ + const float m22 = qi2_M1_2 + (q).qz*(q).qz; \ + (v_out).x = 2*(m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z); \ + (v_out).y = 2*(m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z); \ + (v_out).z = 2*(m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z); \ } #endif /* _qd = -0.5*omega(_r) * _q */ -#define FLOAT_QUAT_DERIVATIVE(_qd, _r, _q) { \ +#define FLOAT_QUAT_DERIVATIVE(_qd, _r, _q) { \ (_qd).qi = -0.5*( (_r).p*(_q).qx + (_r).q*(_q).qy + (_r).r*(_q).qz); \ (_qd).qx = -0.5*(-(_r).p*(_q).qi - (_r).r*(_q).qy + (_r).q*(_q).qz); \ (_qd).qy = -0.5*(-(_r).q*(_q).qi + (_r).r*(_q).qx - (_r).p*(_q).qz); \ @@ -664,33 +664,33 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { } /* _qd = -0.5*omega(_r) * _q */ -#define FLOAT_QUAT_DERIVATIVE_LAGRANGE(_qd, _r, _q) { \ - const float K_LAGRANGE = 1.; \ - const float c = K_LAGRANGE * ( 1 - FLOAT_QUAT_NORM(_q)) / -0.5; \ +#define FLOAT_QUAT_DERIVATIVE_LAGRANGE(_qd, _r, _q) { \ + const float K_LAGRANGE = 1.; \ + const float c = K_LAGRANGE * ( 1 - FLOAT_QUAT_NORM(_q)) / -0.5; \ (_qd).qi = -0.5*( c*(_q).qi + (_r).p*(_q).qx + (_r).q*(_q).qy + (_r).r*(_q).qz); \ (_qd).qx = -0.5*(-(_r).p*(_q).qi + c*(_q).qx - (_r).r*(_q).qy + (_r).q*(_q).qz); \ (_qd).qy = -0.5*(-(_r).q*(_q).qi + (_r).r*(_q).qx + c*(_q).qy - (_r).p*(_q).qz); \ (_qd).qz = -0.5*(-(_r).r*(_q).qi - (_r).q*(_q).qx + (_r).p*(_q).qy + c*(_q).qz); \ } -#define FLOAT_QUAT_OF_EULERS(_q, _e) { \ - \ - const float phi2 = (_e).phi/2.0; \ - const float theta2 = (_e).theta/2.0; \ - const float psi2 = (_e).psi/2.0; \ - \ - const float s_phi2 = sinf( phi2 ); \ - const float c_phi2 = cosf( phi2 ); \ - const float s_theta2 = sinf( theta2 ); \ - const float c_theta2 = cosf( theta2 ); \ - const float s_psi2 = sinf( psi2 ); \ - const float c_psi2 = cosf( psi2 ); \ - \ +#define FLOAT_QUAT_OF_EULERS(_q, _e) { \ + \ + const float phi2 = (_e).phi/2.0; \ + const float theta2 = (_e).theta/2.0; \ + const float psi2 = (_e).psi/2.0; \ + \ + const float s_phi2 = sinf( phi2 ); \ + const float c_phi2 = cosf( phi2 ); \ + const float s_theta2 = sinf( theta2 ); \ + const float c_theta2 = cosf( theta2 ); \ + const float s_psi2 = sinf( psi2 ); \ + const float c_psi2 = cosf( psi2 ); \ + \ (_q).qi = c_phi2 * c_theta2 * c_psi2 + s_phi2 * s_theta2 * s_psi2; \ (_q).qx = -c_phi2 * s_theta2 * s_psi2 + s_phi2 * c_theta2 * c_psi2; \ (_q).qy = c_phi2 * s_theta2 * c_psi2 + s_phi2 * c_theta2 * s_psi2; \ (_q).qz = c_phi2 * c_theta2 * s_psi2 - s_phi2 * s_theta2 * c_psi2; \ - \ + \ } #define FLOAT_QUAT_OF_AXIS_ANGLE(_q, _uv, _an) { \ @@ -701,50 +701,50 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { (_q).qz = san * (_uv).z; \ } -#define FLOAT_QUAT_OF_RMAT(_q, _r) { \ - const float tr = RMAT_TRACE((_r)); \ - if (tr > 0) { \ - const float two_qi = sqrtf(1.+tr); \ - const float four_qi = 2. * two_qi; \ - (_q).qi = 0.5 * two_qi; \ - (_q).qx = (RMAT_ELMT((_r), 1, 2)-RMAT_ELMT((_r), 2, 1))/four_qi; \ - (_q).qy = (RMAT_ELMT((_r), 2, 0)-RMAT_ELMT((_r), 0, 2))/four_qi; \ - (_q).qz = (RMAT_ELMT((_r), 0, 1)-RMAT_ELMT((_r), 1, 0))/four_qi; \ - /*printf("tr > 0\n");*/ \ - } \ - else { \ - if (RMAT_ELMT((_r), 0, 0) > RMAT_ELMT((_r), 1, 1) && \ - RMAT_ELMT((_r), 0, 0) > RMAT_ELMT((_r), 2, 2)) { \ - const float two_qx = sqrtf(RMAT_ELMT((_r), 0, 0) -RMAT_ELMT((_r), 1, 1) \ - -RMAT_ELMT((_r), 2, 2) + 1); \ - const float four_qx = 2. * two_qx; \ - (_q).qi = (RMAT_ELMT((_r), 1, 2)-RMAT_ELMT((_r), 2, 1))/four_qx; \ - (_q).qx = 0.5 * two_qx; \ - (_q).qy = (RMAT_ELMT((_r), 0, 1)+RMAT_ELMT((_r), 1, 0))/four_qx; \ - (_q).qz = (RMAT_ELMT((_r), 2, 0)+RMAT_ELMT((_r), 0, 2))/four_qx; \ - /*printf("m00 largest\n");*/ \ - } \ - else if (RMAT_ELMT((_r), 1, 1) > RMAT_ELMT((_r), 2, 2)) { \ - const float two_qy = \ - sqrtf(RMAT_ELMT((_r), 1, 1) - RMAT_ELMT((_r), 0, 0) - RMAT_ELMT((_r), 2, 2) + 1); \ - const float four_qy = 2. * two_qy; \ - (_q).qi = (RMAT_ELMT((_r), 2, 0) - RMAT_ELMT((_r), 0, 2))/four_qy; \ - (_q).qx = (RMAT_ELMT((_r), 0, 1) + RMAT_ELMT((_r), 1, 0))/four_qy; \ - (_q).qy = 0.5 * two_qy; \ - (_q).qz = (RMAT_ELMT((_r), 1, 2) + RMAT_ELMT((_r), 2, 1))/four_qy; \ - /*printf("m11 largest\n");*/ \ - } \ - else { \ - const float two_qz = \ - sqrtf(RMAT_ELMT((_r), 2, 2) - RMAT_ELMT((_r), 0, 0) - RMAT_ELMT((_r), 1, 1) + 1); \ - const float four_qz = 2. * two_qz; \ - (_q).qi = (RMAT_ELMT((_r), 0, 1)- RMAT_ELMT((_r), 1, 0))/four_qz; \ - (_q).qx = (RMAT_ELMT((_r), 2, 0)+ RMAT_ELMT((_r), 0, 2))/four_qz; \ - (_q).qy = (RMAT_ELMT((_r), 1, 2)+ RMAT_ELMT((_r), 2, 1))/four_qz; \ - (_q).qz = 0.5 * two_qz; \ - /*printf("m22 largest\n");*/ \ - } \ - } \ +#define FLOAT_QUAT_OF_RMAT(_q, _r) { \ + const float tr = RMAT_TRACE((_r)); \ + if (tr > 0) { \ + const float two_qi = sqrtf(1.+tr); \ + const float four_qi = 2. * two_qi; \ + (_q).qi = 0.5 * two_qi; \ + (_q).qx = (RMAT_ELMT((_r), 1, 2)-RMAT_ELMT((_r), 2, 1))/four_qi; \ + (_q).qy = (RMAT_ELMT((_r), 2, 0)-RMAT_ELMT((_r), 0, 2))/four_qi; \ + (_q).qz = (RMAT_ELMT((_r), 0, 1)-RMAT_ELMT((_r), 1, 0))/four_qi; \ + /*printf("tr > 0\n");*/ \ + } \ + else { \ + if (RMAT_ELMT((_r), 0, 0) > RMAT_ELMT((_r), 1, 1) && \ + RMAT_ELMT((_r), 0, 0) > RMAT_ELMT((_r), 2, 2)) { \ + const float two_qx = sqrtf(RMAT_ELMT((_r), 0, 0) -RMAT_ELMT((_r), 1, 1) \ + -RMAT_ELMT((_r), 2, 2) + 1); \ + const float four_qx = 2. * two_qx; \ + (_q).qi = (RMAT_ELMT((_r), 1, 2)-RMAT_ELMT((_r), 2, 1))/four_qx; \ + (_q).qx = 0.5 * two_qx; \ + (_q).qy = (RMAT_ELMT((_r), 0, 1)+RMAT_ELMT((_r), 1, 0))/four_qx; \ + (_q).qz = (RMAT_ELMT((_r), 2, 0)+RMAT_ELMT((_r), 0, 2))/four_qx; \ + /*printf("m00 largest\n");*/ \ + } \ + else if (RMAT_ELMT((_r), 1, 1) > RMAT_ELMT((_r), 2, 2)) { \ + const float two_qy = \ + sqrtf(RMAT_ELMT((_r), 1, 1) - RMAT_ELMT((_r), 0, 0) - RMAT_ELMT((_r), 2, 2) + 1); \ + const float four_qy = 2. * two_qy; \ + (_q).qi = (RMAT_ELMT((_r), 2, 0) - RMAT_ELMT((_r), 0, 2))/four_qy; \ + (_q).qx = (RMAT_ELMT((_r), 0, 1) + RMAT_ELMT((_r), 1, 0))/four_qy; \ + (_q).qy = 0.5 * two_qy; \ + (_q).qz = (RMAT_ELMT((_r), 1, 2) + RMAT_ELMT((_r), 2, 1))/four_qy; \ + /*printf("m11 largest\n");*/ \ + } \ + else { \ + const float two_qz = \ + sqrtf(RMAT_ELMT((_r), 2, 2) - RMAT_ELMT((_r), 0, 0) - RMAT_ELMT((_r), 1, 1) + 1); \ + const float four_qz = 2. * two_qz; \ + (_q).qi = (RMAT_ELMT((_r), 0, 1)- RMAT_ELMT((_r), 1, 0))/four_qz; \ + (_q).qx = (RMAT_ELMT((_r), 2, 0)+ RMAT_ELMT((_r), 0, 2))/four_qz; \ + (_q).qy = (RMAT_ELMT((_r), 1, 2)+ RMAT_ELMT((_r), 2, 1))/four_qz; \ + (_q).qz = 0.5 * two_qz; \ + /*printf("m22 largest\n");*/ \ + } \ + } \ } @@ -756,40 +756,40 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { #define FLOAT_EULERS_NORM(_e) (sqrtf(SQUARE((_e).phi)+SQUARE((_e).theta)+SQUARE((_e).psi))) ; -#define FLOAT_EULERS_OF_RMAT(_e, _rm) { \ - \ - const float dcm00 = (_rm).m[0]; \ - const float dcm01 = (_rm).m[1]; \ - const float dcm02 = (_rm).m[2]; \ - const float dcm12 = (_rm).m[5]; \ - const float dcm22 = (_rm).m[8]; \ - (_e).phi = atan2f( dcm12, dcm22 ); \ - (_e).theta = -asinf( dcm02 ); \ - (_e).psi = atan2f( dcm01, dcm00 ); \ - \ +#define FLOAT_EULERS_OF_RMAT(_e, _rm) { \ + \ + const float dcm00 = (_rm).m[0]; \ + const float dcm01 = (_rm).m[1]; \ + const float dcm02 = (_rm).m[2]; \ + const float dcm12 = (_rm).m[5]; \ + const float dcm22 = (_rm).m[8]; \ + (_e).phi = atan2f( dcm12, dcm22 ); \ + (_e).theta = -asinf( dcm02 ); \ + (_e).psi = atan2f( dcm01, dcm00 ); \ + \ } -#define FLOAT_EULERS_OF_QUAT(_e, _q) { \ - \ - const float qx2 = (_q).qx*(_q).qx; \ - const float qy2 = (_q).qy*(_q).qy; \ - const float qz2 = (_q).qz*(_q).qz; \ - const float qiqx = (_q).qi*(_q).qx; \ - const float qiqy = (_q).qi*(_q).qy; \ - const float qiqz = (_q).qi*(_q).qz; \ - const float qxqy = (_q).qx*(_q).qy; \ - const float qxqz = (_q).qx*(_q).qz; \ - const float qyqz = (_q).qy*(_q).qz; \ - const float dcm00 = 1.0 - 2.*( qy2 + qz2 ); \ - const float dcm01 = 2.*( qxqy + qiqz ); \ - const float dcm02 = 2.*( qxqz - qiqy ); \ - const float dcm12 = 2.*( qyqz + qiqx ); \ - const float dcm22 = 1.0 - 2.*( qx2 + qy2 ); \ - \ - (_e).phi = atan2f( dcm12, dcm22 ); \ - (_e).theta = -asinf( dcm02 ); \ - (_e).psi = atan2f( dcm01, dcm00 ); \ - \ +#define FLOAT_EULERS_OF_QUAT(_e, _q) { \ + \ + const float qx2 = (_q).qx*(_q).qx; \ + const float qy2 = (_q).qy*(_q).qy; \ + const float qz2 = (_q).qz*(_q).qz; \ + const float qiqx = (_q).qi*(_q).qx; \ + const float qiqy = (_q).qi*(_q).qy; \ + const float qiqz = (_q).qi*(_q).qz; \ + const float qxqy = (_q).qx*(_q).qy; \ + const float qxqz = (_q).qx*(_q).qz; \ + const float qyqz = (_q).qy*(_q).qz; \ + const float dcm00 = 1.0 - 2.*( qy2 + qz2 ); \ + const float dcm01 = 2.*( qxqy + qiqz ); \ + const float dcm02 = 2.*( qxqz - qiqy ); \ + const float dcm12 = 2.*( qyqz + qiqx ); \ + const float dcm22 = 1.0 - 2.*( qx2 + qy2 ); \ + \ + (_e).phi = atan2f( dcm12, dcm22 ); \ + (_e).theta = -asinf( dcm02 ); \ + (_e).psi = atan2f( dcm01, dcm00 ); \ + \ } diff --git a/sw/airborne/math/pprz_algebra_int.h b/sw/airborne/math/pprz_algebra_int.h index 3df0026633..d8c75715b1 100644 --- a/sw/airborne/math/pprz_algebra_int.h +++ b/sw/airborne/math/pprz_algebra_int.h @@ -106,14 +106,14 @@ struct Int64Quat { #define INT32_RAD_OF_DEG(_deg) (int32_t)(((int64_t)(_deg) * 14964008)/857374503) #define INT32_DEG_OF_RAD(_rad) (int32_t)(((int64_t)(_rad) * 857374503)/14964008) -#define INT32_ANGLE_NORMALIZE(_a) { \ - while ((_a) > INT32_ANGLE_PI) (_a) -= INT32_ANGLE_2_PI; \ - while ((_a) < -INT32_ANGLE_PI) (_a) += INT32_ANGLE_2_PI; \ +#define INT32_ANGLE_NORMALIZE(_a) { \ + while ((_a) > INT32_ANGLE_PI) (_a) -= INT32_ANGLE_2_PI; \ + while ((_a) < -INT32_ANGLE_PI) (_a) += INT32_ANGLE_2_PI; \ } -#define INT32_COURSE_NORMALIZE(_a) { \ +#define INT32_COURSE_NORMALIZE(_a) { \ while ((_a) < 0) (_a) += INT32_ANGLE_2_PI; \ - while ((_a) >= INT32_ANGLE_2_PI) (_a) -= INT32_ANGLE_2_PI; \ + while ((_a) >= INT32_ANGLE_2_PI) (_a) -= INT32_ANGLE_2_PI; \ } @@ -213,9 +213,9 @@ struct Int64Vect3 { #define INT_VECT2_ASSIGN(_a, _x, _y) VECT2_ASSIGN(_a, _x, _y) -#define INT32_VECT2_NORM(n, v) { \ +#define INT32_VECT2_NORM(n, v) { \ int32_t n2 = (v).x*(v).x + (v).y*(v).y; \ - INT32_SQRT(n, n2); \ + INT32_SQRT(n, n2); \ } #define INT32_VECT2_RSHIFT(_o, _i, _r) { \ @@ -251,36 +251,36 @@ struct Int64Vect3 { #define INT32_VECT3_ADD(_a, _b) VECT3_ADD(_a, _b) -#define INT32_VECT3_SCALE_2(_a, _b, _num, _den) { \ - (_a).x = ((_b).x * (_num)) / (_den); \ - (_a).y = ((_b).y * (_num)) / (_den); \ - (_a).z = ((_b).z * (_num)) / (_den); \ +#define INT32_VECT3_SCALE_2(_a, _b, _num, _den) { \ + (_a).x = ((_b).x * (_num)) / (_den); \ + (_a).y = ((_b).y * (_num)) / (_den); \ + (_a).z = ((_b).z * (_num)) / (_den); \ } #define INT32_VECT3_SDIV(_a, _b, _s) VECT3_SDIV(_a, _b, _s) -#define INT32_VECT3_NORM(n, v) { \ +#define INT32_VECT3_NORM(n, v) { \ int32_t n2 = (v).x*(v).x + (v).y*(v).y + (v).z*(v).z; \ - INT32_SQRT(n, n2); \ + INT32_SQRT(n, n2); \ } #define INT32_VECT3_RSHIFT(_o, _i, _r) { \ - (_o).x = ((_i).x >> (_r)); \ - (_o).y = ((_i).y >> (_r)); \ - (_o).z = ((_i).z >> (_r)); \ + (_o).x = ((_i).x >> (_r)); \ + (_o).y = ((_i).y >> (_r)); \ + (_o).z = ((_i).z >> (_r)); \ } #define INT32_VECT3_LSHIFT(_o, _i, _l) { \ - (_o).x = ((_i).x << (_l)); \ - (_o).y = ((_i).y << (_l)); \ - (_o).z = ((_i).z << (_l)); \ + (_o).x = ((_i).x << (_l)); \ + (_o).y = ((_i).y << (_l)); \ + (_o).z = ((_i).z << (_l)); \ } -#define INT32_VECT3_CROSS_PRODUCT(_vo, _v1, _v2) { \ - (_vo).x = (_v1).y*(_v2).z - (_v1).z*(_v2).y; \ - (_vo).y = (_v1).z*(_v2).x - (_v1).x*(_v2).z; \ - (_vo).z = (_v1).x*(_v2).y - (_v1).y*(_v2).x; \ +#define INT32_VECT3_CROSS_PRODUCT(_vo, _v1, _v2) { \ + (_vo).x = (_v1).y*(_v2).z - (_v1).z*(_v2).y; \ + (_vo).y = (_v1).z*(_v2).x - (_v1).x*(_v2).z; \ + (_vo).z = (_v1).x*(_v2).y - (_v1).y*(_v2).x; \ } @@ -288,46 +288,46 @@ struct Int64Vect3 { /* * 3x3 Matrices */ -#define INT32_MAT33_ZERO(_m) { \ - MAT33_ELMT((_m), 0, 0) = 0; \ - MAT33_ELMT((_m), 0, 1) = 0; \ - MAT33_ELMT((_m), 0, 2) = 0; \ - MAT33_ELMT((_m), 1, 0) = 0; \ - MAT33_ELMT((_m), 1, 1) = 0; \ - MAT33_ELMT((_m), 1, 2) = 0; \ - MAT33_ELMT((_m), 2, 0) = 0; \ - MAT33_ELMT((_m), 2, 1) = 0; \ - MAT33_ELMT((_m), 2, 2) = 0; \ +#define INT32_MAT33_ZERO(_m) { \ + MAT33_ELMT((_m), 0, 0) = 0; \ + MAT33_ELMT((_m), 0, 1) = 0; \ + MAT33_ELMT((_m), 0, 2) = 0; \ + MAT33_ELMT((_m), 1, 0) = 0; \ + MAT33_ELMT((_m), 1, 1) = 0; \ + MAT33_ELMT((_m), 1, 2) = 0; \ + MAT33_ELMT((_m), 2, 0) = 0; \ + MAT33_ELMT((_m), 2, 1) = 0; \ + MAT33_ELMT((_m), 2, 2) = 0; \ } -#define INT32_MAT33_DIAG(_m, _d00, _d11, _d22) { \ - MAT33_ELMT((_m), 0, 0) = (_d00); \ - MAT33_ELMT((_m), 0, 1) = 0; \ - MAT33_ELMT((_m), 0, 2) = 0; \ - MAT33_ELMT((_m), 1, 0) = 0; \ - MAT33_ELMT((_m), 1, 1) = (_d11); \ - MAT33_ELMT((_m), 1, 2) = 0; \ - MAT33_ELMT((_m), 2, 0) = 0; \ - MAT33_ELMT((_m), 2, 1) = 0; \ - MAT33_ELMT((_m), 2, 2) = (_d22); \ +#define INT32_MAT33_DIAG(_m, _d00, _d11, _d22) { \ + MAT33_ELMT((_m), 0, 0) = (_d00); \ + MAT33_ELMT((_m), 0, 1) = 0; \ + MAT33_ELMT((_m), 0, 2) = 0; \ + MAT33_ELMT((_m), 1, 0) = 0; \ + MAT33_ELMT((_m), 1, 1) = (_d11); \ + MAT33_ELMT((_m), 1, 2) = 0; \ + MAT33_ELMT((_m), 2, 0) = 0; \ + MAT33_ELMT((_m), 2, 1) = 0; \ + MAT33_ELMT((_m), 2, 2) = (_d22); \ } -#define INT32_MAT33_VECT3_MUL(_o, _m, _v, _f) { \ - (_o).x = ((_m).m[0]*(_v).x + (_m).m[1]*(_v).y + (_m).m[2]*(_v).z)>>(_f); \ - (_o).y = ((_m).m[3]*(_v).x + (_m).m[4]*(_v).y + (_m).m[5]*(_v).z)>>(_f); \ - (_o).z = ((_m).m[6]*(_v).x + (_m).m[7]*(_v).y + (_m).m[8]*(_v).z)>>(_f); \ +#define INT32_MAT33_VECT3_MUL(_o, _m, _v, _f) { \ + (_o).x = ((_m).m[0]*(_v).x + (_m).m[1]*(_v).y + (_m).m[2]*(_v).z)>>(_f); \ + (_o).y = ((_m).m[3]*(_v).x + (_m).m[4]*(_v).y + (_m).m[5]*(_v).z)>>(_f); \ + (_o).z = ((_m).m[6]*(_v).x + (_m).m[7]*(_v).y + (_m).m[8]*(_v).z)>>(_f); \ } /* * Rotation matrices */ -#define INT32_RMAT_ZERO(_rm) \ +#define INT32_RMAT_ZERO(_rm) \ INT32_MAT33_DIAG(_rm, TRIG_BFP_OF_REAL( 1.), TRIG_BFP_OF_REAL( 1.), TRIG_BFP_OF_REAL( 1.)) /* _m_a2c = _m_a2b comp _m_b2c , aka _m_a2c = _m_b2c * _m_a2b */ -#define INT32_RMAT_COMP(_m_a2c, _m_a2b, _m_b2c) { \ +#define INT32_RMAT_COMP(_m_a2c, _m_a2b, _m_b2c) { \ (_m_a2c).m[0] = ((_m_b2c).m[0]*(_m_a2b).m[0] + (_m_b2c).m[1]*(_m_a2b).m[3] + (_m_b2c).m[2]*(_m_a2b).m[6])>>INT32_TRIG_FRAC; \ (_m_a2c).m[1] = ((_m_b2c).m[0]*(_m_a2b).m[1] + (_m_b2c).m[1]*(_m_a2b).m[4] + (_m_b2c).m[2]*(_m_a2b).m[7])>>INT32_TRIG_FRAC; \ (_m_a2c).m[2] = ((_m_b2c).m[0]*(_m_a2b).m[2] + (_m_b2c).m[1]*(_m_a2b).m[5] + (_m_b2c).m[2]*(_m_a2b).m[8])>>INT32_TRIG_FRAC; \ @@ -340,7 +340,7 @@ struct Int64Vect3 { } /* _m_a2b = _m_a2c comp_inv _m_b2c , aka _m_a2b = inv(_m_b2c) * _m_a2c */ -#define INT32_RMAT_COMP_INV(_m_a2b, _m_a2c, _m_b2c) { \ +#define INT32_RMAT_COMP_INV(_m_a2b, _m_a2c, _m_b2c) { \ (_m_a2b).m[0] = ((_m_b2c).m[0]*(_m_a2c).m[0] + (_m_b2c).m[3]*(_m_a2c).m[3] + (_m_b2c).m[6]*(_m_a2c).m[6])>>INT32_TRIG_FRAC; \ (_m_a2b).m[1] = ((_m_b2c).m[0]*(_m_a2c).m[1] + (_m_b2c).m[3]*(_m_a2c).m[4] + (_m_b2c).m[6]*(_m_a2c).m[7])>>INT32_TRIG_FRAC; \ (_m_a2b).m[2] = ((_m_b2c).m[0]*(_m_a2c).m[2] + (_m_b2c).m[3]*(_m_a2c).m[5] + (_m_b2c).m[6]*(_m_a2c).m[8])>>INT32_TRIG_FRAC; \ @@ -353,13 +353,13 @@ struct Int64Vect3 { } /* _vb = _m_a2b * _va */ -#define INT32_RMAT_VMULT(_vb, _m_a2b, _va) { \ +#define INT32_RMAT_VMULT(_vb, _m_a2b, _va) { \ (_vb).x = ( (_m_a2b).m[0]*(_va).x + (_m_a2b).m[1]*(_va).y + (_m_a2b).m[2]*(_va).z)>>INT32_TRIG_FRAC; \ (_vb).y = ( (_m_a2b).m[3]*(_va).x + (_m_a2b).m[4]*(_va).y + (_m_a2b).m[5]*(_va).z)>>INT32_TRIG_FRAC; \ (_vb).z = ( (_m_a2b).m[6]*(_va).x + (_m_a2b).m[7]*(_va).y + (_m_a2b).m[8]*(_va).z)>>INT32_TRIG_FRAC; \ } -#define INT32_RMAT_TRANSP_VMULT(_vb, _m_b2a, _va) { \ +#define INT32_RMAT_TRANSP_VMULT(_vb, _m_b2a, _va) { \ (_vb).x = ( (_m_b2a).m[0]*(_va).x + (_m_b2a).m[3]*(_va).y + (_m_b2a).m[6]*(_va).z)>>INT32_TRIG_FRAC; \ (_vb).y = ( (_m_b2a).m[1]*(_va).x + (_m_b2a).m[4]*(_va).y + (_m_b2a).m[7]*(_va).z)>>INT32_TRIG_FRAC; \ (_vb).z = ( (_m_b2a).m[2]*(_va).x + (_m_b2a).m[5]*(_va).y + (_m_b2a).m[8]*(_va).z)>>INT32_TRIG_FRAC; \ @@ -371,7 +371,7 @@ struct Int64Vect3 { (_vb).r = ( (_m_a2b).m[6]*(_va).p + (_m_a2b).m[7]*(_va).q + (_m_a2b).m[8]*(_va).r)>>INT32_TRIG_FRAC; \ } -#define INT32_RMAT_TRANSP_RATEMULT(_vb, _m_b2a, _va) { \ +#define INT32_RMAT_TRANSP_RATEMULT(_vb, _m_b2a, _va) { \ (_vb).p = ( (_m_b2a).m[0]*(_va).p + (_m_b2a).m[3]*(_va).q + (_m_b2a).m[6]*(_va).r)>>INT32_TRIG_FRAC; \ (_vb).q = ( (_m_b2a).m[1]*(_va).p + (_m_b2a).m[4]*(_va).q + (_m_b2a).m[7]*(_va).r)>>INT32_TRIG_FRAC; \ (_vb).r = ( (_m_b2a).m[2]*(_va).p + (_m_b2a).m[5]*(_va).q + (_m_b2a).m[8]*(_va).r)>>INT32_TRIG_FRAC; \ @@ -382,7 +382,7 @@ struct Int64Vect3 { * http://www.mathworks.com/access/helpdesk_r13/help/toolbox/aeroblks/quaternionstodirectioncosinematrix.html */ #ifdef ALGEBRA_INT_USE_SLOW_FUNCTIONS -#define INT32_RMAT_OF_QUAT(_rm, _q) { \ +#define INT32_RMAT_OF_QUAT(_rm, _q) { \ const int32_t qx2 = INT_MULT_RSHIFT((_q).qx,(_q).qx, INT32_QUAT_FRAC); \ const int32_t qy2 = INT_MULT_RSHIFT((_q).qy,(_q).qy, INT32_QUAT_FRAC); \ const int32_t qz2 = INT_MULT_RSHIFT((_q).qz,(_q).qz, INT32_QUAT_FRAC); \ @@ -392,50 +392,50 @@ struct Int64Vect3 { const int32_t qxqy = INT_MULT_RSHIFT((_q).qx,(_q).qy, INT32_QUAT_FRAC); \ const int32_t qxqz = INT_MULT_RSHIFT((_q).qx,(_q).qz, INT32_QUAT_FRAC); \ const int32_t qyqz = INT_MULT_RSHIFT((_q).qy,(_q).qz, INT32_QUAT_FRAC); \ - const int32_t one = TRIG_BFP_OF_REAL( 1); \ - const int32_t two = TRIG_BFP_OF_REAL( 2); \ - /* dcm00 = 1.0 - 2.*( qy2 + qz2 ); */ \ + const int32_t one = TRIG_BFP_OF_REAL( 1); \ + const int32_t two = TRIG_BFP_OF_REAL( 2); \ + /* dcm00 = 1.0 - 2.*( qy2 + qz2 ); */ \ (_rm).m[0] = one - INT_MULT_RSHIFT( two, (qy2+qz2), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm01 = 2.*( qxqy + qiqz ); */ \ + /* dcm01 = 2.*( qxqy + qiqz ); */ \ (_rm).m[1] = INT_MULT_RSHIFT( two, (qxqy+qiqz), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm02 = 2.*( qxqz - qiqy ); */ \ + /* dcm02 = 2.*( qxqz - qiqy ); */ \ (_rm).m[2] = INT_MULT_RSHIFT( two, (qxqz-qiqy), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm10 = 2.*( qxqy - qiqz ); */ \ + /* dcm10 = 2.*( qxqy - qiqz ); */ \ (_rm).m[3] = INT_MULT_RSHIFT( two, (qxqy-qiqz), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm11 = 1.0 - 2.*(qx2+qz2); */ \ + /* dcm11 = 1.0 - 2.*(qx2+qz2); */ \ (_rm).m[4] = one - INT_MULT_RSHIFT( two, (qx2+qz2), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm12 = 2.*( qyqz + qiqx ); */ \ + /* dcm12 = 2.*( qyqz + qiqx ); */ \ (_rm).m[5] = INT_MULT_RSHIFT( two, (qyqz+qiqx), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm20 = 2.*( qxqz + qiqy ); */ \ + /* dcm20 = 2.*( qxqz + qiqy ); */ \ (_rm).m[6] = INT_MULT_RSHIFT( two, (qxqz+qiqy), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm21 = 2.*( qyqz - qiqx ); */ \ + /* dcm21 = 2.*( qyqz - qiqx ); */ \ (_rm).m[7] = INT_MULT_RSHIFT( two, (qyqz-qiqx), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm22 = 1.0 - 2.*( qx2 + qy2 ); */ \ + /* dcm22 = 1.0 - 2.*( qx2 + qy2 ); */ \ (_rm).m[8] = one - INT_MULT_RSHIFT( two, (qx2+qy2), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ } #else - #define INT32_RMAT_OF_QUAT(_rm, _q) { \ - const int32_t _2qi2_m1 = INT_MULT_RSHIFT((_q).qi,(_q).qi, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1)-TRIG_BFP_OF_REAL( 1); \ - (_rm).m[0] = INT_MULT_RSHIFT((_q).qx,(_q).qx, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - (_rm).m[4] = INT_MULT_RSHIFT((_q).qy,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - (_rm).m[8] = INT_MULT_RSHIFT((_q).qz,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - \ - const int32_t _2qiqx = INT_MULT_RSHIFT((_q).qi,(_q).qx, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - const int32_t _2qiqy = INT_MULT_RSHIFT((_q).qi,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - const int32_t _2qiqz = INT_MULT_RSHIFT((_q).qi,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - (_rm).m[1] = INT_MULT_RSHIFT((_q).qx,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - (_rm).m[2] = INT_MULT_RSHIFT((_q).qx,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - (_rm).m[5] = INT_MULT_RSHIFT((_q).qy,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ - \ - (_rm).m[0] += _2qi2_m1; \ - (_rm).m[3] = (_rm).m[1]-_2qiqz; \ - (_rm).m[6] = (_rm).m[2]+_2qiqy; \ - (_rm).m[7] = (_rm).m[5]-_2qiqx; \ - (_rm).m[4] += _2qi2_m1; \ - (_rm).m[1] += _2qiqz; \ - (_rm).m[2] -= _2qiqy; \ - (_rm).m[5] += _2qiqx; \ - (_rm).m[8] += _2qi2_m1; \ + #define INT32_RMAT_OF_QUAT(_rm, _q) { \ + const int32_t _2qi2_m1 = INT_MULT_RSHIFT((_q).qi,(_q).qi, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1)-TRIG_BFP_OF_REAL( 1); \ + (_rm).m[0] = INT_MULT_RSHIFT((_q).qx,(_q).qx, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + (_rm).m[4] = INT_MULT_RSHIFT((_q).qy,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + (_rm).m[8] = INT_MULT_RSHIFT((_q).qz,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + \ + const int32_t _2qiqx = INT_MULT_RSHIFT((_q).qi,(_q).qx, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + const int32_t _2qiqy = INT_MULT_RSHIFT((_q).qi,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + const int32_t _2qiqz = INT_MULT_RSHIFT((_q).qi,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + (_rm).m[1] = INT_MULT_RSHIFT((_q).qx,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + (_rm).m[2] = INT_MULT_RSHIFT((_q).qx,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + (_rm).m[5] = INT_MULT_RSHIFT((_q).qy,(_q).qz, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ + \ + (_rm).m[0] += _2qi2_m1; \ + (_rm).m[3] = (_rm).m[1]-_2qiqz; \ + (_rm).m[6] = (_rm).m[2]+_2qiqy; \ + (_rm).m[7] = (_rm).m[5]-_2qiqx; \ + (_rm).m[4] += _2qi2_m1; \ + (_rm).m[1] += _2qiqz; \ + (_rm).m[2] -= _2qiqy; \ + (_rm).m[5] += _2qiqx; \ + (_rm).m[8] += _2qi2_m1; \ } #endif @@ -446,21 +446,21 @@ struct Int64Vect3 { #define INT32_RMAT_OF_EULERS(_rm, _e) INT32_RMAT_OF_EULERS_321(_rm, _e) -#define INT32_RMAT_OF_EULERS_321(_rm, _e) { \ - \ - int32_t sphi; \ - PPRZ_ITRIG_SIN(sphi, (_e).phi); \ - int32_t cphi; \ - PPRZ_ITRIG_COS(cphi, (_e).phi); \ - int32_t stheta; \ - PPRZ_ITRIG_SIN(stheta, (_e).theta); \ - int32_t ctheta; \ - PPRZ_ITRIG_COS(ctheta, (_e).theta); \ - int32_t spsi; \ - PPRZ_ITRIG_SIN(spsi, (_e).psi); \ - int32_t cpsi; \ - PPRZ_ITRIG_COS(cpsi, (_e).psi); \ - \ +#define INT32_RMAT_OF_EULERS_321(_rm, _e) { \ + \ + int32_t sphi; \ + PPRZ_ITRIG_SIN(sphi, (_e).phi); \ + int32_t cphi; \ + PPRZ_ITRIG_COS(cphi, (_e).phi); \ + int32_t stheta; \ + PPRZ_ITRIG_SIN(stheta, (_e).theta); \ + int32_t ctheta; \ + PPRZ_ITRIG_COS(ctheta, (_e).theta); \ + int32_t spsi; \ + PPRZ_ITRIG_SIN(spsi, (_e).psi); \ + int32_t cpsi; \ + PPRZ_ITRIG_COS(cpsi, (_e).psi); \ + \ int32_t ctheta_cpsi = INT_MULT_RSHIFT(ctheta, cpsi, INT32_TRIG_FRAC); \ int32_t ctheta_spsi = INT_MULT_RSHIFT(ctheta, spsi, INT32_TRIG_FRAC); \ int32_t cphi_spsi = INT_MULT_RSHIFT(cphi, spsi, INT32_TRIG_FRAC); \ @@ -471,41 +471,41 @@ struct Int64Vect3 { int32_t sphi_stheta = INT_MULT_RSHIFT(sphi, stheta, INT32_TRIG_FRAC); \ int32_t sphi_spsi = INT_MULT_RSHIFT(sphi, spsi, INT32_TRIG_FRAC); \ int32_t sphi_cpsi = INT_MULT_RSHIFT(sphi, cpsi, INT32_TRIG_FRAC); \ - \ + \ int32_t sphi_stheta_cpsi = INT_MULT_RSHIFT(sphi_stheta, cpsi, INT32_TRIG_FRAC); \ int32_t sphi_stheta_spsi = INT_MULT_RSHIFT(sphi_stheta, spsi, INT32_TRIG_FRAC); \ int32_t cphi_stheta_cpsi = INT_MULT_RSHIFT(cphi_stheta, cpsi, INT32_TRIG_FRAC); \ int32_t cphi_stheta_spsi = INT_MULT_RSHIFT(cphi_stheta, spsi, INT32_TRIG_FRAC); \ - \ - RMAT_ELMT(_rm, 0, 0) = ctheta_cpsi; \ - RMAT_ELMT(_rm, 0, 1) = ctheta_spsi; \ - RMAT_ELMT(_rm, 0, 2) = -stheta; \ - RMAT_ELMT(_rm, 1, 0) = sphi_stheta_cpsi - cphi_spsi; \ - RMAT_ELMT(_rm, 1, 1) = sphi_stheta_spsi + cphi_cpsi; \ - RMAT_ELMT(_rm, 1, 2) = sphi_ctheta; \ - RMAT_ELMT(_rm, 2, 0) = cphi_stheta_cpsi + sphi_spsi; \ - RMAT_ELMT(_rm, 2, 1) = cphi_stheta_spsi - sphi_cpsi; \ - RMAT_ELMT(_rm, 2, 2) = cphi_ctheta; \ - \ + \ + RMAT_ELMT(_rm, 0, 0) = ctheta_cpsi; \ + RMAT_ELMT(_rm, 0, 1) = ctheta_spsi; \ + RMAT_ELMT(_rm, 0, 2) = -stheta; \ + RMAT_ELMT(_rm, 1, 0) = sphi_stheta_cpsi - cphi_spsi; \ + RMAT_ELMT(_rm, 1, 1) = sphi_stheta_spsi + cphi_cpsi; \ + RMAT_ELMT(_rm, 1, 2) = sphi_ctheta; \ + RMAT_ELMT(_rm, 2, 0) = cphi_stheta_cpsi + sphi_spsi; \ + RMAT_ELMT(_rm, 2, 1) = cphi_stheta_spsi - sphi_cpsi; \ + RMAT_ELMT(_rm, 2, 2) = cphi_ctheta; \ + \ } -#define INT32_RMAT_OF_EULERS_312(_rm, _e) { \ - \ - int32_t sphi; \ - PPRZ_ITRIG_SIN(sphi, (_e).phi); \ - int32_t cphi; \ - PPRZ_ITRIG_COS(cphi, (_e).phi); \ - int32_t stheta; \ - PPRZ_ITRIG_SIN(stheta, (_e).theta); \ - int32_t ctheta; \ - PPRZ_ITRIG_COS(ctheta, (_e).theta); \ - int32_t spsi; \ - PPRZ_ITRIG_SIN(spsi, (_e).psi); \ - int32_t cpsi; \ - PPRZ_ITRIG_COS(cpsi, (_e).psi); \ - \ - \ +#define INT32_RMAT_OF_EULERS_312(_rm, _e) { \ + \ + int32_t sphi; \ + PPRZ_ITRIG_SIN(sphi, (_e).phi); \ + int32_t cphi; \ + PPRZ_ITRIG_COS(cphi, (_e).phi); \ + int32_t stheta; \ + PPRZ_ITRIG_SIN(stheta, (_e).theta); \ + int32_t ctheta; \ + PPRZ_ITRIG_COS(ctheta, (_e).theta); \ + int32_t spsi; \ + PPRZ_ITRIG_SIN(spsi, (_e).psi); \ + int32_t cpsi; \ + PPRZ_ITRIG_COS(cpsi, (_e).psi); \ + \ + \ int32_t stheta_spsi = INT_MULT_RSHIFT(stheta, spsi, INT32_TRIG_FRAC); \ int32_t stheta_cpsi = INT_MULT_RSHIFT(stheta, cpsi, INT32_TRIG_FRAC); \ int32_t ctheta_spsi = INT_MULT_RSHIFT(ctheta, spsi, INT32_TRIG_FRAC); \ @@ -516,22 +516,22 @@ struct Int64Vect3 { int32_t cphi_cpsi = INT_MULT_RSHIFT(cphi, cpsi, INT32_TRIG_FRAC); \ int32_t sphi_stheta = INT_MULT_RSHIFT(sphi, stheta, INT32_TRIG_FRAC); \ int32_t sphi_ctheta = INT_MULT_RSHIFT(sphi, ctheta, INT32_TRIG_FRAC); \ - \ + \ int32_t sphi_stheta_spsi = INT_MULT_RSHIFT(sphi_stheta, spsi, INT32_TRIG_FRAC); \ int32_t sphi_stheta_cpsi = INT_MULT_RSHIFT(sphi_stheta, cpsi, INT32_TRIG_FRAC); \ int32_t sphi_ctheta_spsi = INT_MULT_RSHIFT(sphi_ctheta, spsi, INT32_TRIG_FRAC); \ int32_t sphi_ctheta_cpsi = INT_MULT_RSHIFT(sphi_ctheta, cpsi, INT32_TRIG_FRAC); \ - \ - RMAT_ELMT(_rm, 0, 0) = ctheta_cpsi - sphi_stheta_spsi; \ - RMAT_ELMT(_rm, 0, 1) = ctheta_spsi + sphi_stheta_cpsi; \ - RMAT_ELMT(_rm, 0, 2) = -cphi_stheta; \ - RMAT_ELMT(_rm, 1, 0) = -cphi_spsi; \ - RMAT_ELMT(_rm, 1, 1) = cphi_cpsi; \ - RMAT_ELMT(_rm, 1, 2) = sphi; \ - RMAT_ELMT(_rm, 2, 0) = stheta_cpsi + sphi_ctheta_spsi; \ - RMAT_ELMT(_rm, 2, 1) = stheta_spsi - sphi_ctheta_cpsi; \ - RMAT_ELMT(_rm, 2, 2) = cphi_ctheta; \ - \ + \ + RMAT_ELMT(_rm, 0, 0) = ctheta_cpsi - sphi_stheta_spsi; \ + RMAT_ELMT(_rm, 0, 1) = ctheta_spsi + sphi_stheta_cpsi; \ + RMAT_ELMT(_rm, 0, 2) = -cphi_stheta; \ + RMAT_ELMT(_rm, 1, 0) = -cphi_spsi; \ + RMAT_ELMT(_rm, 1, 1) = cphi_cpsi; \ + RMAT_ELMT(_rm, 1, 2) = sphi; \ + RMAT_ELMT(_rm, 2, 0) = stheta_cpsi + sphi_ctheta_spsi; \ + RMAT_ELMT(_rm, 2, 1) = stheta_spsi - sphi_ctheta_cpsi; \ + RMAT_ELMT(_rm, 2, 2) = cphi_ctheta; \ + \ } @@ -539,36 +539,36 @@ struct Int64Vect3 { * Quaternions */ -#define INT32_QUAT_ZERO(_q) { \ - (_q).qi = QUAT1_BFP_OF_REAL(1); \ - (_q).qx = 0; \ - (_q).qy = 0; \ - (_q).qz = 0; \ +#define INT32_QUAT_ZERO(_q) { \ + (_q).qi = QUAT1_BFP_OF_REAL(1); \ + (_q).qx = 0; \ + (_q).qy = 0; \ + (_q).qz = 0; \ } #define INT32_QUAT_INVERT(_qo, _qi) QUAT_INVERT(_qo, _qi) -#define INT32_QUAT_NORM(n, q) { \ +#define INT32_QUAT_NORM(n, q) { \ int32_t n2 = (q).qi*(q).qi + (q).qx*(q).qx + (q).qy*(q).qy + (q).qz*(q).qz; \ - INT32_SQRT(n, n2); \ + INT32_SQRT(n, n2); \ } -#define INT32_QUAT_WRAP_SHORTEST(q) { \ - if ((q).qi < 0) \ - QUAT_EXPLEMENTARY(q,q); \ +#define INT32_QUAT_WRAP_SHORTEST(q) { \ + if ((q).qi < 0) \ + QUAT_EXPLEMENTARY(q,q); \ } -#define INT32_QUAT_NORMALIZE(q) { \ - int32_t n; \ - INT32_QUAT_NORM(n, q); \ - (q).qi = (q).qi * QUAT1_BFP_OF_REAL(1) / n; \ - (q).qx = (q).qx * QUAT1_BFP_OF_REAL(1) / n; \ - (q).qy = (q).qy * QUAT1_BFP_OF_REAL(1) / n; \ - (q).qz = (q).qz * QUAT1_BFP_OF_REAL(1) / n; \ +#define INT32_QUAT_NORMALIZE(q) { \ + int32_t n; \ + INT32_QUAT_NORM(n, q); \ + (q).qi = (q).qi * QUAT1_BFP_OF_REAL(1) / n; \ + (q).qx = (q).qx * QUAT1_BFP_OF_REAL(1) / n; \ + (q).qy = (q).qy * QUAT1_BFP_OF_REAL(1) / n; \ + (q).qz = (q).qz * QUAT1_BFP_OF_REAL(1) / n; \ } /* _a2c = _a2b comp _b2c , aka _a2c = _b2c * _a2b */ -#define INT32_QUAT_COMP(_a2c, _a2b, _b2c) { \ +#define INT32_QUAT_COMP(_a2c, _a2b, _b2c) { \ (_a2c).qi = ((_a2b).qi*(_b2c).qi - (_a2b).qx*(_b2c).qx - (_a2b).qy*(_b2c).qy - (_a2b).qz*(_b2c).qz)>>INT32_QUAT_FRAC; \ (_a2c).qx = ((_a2b).qi*(_b2c).qx + (_a2b).qx*(_b2c).qi + (_a2b).qy*(_b2c).qz - (_a2b).qz*(_b2c).qy)>>INT32_QUAT_FRAC; \ (_a2c).qy = ((_a2b).qi*(_b2c).qy - (_a2b).qx*(_b2c).qz + (_a2b).qy*(_b2c).qi + (_a2b).qz*(_b2c).qx)>>INT32_QUAT_FRAC; \ @@ -576,7 +576,7 @@ struct Int64Vect3 { } /* _a2b = _a2b comp_inv _b2c , aka _a2b = inv(_b2c) * _a2c */ -#define INT32_QUAT_COMP_INV(_a2b, _a2c, _b2c) { \ +#define INT32_QUAT_COMP_INV(_a2b, _a2c, _b2c) { \ (_a2b).qi = ( (_a2c).qi*(_b2c).qi + (_a2c).qx*(_b2c).qx + (_a2c).qy*(_b2c).qy + (_a2c).qz*(_b2c).qz)>>INT32_QUAT_FRAC; \ (_a2b).qx = (-(_a2c).qi*(_b2c).qx + (_a2c).qx*(_b2c).qi - (_a2c).qy*(_b2c).qz + (_a2c).qz*(_b2c).qy)>>INT32_QUAT_FRAC; \ (_a2b).qy = (-(_a2c).qi*(_b2c).qy + (_a2c).qx*(_b2c).qz + (_a2c).qy*(_b2c).qi - (_a2c).qz*(_b2c).qx)>>INT32_QUAT_FRAC; \ @@ -584,7 +584,7 @@ struct Int64Vect3 { } /* _b2c = _a2b inv_comp _a2c , aka _b2c = _a2c * inv(_a2b) */ -#define INT32_QUAT_INV_COMP(_b2c, _a2b, _a2c) { \ +#define INT32_QUAT_INV_COMP(_b2c, _a2b, _a2c) { \ (_b2c).qi = ((_a2b).qi*(_a2c).qi + (_a2b).qx*(_a2c).qx + (_a2b).qy*(_a2c).qy + (_a2b).qz*(_a2c).qz)>>INT32_QUAT_FRAC; \ (_b2c).qx = ((_a2b).qi*(_a2c).qx - (_a2b).qx*(_a2c).qi - (_a2b).qy*(_a2c).qz + (_a2b).qz*(_a2c).qy)>>INT32_QUAT_FRAC; \ (_b2c).qy = ((_a2b).qi*(_a2c).qy + (_a2b).qx*(_a2c).qz - (_a2b).qy*(_a2c).qi - (_a2b).qz*(_a2c).qx)>>INT32_QUAT_FRAC; \ @@ -599,16 +599,16 @@ struct Int64Vect3 { } /* _a2c = _a2b comp _b2c , aka _a2c = _a2b * _b2c */ -#define INT32_QUAT_COMP_NORM_SHORTEST(_a2c, _a2b, _b2c) { \ - INT32_QUAT_COMP(_a2c, _a2b, _b2c); \ - INT32_QUAT_WRAP_SHORTEST(_a2c); \ - INT32_QUAT_NORMALIZE(_a2c); \ +#define INT32_QUAT_COMP_NORM_SHORTEST(_a2c, _a2b, _b2c) { \ + INT32_QUAT_COMP(_a2c, _a2b, _b2c); \ + INT32_QUAT_WRAP_SHORTEST(_a2c); \ + INT32_QUAT_NORMALIZE(_a2c); \ } /* _qd = -0.5*omega(_r) * _q */ // mult with 0.5 is done by shifting one more bit to the right -#define INT32_QUAT_DERIVATIVE(_qd, _r, _q) { \ +#define INT32_QUAT_DERIVATIVE(_qd, _r, _q) { \ (_qd).qi = (-( (_r).p*(_q).qx + (_r).q*(_q).qy + (_r).r*(_q).qz))>>(INT32_RATE_FRAC+1); \ (_qd).qx = (-(-(_r).p*(_q).qi - (_r).r*(_q).qy + (_r).q*(_q).qz))>>(INT32_RATE_FRAC+1); \ (_qd).qy = (-(-(_r).q*(_q).qi + (_r).r*(_q).qx - (_r).p*(_q).qz))>>(INT32_RATE_FRAC+1); \ @@ -642,42 +642,42 @@ struct Int64Vect3 { #ifdef ALGEBRA_INT_USE_SLOW_FUNCTIONS -#define INT32_QUAT_VMULT(v_out, q, v_in) { \ - const int32_t qi2 = ((q).qi*(q).qi)>>INT32_QUAT_FRAC; \ - const int32_t qx2 = ((q).qx*(q).qx)>>INT32_QUAT_FRAC; \ - const int32_t qy2 = ((q).qy*(q).qy)>>INT32_QUAT_FRAC; \ - const int32_t qz2 = ((q).qz*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t qiqx = ((q).qi*(q).qx)>>INT32_QUAT_FRAC; \ - const int32_t qiqy = ((q).qi*(q).qy)>>INT32_QUAT_FRAC; \ - const int32_t qiqz = ((q).qi*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t qxqy = ((q).qx*(q).qy)>>INT32_QUAT_FRAC; \ - const int32_t qxqz = ((q).qx*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t qyqz = ((q).qy*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t m00 = qi2 + qx2 - qy2 - qz2; \ - const int32_t m01 = 2 * (qxqy + qiqz ); \ - const int32_t m02 = 2 * (qxqz - qiqy ); \ - const int32_t m10 = 2 * (qxqy - qiqz ); \ - const int32_t m11 = qi2 - qx2 + qy2 - qz2; \ - const int32_t m12 = 2 * (qyqz + qiqx ); \ - const int32_t m20 = 2 * (qxqz + qiqy ); \ - const int32_t m21 = 2 * (qyqz - qiqx ); \ - const int32_t m22 = qi2 - qx2 - qy2 + qz2; \ +#define INT32_QUAT_VMULT(v_out, q, v_in) { \ + const int32_t qi2 = ((q).qi*(q).qi)>>INT32_QUAT_FRAC; \ + const int32_t qx2 = ((q).qx*(q).qx)>>INT32_QUAT_FRAC; \ + const int32_t qy2 = ((q).qy*(q).qy)>>INT32_QUAT_FRAC; \ + const int32_t qz2 = ((q).qz*(q).qz)>>INT32_QUAT_FRAC; \ + const int32_t qiqx = ((q).qi*(q).qx)>>INT32_QUAT_FRAC; \ + const int32_t qiqy = ((q).qi*(q).qy)>>INT32_QUAT_FRAC; \ + const int32_t qiqz = ((q).qi*(q).qz)>>INT32_QUAT_FRAC; \ + const int32_t qxqy = ((q).qx*(q).qy)>>INT32_QUAT_FRAC; \ + const int32_t qxqz = ((q).qx*(q).qz)>>INT32_QUAT_FRAC; \ + const int32_t qyqz = ((q).qy*(q).qz)>>INT32_QUAT_FRAC; \ + const int32_t m00 = qi2 + qx2 - qy2 - qz2; \ + const int32_t m01 = 2 * (qxqy + qiqz ); \ + const int32_t m02 = 2 * (qxqz - qiqy ); \ + const int32_t m10 = 2 * (qxqy - qiqz ); \ + const int32_t m11 = qi2 - qx2 + qy2 - qz2; \ + const int32_t m12 = 2 * (qyqz + qiqx ); \ + const int32_t m20 = 2 * (qxqz + qiqy ); \ + const int32_t m21 = 2 * (qyqz - qiqx ); \ + const int32_t m22 = qi2 - qx2 - qy2 + qz2; \ (v_out).x = (m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z)>>INT32_QUAT_FRAC; \ (v_out).y = (m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z)>>INT32_QUAT_FRAC; \ (v_out).z = (m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z)>>INT32_QUAT_FRAC; \ } #else -#define INT32_QUAT_VMULT(v_out, q, v_in) { \ - const int32_t _2qi2_m1 = (((q).qi*(q).qi)>>(INT32_QUAT_FRAC-1)) - QUAT1_BFP_OF_REAL( 1); \ - const int32_t _2qx2 = ((q).qx*(q).qx)>>(INT32_QUAT_FRAC-1); \ - const int32_t _2qy2 = ((q).qy*(q).qy)>>(INT32_QUAT_FRAC-1); \ - const int32_t _2qz2 = ((q).qz*(q).qz)>>(INT32_QUAT_FRAC-1); \ - const int32_t _2qiqx = ((q).qi*(q).qx)>>(INT32_QUAT_FRAC-1); \ - const int32_t _2qiqy = ((q).qi*(q).qy)>>(INT32_QUAT_FRAC-1); \ - const int32_t _2qiqz = ((q).qi*(q).qz)>>(INT32_QUAT_FRAC-1); \ - const int32_t m01 = (((q).qx*(q).qy)>>(INT32_QUAT_FRAC-1)) + _2qiqz; \ - const int32_t m02 = (((q).qx*(q).qz)>>(INT32_QUAT_FRAC-1)) - _2qiqy; \ - const int32_t m12 = (((q).qy*(q).qz)>>(INT32_QUAT_FRAC-1)) + _2qiqx; \ +#define INT32_QUAT_VMULT(v_out, q, v_in) { \ + const int32_t _2qi2_m1 = (((q).qi*(q).qi)>>(INT32_QUAT_FRAC-1)) - QUAT1_BFP_OF_REAL( 1); \ + const int32_t _2qx2 = ((q).qx*(q).qx)>>(INT32_QUAT_FRAC-1); \ + const int32_t _2qy2 = ((q).qy*(q).qy)>>(INT32_QUAT_FRAC-1); \ + const int32_t _2qz2 = ((q).qz*(q).qz)>>(INT32_QUAT_FRAC-1); \ + const int32_t _2qiqx = ((q).qi*(q).qx)>>(INT32_QUAT_FRAC-1); \ + const int32_t _2qiqy = ((q).qi*(q).qy)>>(INT32_QUAT_FRAC-1); \ + const int32_t _2qiqz = ((q).qi*(q).qz)>>(INT32_QUAT_FRAC-1); \ + const int32_t m01 = (((q).qx*(q).qy)>>(INT32_QUAT_FRAC-1)) + _2qiqz; \ + const int32_t m02 = (((q).qx*(q).qz)>>(INT32_QUAT_FRAC-1)) - _2qiqy; \ + const int32_t m12 = (((q).qy*(q).qz)>>(INT32_QUAT_FRAC-1)) + _2qiqx; \ (v_out).x = (_2qi2_m1*(v_in).x + _2qx2 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z)>>INT32_QUAT_FRAC; \ (v_out).y = (_2qi2_m1*(v_in).y + m01 * (v_in).x -2*_2qiqz*(v_in).x + _2qy2 * (v_in).y + m12 * (v_in).z)>>INT32_QUAT_FRAC; \ (v_out).z = (_2qi2_m1*(v_in).z + m02 * (v_in).x +2*_2qiqy*(v_in).x+ m12 * (v_in).y -2*_2qiqx*(v_in).y+ _2qz2 * (v_in).z)>>INT32_QUAT_FRAC; \ @@ -689,124 +689,124 @@ struct Int64Vect3 { /* * http://www.mathworks.com/access/helpdesk_r13/help/toolbox/aeroblks/euleranglestoquaternions.html */ -#define INT32_QUAT_OF_EULERS(_q, _e) { \ - const int32_t phi2 = (_e).phi / 2; \ - const int32_t theta2 = (_e).theta / 2; \ - const int32_t psi2 = (_e).psi / 2; \ - \ - int32_t s_phi2; \ - PPRZ_ITRIG_SIN(s_phi2, phi2); \ - int32_t c_phi2; \ - PPRZ_ITRIG_COS(c_phi2, phi2); \ - int32_t s_theta2; \ - PPRZ_ITRIG_SIN(s_theta2, theta2); \ - int32_t c_theta2; \ - PPRZ_ITRIG_COS(c_theta2, theta2); \ - int32_t s_psi2; \ - PPRZ_ITRIG_SIN(s_psi2, psi2); \ - int32_t c_psi2; \ - PPRZ_ITRIG_COS(c_psi2, psi2); \ - \ +#define INT32_QUAT_OF_EULERS(_q, _e) { \ + const int32_t phi2 = (_e).phi / 2; \ + const int32_t theta2 = (_e).theta / 2; \ + const int32_t psi2 = (_e).psi / 2; \ + \ + int32_t s_phi2; \ + PPRZ_ITRIG_SIN(s_phi2, phi2); \ + int32_t c_phi2; \ + PPRZ_ITRIG_COS(c_phi2, phi2); \ + int32_t s_theta2; \ + PPRZ_ITRIG_SIN(s_theta2, theta2); \ + int32_t c_theta2; \ + PPRZ_ITRIG_COS(c_theta2, theta2); \ + int32_t s_psi2; \ + PPRZ_ITRIG_SIN(s_psi2, psi2); \ + int32_t c_psi2; \ + PPRZ_ITRIG_COS(c_psi2, psi2); \ + \ int32_t c_th_c_ps = INT_MULT_RSHIFT(c_theta2, c_psi2, INT32_TRIG_FRAC); \ int32_t c_th_s_ps = INT_MULT_RSHIFT(c_theta2, s_psi2, INT32_TRIG_FRAC); \ int32_t s_th_s_ps = INT_MULT_RSHIFT(s_theta2, s_psi2, INT32_TRIG_FRAC); \ int32_t s_th_c_ps = INT_MULT_RSHIFT(s_theta2, c_psi2, INT32_TRIG_FRAC); \ - \ + \ (_q).qi = INT_MULT_RSHIFT( c_phi2, c_th_c_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC) + \ - INT_MULT_RSHIFT( s_phi2, s_th_s_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ + INT_MULT_RSHIFT( s_phi2, s_th_s_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ (_q).qx = INT_MULT_RSHIFT(-c_phi2, s_th_s_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC) + \ - INT_MULT_RSHIFT( s_phi2, c_th_c_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ + INT_MULT_RSHIFT( s_phi2, c_th_c_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ (_q).qy = INT_MULT_RSHIFT( c_phi2, s_th_c_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC) + \ - INT_MULT_RSHIFT( s_phi2, c_th_s_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ + INT_MULT_RSHIFT( s_phi2, c_th_s_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ (_q).qz = INT_MULT_RSHIFT( c_phi2, c_th_s_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC) + \ - INT_MULT_RSHIFT(-s_phi2, s_th_c_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ + INT_MULT_RSHIFT(-s_phi2, s_th_c_ps, INT32_TRIG_FRAC + INT32_TRIG_FRAC - INT32_QUAT_FRAC); \ } -#define INT32_QUAT_OF_AXIS_ANGLE(_q, _uv, _an) { \ - int32_t san2; \ - PPRZ_ITRIG_SIN(san2, (_an/2)); \ - int32_t can2; \ - PPRZ_ITRIG_COS(can2, (_an/2)); \ - _q.qi = can2; \ - _q.qx = san2 * _uv.x; \ - _q.qy = san2 * _uv.y; \ - _q.qz = san2 * _uv.z; \ +#define INT32_QUAT_OF_AXIS_ANGLE(_q, _uv, _an) { \ + int32_t san2; \ + PPRZ_ITRIG_SIN(san2, (_an/2)); \ + int32_t can2; \ + PPRZ_ITRIG_COS(can2, (_an/2)); \ + _q.qi = can2; \ + _q.qx = san2 * _uv.x; \ + _q.qy = san2 * _uv.y; \ + _q.qz = san2 * _uv.z; \ } -#define INT32_QUAT_OF_RMAT(_q, _r) { \ - const int32_t tr = RMAT_TRACE(_r); \ - if (tr > 0) { \ - const int32_t two_qi_two = TRIG_BFP_OF_REAL(1.) + tr; \ - int32_t two_qi; \ - INT32_SQRT(two_qi, (two_qi_two< RMAT_ELMT(_r, 1, 1) && \ - RMAT_ELMT(_r, 0, 0) > RMAT_ELMT(_r, 2, 2)) { \ - const int32_t two_qx_two = RMAT_ELMT(_r, 0, 0) - RMAT_ELMT(_r, 1, 1) \ - - RMAT_ELMT(_r, 2, 2) + TRIG_BFP_OF_REAL(1.); \ - int32_t two_qx; \ - INT32_SQRT(two_qx, (two_qx_two< RMAT_ELMT(_r, 2, 2)) { \ - const int32_t two_qy_two = RMAT_ELMT(_r, 1, 1) - RMAT_ELMT(_r, 0, 0) \ - - RMAT_ELMT(_r, 2, 2) + TRIG_BFP_OF_REAL(1.); \ - int32_t two_qy; \ - INT32_SQRT(two_qy, (two_qy_two< 0) { \ + const int32_t two_qi_two = TRIG_BFP_OF_REAL(1.) + tr; \ + int32_t two_qi; \ + INT32_SQRT(two_qi, (two_qi_two< RMAT_ELMT(_r, 1, 1) && \ + RMAT_ELMT(_r, 0, 0) > RMAT_ELMT(_r, 2, 2)) { \ + const int32_t two_qx_two = RMAT_ELMT(_r, 0, 0) - RMAT_ELMT(_r, 1, 1) \ + - RMAT_ELMT(_r, 2, 2) + TRIG_BFP_OF_REAL(1.); \ + int32_t two_qx; \ + INT32_SQRT(two_qx, (two_qx_two< RMAT_ELMT(_r, 2, 2)) { \ + const int32_t two_qy_two = RMAT_ELMT(_r, 1, 1) - RMAT_ELMT(_r, 0, 0) \ + - RMAT_ELMT(_r, 2, 2) + TRIG_BFP_OF_REAL(1.); \ + int32_t two_qy; \ + INT32_SQRT(two_qy, (two_qy_two<> (_r)); \ - (_o).q = ((_i).q >> (_r)); \ - (_o).r = ((_i).r >> (_r)); \ +#define INT_RATES_RSHIFT(_o, _i, _r) { \ + (_o).p = ((_i).p >> (_r)); \ + (_o).q = ((_i).q >> (_r)); \ + (_o).r = ((_i).r >> (_r)); \ } -#define INT_RATES_LSHIFT(_o, _i, _r) { \ - (_o).p = ((_i).p << (_r)); \ - (_o).q = ((_i).q << (_r)); \ - (_o).r = ((_i).r << (_r)); \ +#define INT_RATES_LSHIFT(_o, _i, _r) { \ + (_o).p = ((_i).p << (_r)); \ + (_o).q = ((_i).q << (_r)); \ + (_o).r = ((_i).r << (_r)); \ } -#define INT32_RATES_OF_EULERS_DOT_321(_r, _e, _ed) { \ - \ - int32_t sphi; \ - PPRZ_ITRIG_SIN(sphi, (_e).phi); \ - int32_t cphi; \ - PPRZ_ITRIG_COS(cphi, (_e).phi); \ - int32_t stheta; \ - PPRZ_ITRIG_SIN(stheta, (_e).theta); \ - int32_t ctheta; \ - PPRZ_ITRIG_COS(ctheta, (_e).theta); \ - \ +#define INT32_RATES_OF_EULERS_DOT_321(_r, _e, _ed) { \ + \ + int32_t sphi; \ + PPRZ_ITRIG_SIN(sphi, (_e).phi); \ + int32_t cphi; \ + PPRZ_ITRIG_COS(cphi, (_e).phi); \ + int32_t stheta; \ + PPRZ_ITRIG_SIN(stheta, (_e).theta); \ + int32_t ctheta; \ + PPRZ_ITRIG_COS(ctheta, (_e).theta); \ + \ int32_t cphi_ctheta = INT_MULT_RSHIFT(cphi, ctheta, INT32_TRIG_FRAC); \ int32_t sphi_ctheta = INT_MULT_RSHIFT(sphi, ctheta, INT32_TRIG_FRAC); \ - \ + \ (_r).p = - INT_MULT_RSHIFT(stheta, (_ed).psi, INT32_TRIG_FRAC) + (_ed).phi; \ (_r).q = INT_MULT_RSHIFT(sphi_ctheta, (_ed).psi, INT32_TRIG_FRAC) + INT_MULT_RSHIFT(cphi, (_ed).theta, INT32_TRIG_FRAC); \ (_r).r = INT_MULT_RSHIFT(cphi_ctheta, (_ed).psi, INT32_TRIG_FRAC) - INT_MULT_RSHIFT(sphi, (_ed).theta, INT32_TRIG_FRAC); \ - \ + \ } #define INT32_RATES_OF_EULERS_DOT(_r, _e, _ed) INT32_RATES_OF_EULERS_DOT_321(_r, _e, _ed) -#define INT32_EULERS_DOT_321_OF_RATES(_ed, _e, _r) { \ - \ - int32_t sphi; \ - PPRZ_ITRIG_SIN(sphi, (_e).phi); \ - int32_t cphi; \ - PPRZ_ITRIG_COS(cphi, (_e).phi); \ - int32_t stheta; \ - PPRZ_ITRIG_SIN(stheta, (_e).theta); \ - int64_t ctheta; \ - PPRZ_ITRIG_COS(ctheta, (_e).theta); \ - \ - if (ctheta != 0) { \ +#define INT32_EULERS_DOT_321_OF_RATES(_ed, _e, _r) { \ + \ + int32_t sphi; \ + PPRZ_ITRIG_SIN(sphi, (_e).phi); \ + int32_t cphi; \ + PPRZ_ITRIG_COS(cphi, (_e).phi); \ + int32_t stheta; \ + PPRZ_ITRIG_SIN(stheta, (_e).theta); \ + int64_t ctheta; \ + PPRZ_ITRIG_COS(ctheta, (_e).theta); \ + \ + if (ctheta != 0) { \ int64_t cphi_stheta = INT_MULT_RSHIFT(cphi, stheta, INT32_TRIG_FRAC); \ int64_t sphi_stheta = INT_MULT_RSHIFT(sphi, stheta, INT32_TRIG_FRAC); \ - \ + \ (_ed).phi = (_r).p + (int32_t)((sphi_stheta * (int64_t)(_r).q) / ctheta) + (int32_t)((cphi_stheta * (int64_t)(_r).r) / ctheta); \ (_ed).theta = INT_MULT_RSHIFT(cphi, (_r).q, INT32_TRIG_FRAC) - INT_MULT_RSHIFT(sphi, (_r).r, INT32_TRIG_FRAC); \ (_ed).psi = (int32_t)(((int64_t)sphi * (int64_t)(_r).q) / ctheta) + (int32_t)(((int64_t)cphi * (int64_t)(_r).r) / ctheta); \ - } \ - /* FIXME: What do you wanna do when you hit the singularity ? */ \ - /* probably not return an uninitialized variable, or ? */ \ - else { \ - INT_EULERS_ZERO(_ed); \ - } \ + } \ + /* FIXME: What do you wanna do when you hit the singularity ? */ \ + /* probably not return an uninitialized variable, or ? */ \ + else { \ + INT_EULERS_ZERO(_ed); \ + } \ } #define INT32_EULERS_DOT_OF_RATES(_ed, _e, _r) INT32_EULERS_DOT_321_OF_RATES(_ed, _e, _r) @@ -977,23 +977,23 @@ struct Int64Vect3 { * */ #define INT32_SQRT_MAX_ITER 40 -#define INT32_SQRT(_out,_in) { \ +#define INT32_SQRT(_out,_in) { \ if ((_in) == 0) \ (_out) = 0; \ - else { \ - uint32_t s1, s2; \ - uint8_t iter = 0; \ - s2 = _in; \ - do { \ - s1 = s2; \ - s2 = (_in) / s1; \ - s2 += s1; \ - s2 /= 2; \ - iter++; \ - } \ - while( ( (s1-s2) > 1) && (iter < INT32_SQRT_MAX_ITER)); \ - (_out) = s2; \ - } \ + else { \ + uint32_t s1, s2; \ + uint8_t iter = 0; \ + s2 = _in; \ + do { \ + s1 = s2; \ + s2 = (_in) / s1; \ + s2 += s1; \ + s2 /= 2; \ + iter++; \ + } \ + while( ( (s1-s2) > 1) && (iter < INT32_SQRT_MAX_ITER)); \ + (_out) = s2; \ + } \ } @@ -1002,41 +1002,41 @@ struct Int64Vect3 { #define R_FRAC 14 -#define INT32_ATAN2(_a, _y, _x) { \ - const int32_t c1 = INT32_ANGLE_PI_4; \ - const int32_t c2 = 3 * INT32_ANGLE_PI_4; \ - const int32_t abs_y = abs(_y) + 1; \ - int32_t r; \ +#define INT32_ATAN2(_a, _y, _x) { \ + const int32_t c1 = INT32_ANGLE_PI_4; \ + const int32_t c2 = 3 * INT32_ANGLE_PI_4; \ + const int32_t abs_y = abs(_y) + 1; \ + int32_t r; \ if ( (_x) >= 0) { \ r = (((_x)-abs_y)<>R_FRAC); \ - } \ - else { \ + } \ + else { \ r = (((_x)+abs_y)<>R_FRAC); \ - } \ - if ((_y)<0) \ + (_a) = c2 - ((c1 * r)>>R_FRAC); \ + } \ + if ((_y)<0) \ (_a) = -(_a); \ } -#define INT32_ATAN2_2(_a, _y, _x) { \ - const int32_t c1 = INT32_ANGLE_PI_4; \ - const int32_t c2 = 3 * INT32_ANGLE_PI_4; \ - const int32_t abs_y = abs(_y) + 1; \ - int32_t r; \ - if ( (_x) >= 0) { \ - r = (((_x)-abs_y)<>R_FRAC; \ +#define INT32_ATAN2_2(_a, _y, _x) { \ + const int32_t c1 = INT32_ANGLE_PI_4; \ + const int32_t c2 = 3 * INT32_ANGLE_PI_4; \ + const int32_t abs_y = abs(_y) + 1; \ + int32_t r; \ + if ( (_x) >= 0) { \ + r = (((_x)-abs_y)<>R_FRAC; \ int32_t tmp1 = ((r2 * (int32_t)ANGLE_BFP_OF_REAL(0.1963))>>INT32_ANGLE_FRAC) - ANGLE_BFP_OF_REAL(0.9817); \ - (_a) = ((tmp1 * r)>>R_FRAC) + c1; \ - } \ - else { \ - r = (((_x)+abs_y)<>R_FRAC); \ - } \ - if ((_y)<0) \ - (_a) = -(_a); \ + (_a) = ((tmp1 * r)>>R_FRAC) + c1; \ + } \ + else { \ + r = (((_x)+abs_y)<>R_FRAC); \ + } \ + if ((_y)<0) \ + (_a) = -(_a); \ } From fcc3b270ed164cb37b1db9e3cb3d8c2a084cfd82 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 13 Aug 2013 14:14:41 +0200 Subject: [PATCH 075/309] [rotorcraft] v_adapt: config improvements and refactor - GUIDANCE_V_ADAPT_INITIAL_HOVER_THROTTLE settable in % with default of 0.3 - GUIDANCE_V_ADAPT_THROTTLE_ENABLED: - TRUE by default if GUIDANCE_V_NOMINAL_HOVER_THROTTLE was not defined - FALSE by default if only GUIDANCE_V_NOMINAL_HOVER_THROTTLE was set in airframe file (for backwards compatibily) - switching between nominal_trottle and the adaptive estimate during operation via settings --- conf/firmwares/rotorcraft.makefile | 1 + .../subsystems/rotorcraft/fdm_jsbsim.makefile | 1 + conf/settings/control/rotorcraft_guidance.xml | 3 +- .../rotorcraft/guidance/guidance_v.c | 51 +++++--- .../rotorcraft/guidance/guidance_v.h | 14 ++- .../{guidance_v_adpt.h => guidance_v_adapt.c} | 116 ++++++++---------- .../rotorcraft/guidance/guidance_v_adapt.h | 57 +++++++++ 7 files changed, 150 insertions(+), 93 deletions(-) rename sw/airborne/firmwares/rotorcraft/guidance/{guidance_v_adpt.h => guidance_v_adapt.c} (79%) create mode 100644 sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.h diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index ffbea72141..bb42616a4b 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -275,6 +275,7 @@ ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_h.c ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_h_ref.c ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v.c ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_ref.c +ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_adapt.c # # INS choice diff --git a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile index f57c246e8c..4785cbc075 100644 --- a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile @@ -119,6 +119,7 @@ nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_h.c nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_h_ref.c nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v.c nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_ref.c +nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_adapt.c # # INS choice diff --git a/conf/settings/control/rotorcraft_guidance.xml b/conf/settings/control/rotorcraft_guidance.xml index 1362a96a38..45c73a958b 100644 --- a/conf/settings/control/rotorcraft_guidance.xml +++ b/conf/settings/control/rotorcraft_guidance.xml @@ -7,7 +7,8 @@ - + + diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index 53f74082a7..432f655f1b 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -24,32 +24,43 @@ * */ -#define GUIDANCE_V_C +#include "generated/airframe.h" #include "firmwares/rotorcraft/guidance/guidance_v.h" - #include "subsystems/radio_control.h" #include "firmwares/rotorcraft/stabilization.h" -// #include "booz_fms.h" FIXME #include "firmwares/rotorcraft/navigation.h" #include "state.h" #include "math/pprz_algebra_int.h" -#include "generated/airframe.h" - -/* warn if some gains are still negative */ +/* error if some gains are negative */ #if (GUIDANCE_V_HOVER_KP < 0) || \ (GUIDANCE_V_HOVER_KD < 0) || \ (GUIDANCE_V_HOVER_KI < 0) -#error "ALL control gains are now positive!!!" +#error "ALL control gains must be positive!!!" #endif + +/* If only GUIDANCE_V_NOMINAL_HOVER_THROTTLE is defined, + * disable the adaptive throttle estimation by default. + * Otherwise enable adaptive estimation by default. + */ #ifdef GUIDANCE_V_NOMINAL_HOVER_THROTTLE -PRINT_CONFIG_VAR(GUIDANCE_V_NOMINAL_HOVER_THROTTLE) +# ifndef GUIDANCE_V_ADAPT_THROTTLE_ENABLED +# define GUIDANCE_V_ADAPT_THROTTLE_ENABLED FALSE +# endif +#else +# define GUIDANCE_V_NOMINAL_HOVER_THROTTLE 0.4 +# ifndef GUIDANCE_V_ADAPT_THROTTLE_ENABLED +# define GUIDANCE_V_ADAPT_THROTTLE_ENABLED TRUE +# endif #endif +PRINT_CONFIG_VAR(GUIDANCE_V_NOMINAL_HOVER_THROTTLE) +PRINT_CONFIG_VAR(GUIDANCE_V_ADAPT_THROTTLE_ENABLED) + uint8_t guidance_v_mode; int32_t guidance_v_ff_cmd; @@ -57,6 +68,7 @@ int32_t guidance_v_fb_cmd; int32_t guidance_v_delta_t; float guidance_v_nominal_throttle; +bool_t guidance_v_adapt_throttle_enabled; /** Direct throttle from radio control. @@ -91,7 +103,7 @@ int32_t guidance_v_z_sum_err; } -__attribute__ ((always_inline)) static inline void run_hover_loop(bool_t in_flight); +void run_hover_loop(bool_t in_flight); void guidance_v_init(void) { @@ -104,9 +116,8 @@ void guidance_v_init(void) { guidance_v_z_sum_err = 0; -#ifdef GUIDANCE_V_NOMINAL_HOVER_THROTTLE guidance_v_nominal_throttle = GUIDANCE_V_NOMINAL_HOVER_THROTTLE; -#endif + guidance_v_adapt_throttle_enabled = GUIDANCE_V_ADAPT_THROTTLE_ENABLED; gv_adapt_init(); } @@ -254,7 +265,7 @@ void guidance_v_run(bool_t in_flight) { #define MAX_BANK_COEF (BFP_OF_REAL(RadOfDeg(30.),INT32_TRIG_FRAC)) -__attribute__ ((always_inline)) static inline void run_hover_loop(bool_t in_flight) { +void run_hover_loop(bool_t in_flight) { /* convert our reference to generic representation */ int64_t tmp = gv_z_ref>>(GV_Z_REF_FRAC - INT32_POS_FRAC); @@ -275,13 +286,17 @@ __attribute__ ((always_inline)) static inline void run_hover_loop(bool_t in_flig guidance_v_z_sum_err = 0; /* our nominal command : (g + zdd)*m */ -#ifdef GUIDANCE_V_NOMINAL_HOVER_THROTTLE - const int32_t inv_m = BFP_OF_REAL(9.81/(guidance_v_nominal_throttle*MAX_PPRZ), FF_CMD_FRAC); -#else - const int32_t inv_m = gv_adapt_X>>(GV_ADAPT_X_FRAC - FF_CMD_FRAC); -#endif + int32_t inv_m; + if (guidance_v_adapt_throttle_enabled) { + inv_m = gv_adapt_X >> (GV_ADAPT_X_FRAC - FF_CMD_FRAC); + } + else { + /* use the fixed nominal throttle */ + inv_m = BFP_OF_REAL(9.81 / (guidance_v_nominal_throttle * MAX_PPRZ), FF_CMD_FRAC); + } + const int32_t g_m_zdd = (int32_t)BFP_OF_REAL(9.81, FF_CMD_FRAC) - - (guidance_v_zdd_ref<<(FF_CMD_FRAC - INT32_ACCEL_FRAC)); + (guidance_v_zdd_ref << (FF_CMD_FRAC - INT32_ACCEL_FRAC)); guidance_v_ff_cmd = g_m_zdd / inv_m; int32_t cphi,ctheta,cphitheta; diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h index a9c2f86403..4a94b4cfa8 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h @@ -24,15 +24,13 @@ * */ -#ifndef GUIDANCE_V -#define GUIDANCE_V +#ifndef GUIDANCE_V_H +#define GUIDANCE_V_H #include "std.h" -#include "generated/airframe.h" #include "firmwares/rotorcraft/guidance/guidance_v_ref.h" - -#include "firmwares/rotorcraft/guidance/guidance_v_adpt.h" +#include "firmwares/rotorcraft/guidance/guidance_v_adapt.h" #define GUIDANCE_V_MODE_KILL 0 #define GUIDANCE_V_MODE_RC_DIRECT 1 @@ -89,6 +87,10 @@ extern int32_t guidance_v_delta_t; */ extern float guidance_v_nominal_throttle; +/** Use adaptive throttle command estimation. + */ +extern bool_t guidance_v_adapt_throttle_enabled; + extern int32_t guidance_v_kp; ///< vertical control P-gain extern int32_t guidance_v_kd; ///< vertical control D-gain extern int32_t guidance_v_ki; ///< vertical control I-gain @@ -104,4 +106,4 @@ extern void guidance_v_run(bool_t in_flight); guidance_v_z_sum_err = 0; \ } -#endif /* GUIDANCE_V */ +#endif /* GUIDANCE_V_H */ diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c similarity index 79% rename from sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h rename to sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c index ba743cb2cd..bcc58fbb15 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adpt.h +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2009-2010 The Paparazzi Team + * Copyright (C) 2009-2013 The Paparazzi Team * * This file is part of paparazzi. * @@ -19,18 +19,47 @@ * Boston, MA 02111-1307, USA. */ -/** @file firmwares/rotorcraft/guidance/guidance_v_adpt.h - * Adaptation bloc of the vertical guidance. +/** @file firmwares/rotorcraft/guidance/guidance_v_adapt.c + * Adaptation block of the vertical guidance. * * This is a dimension one kalman filter estimating - * the ratio of vertical acceleration over thrust command ( ~ invert of the mass ) - * needed by the invert dynamic model to produce a nominal command + * the ratio of vertical acceleration over thrust command ( ~ inverse of the mass ) + * needed by the invert dynamic model to produce a nominal command. */ -#ifndef GUIDANCE_V_ADPT -#define GUIDANCE_V_ADPT - +#include "firmwares/rotorcraft/guidance/guidance_v_adapt.h" #include "paparazzi.h" +#include "math/pprz_algebra_int.h" + + +/** Initial hover throttle as factor of MAX_PPRZ. + * Should be a value between #GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE and + * #GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE. + * It is better to start with low thrust and let it rise as the adaptive filter + * finds the vehicle needs more thrust. + */ +#ifndef GUIDANCE_V_ADAPT_INITIAL_HOVER_THROTTLE +#define GUIDANCE_V_ADAPT_INITIAL_HOVER_THROTTLE 0.3 +#endif +PRINT_CONFIG_VAR(GUIDANCE_V_ADAPT_INITIAL_HOVER_THROTTLE) + +/** Minimum hover throttle as factor of MAX_PPRZ. + * With the default of 0.2 the nominal hover throttle will + * never go lower than 20%. + */ +#ifndef GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE +#define GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE 0.2 +#endif +PRINT_CONFIG_VAR(GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE) + +/** Maximum hover throttle as factor of MAX_PPRZ. + * With the default of 0.75 the nominal hover throttle will + * never go over 75% of max throttle. + */ +#ifndef GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE +#define GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE 0.75 +#endif +PRINT_CONFIG_VAR(GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE) /** Adapt noise factor. * Smaller values will make the filter to adapt faster. @@ -41,14 +70,6 @@ #define GUIDANCE_V_ADAPT_NOISE_FACTOR 1.0 #endif -/** Initial estimation. - * The initial value can be adapted for faster converging time. - * It is usually recommended to start with a low value (overestimation of the mass), - * as it is helping for a smooth takeoff. - */ -#ifndef GUIDANCE_V_ADAPT_X0 -#define GUIDANCE_V_ADAPT_X0 0.003 -#endif /** Filter is not fed if accel values are more than +/- MAX_ACCEL. * MAX_ACCEL is a positive value in m/s^2 @@ -67,53 +88,12 @@ #define GUIDANCE_V_ADAPT_MIN_CMD 0.1 #endif -/** Minimum hover throttle as factor of MAX_PPRZ. - * With the default of 0.2 the nominal hover throttle will - * never go lower than 20%. - */ -#ifndef GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE -#define GUIDANCE_V_ADAPT_MIN_HOVER_THROTTLE 0.2 -#endif -/** Maximum hover throttle as factor of MAX_PPRZ. - * With the default of 0.75 the nominal hover throttle will - * never go over 75% of max throttle. - */ -#ifndef GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE -#define GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE 0.75 -#endif - -/** State of the estimator. - * fixed point representation with #GV_ADAPT_X_FRAC - * Q13.18 - */ -extern int32_t gv_adapt_X; -#define GV_ADAPT_X_FRAC 24 - -/** Covariance. - * fixed point representation with #GV_ADAPT_P_FRAC - * Q13.18 - */ -extern int32_t gv_adapt_P; -#define GV_ADAPT_P_FRAC 18 - -/** Measurement */ -extern int32_t gv_adapt_Xmeas; - - -#ifdef GUIDANCE_V_C int32_t gv_adapt_X; int32_t gv_adapt_P; int32_t gv_adapt_Xmeas; - -/* Initial State and Covariance */ -#define GV_ADAPT_X0_F GUIDANCE_V_ADAPT_X0 -#define GV_ADAPT_X0 BFP_OF_REAL(GV_ADAPT_X0_F, GV_ADAPT_X_FRAC) -#define GV_ADAPT_P0_F 0.1 -#define GV_ADAPT_P0 BFP_OF_REAL(GV_ADAPT_P0_F, GV_ADAPT_P_FRAC) - /* System noises */ #ifndef GV_ADAPT_SYS_NOISE_F #define GV_ADAPT_SYS_NOISE_F 0.00005 @@ -125,10 +105,15 @@ int32_t gv_adapt_Xmeas; #define GV_ADAPT_MEAS_NOISE_HOVER BFP_OF_REAL(GV_ADAPT_MEAS_NOISE_HOVER_F, GV_ADAPT_P_FRAC) #define GV_ADAPT_MEAS_NOISE_OF_ZD (100.0*GUIDANCE_V_ADAPT_NOISE_FACTOR) +/* Initial Covariance */ +#define GV_ADAPT_P0_F 0.1 +static const int32_t gv_adapt_P0 = BFP_OF_REAL(GV_ADAPT_P0_F, GV_ADAPT_P_FRAC); +static const int32_t gv_adapt_X0 = BFP_OF_REAL(9.81, GV_ADAPT_X_FRAC) / + (GUIDANCE_V_ADAPT_INITIAL_HOVER_THROTTLE * MAX_PPRZ); -static inline void gv_adapt_init(void) { - gv_adapt_X = GV_ADAPT_X0; - gv_adapt_P = GV_ADAPT_P0; +void gv_adapt_init(void) { + gv_adapt_X = gv_adapt_X0; + gv_adapt_P = gv_adapt_P0; } #define K_FRAC 12 @@ -138,7 +123,7 @@ static inline void gv_adapt_init(void) { * @param thrust_applied controller input [0 : MAX_PPRZ] * @param zd_ref vertical speed reference in m/s with #INT32_SPEED_FRAC */ -static inline void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_t zd_ref) { +void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_t zd_ref) { static const int32_t gv_adapt_min_cmd = GUIDANCE_V_ADAPT_MIN_CMD * MAX_PPRZ; static const int32_t gv_adapt_max_cmd = GUIDANCE_V_ADAPT_MAX_CMD * MAX_PPRZ; @@ -177,8 +162,8 @@ static inline void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_ /* Update Covariance Pnew = P - K * P */ gv_adapt_P = gv_adapt_P - ((K * gv_adapt_P)>>K_FRAC); /* Don't let covariance climb over initial value */ - if (gv_adapt_P > GV_ADAPT_P0) { - gv_adapt_P = GV_ADAPT_P0; + if (gv_adapt_P > gv_adapt_P0) { + gv_adapt_P = gv_adapt_P0; } /* Update State */ @@ -195,8 +180,3 @@ static inline void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_ (GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE * MAX_PPRZ); Bound(gv_adapt_X, min_out, max_out); } - - -#endif /* GUIDANCE_V_C */ - -#endif /* GUIDANCE_V_ADPT */ diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.h new file mode 100644 index 0000000000..8be2e35a22 --- /dev/null +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.h @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2009-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** @file firmwares/rotorcraft/guidance/guidance_v_adapt.h + * Adaptation block of the vertical guidance. + * + * This is a dimension one kalman filter estimating + * the ratio of vertical acceleration over thrust command ( ~ inverse of the mass ) + * needed by the invert dynamic model to produce a nominal command. + */ + +#ifndef GUIDANCE_V_ADAPT_H +#define GUIDANCE_V_ADAPT_H + +#include "std.h" + +/** State of the estimator. + * fixed point representation with #GV_ADAPT_X_FRAC + * Q13.18 + */ +extern int32_t gv_adapt_X; +#define GV_ADAPT_X_FRAC 24 + +/** Covariance. + * fixed point representation with #GV_ADAPT_P_FRAC + * Q13.18 + */ +extern int32_t gv_adapt_P; +#define GV_ADAPT_P_FRAC 18 + +/** Measurement */ +extern int32_t gv_adapt_Xmeas; + + +extern void gv_adapt_init(void); +extern void gv_adapt_run(int32_t zdd_meas, int32_t thrust_applied, int32_t zd_ref); + + +#endif /* GUIDANCE_V_ADAPT_H */ From b96785b36f8c896b2f5cfcc3ac11dd8c32296905 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 13 Aug 2013 14:22:30 +0200 Subject: [PATCH 076/309] [conf] update some airframe examples to GUIDANCE_V_ADAPT changes --- conf/airframes/ardrone2_raw.xml | 7 +++---- conf/airframes/ardrone2_sdk.xml | 5 ++--- conf/airframes/examples/lisa_asctec.xml | 1 + .../airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml | 4 ++-- conf/airframes/examples/quadrotor_lisa_m_mkk.xml | 4 ++-- conf/airframes/examples/quadrotor_mlkf.xml | 4 ++-- conf/airframes/examples/quadshot_asp21_spektrum.xml | 3 ++- conf/airframes/examples/stm32f4_discovery_test.xml | 1 - conf/airframes/fraser_lisa_m_rotorcraft.xml | 3 ++- 9 files changed, 16 insertions(+), 16 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 29a86dda84..3e461ac70c 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -202,10 +202,9 @@ - - - + + +
diff --git a/conf/airframes/ardrone2_sdk.xml b/conf/airframes/ardrone2_sdk.xml index dfbcab0f90..154b0126fb 100644 --- a/conf/airframes/ardrone2_sdk.xml +++ b/conf/airframes/ardrone2_sdk.xml @@ -84,9 +84,8 @@ - - + +
diff --git a/conf/airframes/examples/lisa_asctec.xml b/conf/airframes/examples/lisa_asctec.xml index 75f60ddfdf..4deef180d9 100644 --- a/conf/airframes/examples/lisa_asctec.xml +++ b/conf/airframes/examples/lisa_asctec.xml @@ -163,6 +163,7 @@ +
diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index 2d507056ae..3f07ab9cf2 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -186,8 +186,8 @@ - - + +
diff --git a/conf/airframes/examples/quadrotor_lisa_m_mkk.xml b/conf/airframes/examples/quadrotor_lisa_m_mkk.xml index 42fcb6b0d0..4a20c2b893 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_mkk.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_mkk.xml @@ -180,8 +180,8 @@ - - + +
diff --git a/conf/airframes/examples/quadrotor_mlkf.xml b/conf/airframes/examples/quadrotor_mlkf.xml index 7a858bf286..151464b016 100644 --- a/conf/airframes/examples/quadrotor_mlkf.xml +++ b/conf/airframes/examples/quadrotor_mlkf.xml @@ -190,8 +190,8 @@ - - + +
diff --git a/conf/airframes/examples/quadshot_asp21_spektrum.xml b/conf/airframes/examples/quadshot_asp21_spektrum.xml index 1c3262b131..771f4082c8 100644 --- a/conf/airframes/examples/quadshot_asp21_spektrum.xml +++ b/conf/airframes/examples/quadshot_asp21_spektrum.xml @@ -199,7 +199,8 @@ More information on the Quadshot can be found at transition-robotics.com --> - + +
diff --git a/conf/airframes/examples/stm32f4_discovery_test.xml b/conf/airframes/examples/stm32f4_discovery_test.xml index 8957d373cd..2f10e1c38b 100644 --- a/conf/airframes/examples/stm32f4_discovery_test.xml +++ b/conf/airframes/examples/stm32f4_discovery_test.xml @@ -186,7 +186,6 @@ -
diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index 877f496e66..3c042afc6c 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -224,7 +224,8 @@ - + +
From 03c45272909425c1721f44f56523852df02651d5 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Tue, 13 Aug 2013 15:21:58 +0200 Subject: [PATCH 077/309] [cleaning] remove some f***ing names and comments --- Makefile | 2 +- conf/airframes/obsolete/Poine/test_libeknav.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 41b749dadc..39e02ab114 100644 --- a/Makefile +++ b/Makefile @@ -31,7 +31,7 @@ PAPARAZZI_SRC=$(shell pwd) empty= space=$(empty) $(empty) ifneq ($(findstring $(space),$(PAPARAZZI_SRC)),) - $(error No fucking spaces allowed in the current directory name) + $(error No spaces allowed in the current directory name) endif ifeq ($(PAPARAZZI_HOME),) PAPARAZZI_HOME=$(PAPARAZZI_SRC) diff --git a/conf/airframes/obsolete/Poine/test_libeknav.xml b/conf/airframes/obsolete/Poine/test_libeknav.xml index 59ec1b8ac7..344e8db8b3 100644 --- a/conf/airframes/obsolete/Poine/test_libeknav.xml +++ b/conf/airframes/obsolete/Poine/test_libeknav.xml @@ -1,4 +1,4 @@ - + From c32ea43ed2a712e5b03c0d814513275d903a4bc0 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 13 Aug 2013 17:20:07 +0200 Subject: [PATCH 078/309] [rotorcraft] guidance_h: normalize psi sp from nav_heading --- sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c | 1 + 1 file changed, 1 insertion(+) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index e609a89624..1b5cdbf0b2 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -267,6 +267,7 @@ void guidance_h_run(bool_t in_flight) { /* set psi command */ guidance_h_command_body.psi = nav_heading; + INT32_ANGLE_NORMALIZE(guidance_h_command_body.psi); /* compute roll and pitch commands and set final attitude setpoint */ guidance_h_traj_run(in_flight); } From 0a3507496d577e56f0e01de026f7aced966b521b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 13 Aug 2013 17:36:57 +0200 Subject: [PATCH 079/309] [conf][airframes] joystick axis as mode in nps --- conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml | 2 ++ conf/airframes/fraser_lisa_m_rotorcraft.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index 2d507056ae..099ab06ca6 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -202,6 +202,8 @@ + +
diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index 877f496e66..f7e3935c5f 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -239,6 +239,7 @@ +
From 9822239abd1c510e1c4297bad757ead0bb81c01c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 13 Aug 2013 18:52:20 +0200 Subject: [PATCH 080/309] [rotorcraft] supress warning about uninitialized var --- sw/airborne/firmwares/rotorcraft/telemetry.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index b35591458d..d50d022a38 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -274,7 +274,7 @@ #define PERIODIC_SEND_STAB_ATTITUDE(_trans, _dev) { \ struct FloatRates* body_rate = stateGetBodyRates_f(); \ struct FloatEulers* att = stateGetNedToBodyEulers_f(); \ - float foo; \ + float foo = 0.0; \ DOWNLINK_SEND_STAB_ATTITUDE_FLOAT(_trans, _dev, \ &(body_rate->p), &(body_rate->q), &(body_rate->r), \ &(att->phi), &(att->theta), &(att->psi), \ From d15131c0f33c4d7cb395730898b570bb511ba18b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 16:55:45 +0200 Subject: [PATCH 081/309] [math] prevent division by zero in INT32_QUAT_NORMALIZE --- sw/airborne/math/pprz_algebra_int.h | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/sw/airborne/math/pprz_algebra_int.h b/sw/airborne/math/pprz_algebra_int.h index d8c75715b1..4135dbb4cd 100644 --- a/sw/airborne/math/pprz_algebra_int.h +++ b/sw/airborne/math/pprz_algebra_int.h @@ -558,13 +558,15 @@ struct Int64Vect3 { QUAT_EXPLEMENTARY(q,q); \ } -#define INT32_QUAT_NORMALIZE(q) { \ - int32_t n; \ - INT32_QUAT_NORM(n, q); \ - (q).qi = (q).qi * QUAT1_BFP_OF_REAL(1) / n; \ - (q).qx = (q).qx * QUAT1_BFP_OF_REAL(1) / n; \ - (q).qy = (q).qy * QUAT1_BFP_OF_REAL(1) / n; \ - (q).qz = (q).qz * QUAT1_BFP_OF_REAL(1) / n; \ +#define INT32_QUAT_NORMALIZE(q) { \ + int32_t n; \ + INT32_QUAT_NORM(n, q); \ + if (n > 0) { \ + (q).qi = (q).qi * QUAT1_BFP_OF_REAL(1) / n; \ + (q).qx = (q).qx * QUAT1_BFP_OF_REAL(1) / n; \ + (q).qy = (q).qy * QUAT1_BFP_OF_REAL(1) / n; \ + (q).qz = (q).qz * QUAT1_BFP_OF_REAL(1) / n; \ + } \ } /* _a2c = _a2b comp _b2c , aka _a2c = _b2c * _a2b */ From 96dd3e4ff16d212958dfa9c8d2177374906f3c0c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 14 Aug 2013 17:40:14 +0200 Subject: [PATCH 082/309] [rotorcraft] v_adapt: include generated airframe.h --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c | 1 + 1 file changed, 1 insertion(+) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c index bcc58fbb15..382a3cb0bb 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c @@ -30,6 +30,7 @@ #include "firmwares/rotorcraft/guidance/guidance_v_adapt.h" #include "paparazzi.h" #include "math/pprz_algebra_int.h" +#include "generated/airframe.h" /** Initial hover throttle as factor of MAX_PPRZ. From 7ae656c766b633f47dc4a65703cae6bbf9931c66 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 15 Aug 2013 14:23:01 +0200 Subject: [PATCH 083/309] whitespace cleanup and include guard fix --- sw/airborne/boards/krooz/imu_krooz.c | 8 ++-- sw/airborne/modules/max7456/max7456.c | 56 +++++++++++----------- sw/airborne/modules/max7456/max7456_regs.h | 11 ++--- 3 files changed, 37 insertions(+), 38 deletions(-) diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index 01fb83e3d2..fe14fbb448 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -89,7 +89,7 @@ void imu_impl_init( void ) // Init median filters #if IMU_KROOZ_USE_GYRO_MEDIAN_FILTER InitMedianFilterRatesInt(median_gyro); -#endif +#endif #if IMU_KROOZ_USE_ACCEL_MEDIAN_FILTER InitMedianFilterVect3Int(median_accel); #endif @@ -124,17 +124,17 @@ void imu_periodic( void ) #if IMU_KROOZ_USE_ACCEL_MEDIAN_FILTER UpdateMedianFilterVect3Int(median_accel, imu.accel_unscaled); #endif - + RATES_SMUL(imu_krooz.gyro_filtered, imu_krooz.gyro_filtered, IMU_KROOZ_GYRO_AVG_FILTER); RATES_ADD(imu_krooz.gyro_filtered, imu.gyro_unscaled); RATES_SDIV(imu_krooz.gyro_filtered, imu_krooz.gyro_filtered, (IMU_KROOZ_GYRO_AVG_FILTER + 1)); RATES_COPY(imu.gyro_unscaled, imu_krooz.gyro_filtered); - + VECT3_SMUL(imu_krooz.accel_filtered, imu_krooz.accel_filtered, IMU_KROOZ_ACCEL_AVG_FILTER); VECT3_ADD(imu_krooz.accel_filtered, imu.accel_unscaled); VECT3_SDIV(imu_krooz.accel_filtered, imu_krooz.accel_filtered, (IMU_KROOZ_ACCEL_AVG_FILTER + 1)); VECT3_COPY(imu.accel_unscaled, imu_krooz.accel_filtered); - + RATES_ASSIGN(imu_krooz.rates_sum, 0, 0, 0); VECT3_ASSIGN(imu_krooz.accel_sum, 0, 0, 0); imu_krooz.meas_nb = 0; diff --git a/sw/airborne/modules/max7456/max7456.c b/sw/airborne/modules/max7456/max7456.c index c022b4eb16..500aa20f72 100644 --- a/sw/airborne/modules/max7456/max7456.c +++ b/sw/airborne/modules/max7456/max7456.c @@ -18,12 +18,12 @@ * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. */ - + /** * @file modules/max7456/max7456.c * Maxim MAX7456 single-channel monochrome on-screen display driver. * - */ + */ #include "std.h" #include "stdio.h" @@ -66,7 +66,7 @@ uint8_t step = 0; uint16_t osd_char_address = 0; uint8_t osd_attr = FALSE; -enum max7456_osd_status_codes { +enum max7456_osd_status_codes { OSD_UNINIT, OSD_INIT1, OSD_INIT2, @@ -118,7 +118,7 @@ void max7456_periodic(void) { float temp = 0; //This code is executed always and checks if the "osd_enable" var has been changed by telemetry. -//If yes then it commands a reset but this time turns on or off the osd overlay, not the video. +//If yes then it commands a reset but this time turns on or off the osd overlay, not the video. if (max7456_osd_status == OSD_IDLE) { if(osd_enable > 1) osd_enable = 1; @@ -134,8 +134,8 @@ void max7456_periodic(void) { max7456_trans.status = SPITransDone; max7456_trans.output_buf[0] = OSD_VM0_REG; //This operation needs at least 100us but when the periodic function will be invoked again - //sufficient time will have elapsed even with at a periodic frequency of 1000 Hz - max7456_trans.output_buf[1] = OSD_RESET; + //sufficient time will have elapsed even with at a periodic frequency of 1000 Hz + max7456_trans.output_buf[1] = OSD_RESET; max7456_osd_status = OSD_INIT1; spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); } @@ -145,7 +145,7 @@ void max7456_periodic(void) { max7456_trans.input_length = 1; max7456_trans.output_buf[0] = OSD_OSDBL_REG_R; max7456_osd_status = OSD_INIT3; - spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); + spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); } else if (max7456_osd_status == OSD_IDLE && osd_enable > 0) { // DRAW THE OSD SCREEN @@ -199,13 +199,13 @@ void max7456_periodic(void) { return; } -void max7456_event(void) { +void max7456_event(void) { static uint8_t x = 0; if (max7456_trans.status == SPITransSuccess) { max7456_trans.status = SPITransDone; - + switch (max7456_osd_status) { case (OSD_INIT1): max7456_osd_status = OSD_INIT2; @@ -240,7 +240,7 @@ void max7456_event(void) { max7456_osd_status = OSD_S_STEP2; spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); break; - case (OSD_S_STEP2): + case (OSD_S_STEP2): max7456_trans.output_length = 2; max7456_trans.output_buf[0] = OSD_DMM_REG; max7456_trans.output_buf[1] = OSD_AUTO_INCREMENT_MODE | osd_attr; @@ -248,18 +248,18 @@ void max7456_event(void) { spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); x = 0; break; - case (OSD_S_STEP3): + case (OSD_S_STEP3): max7456_trans.output_length = 1; //1 byte tranfers, auto address incrementing. if (osd_string[x] != 0XFF) { max7456_trans.output_buf[0] = osd_string[x++]; spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); } - else { + else { max7456_trans.output_buf[0] = 0xFF; //Exit the auto increment mode max7456_osd_status = OSD_FINISHED; spi_submit(&(MAX7456_SPI_DEV), &max7456_trans); } - break; + break; case (OSD_FINISHED): osd_attr = 0; max7456_trans.status = SPITransDone; @@ -274,13 +274,13 @@ void max7456_event(void) { static char ascii_to_osd_c(char c) { if (c >= '0' && c <= '9') { - if (c == '0') - c -= 38; + if (c == '0') + c -= 38; else c -= 48; } else { - if (c >= 'A' && c <= 'Z') + if (c >= 'A' && c <= 'Z') c -= 54; else { if (c >= 'a' && c <= 'z') @@ -324,12 +324,12 @@ static void osd_put_s(char *string, uint8_t attributes, uint8_t char_nb, uint8_t // translate the string and put it to the "osd_string" '\0' = 0xff x = 0; while (*(string+x) != '\0') { - osd_string[x] = ascii_to_osd_c(*(string+x)); - x++; + osd_string[x] = ascii_to_osd_c(*(string+x)); + x++; } osd_string[x] = ascii_to_osd_c(*(string+x)); - for (x=0; x < sizeof(osd_string); x++) { + for (x=0; x < sizeof(osd_string); x++) { if(osd_string[x] == 0xff) break; } @@ -340,7 +340,7 @@ static void osd_put_s(char *string, uint8_t attributes, uint8_t char_nb, uint8_t } osd_string[x] = 0xff; - osd_attr = attributes; + osd_attr = attributes; //TRIGGER THE SPI TRANSFERS. The rest of the spi transfers occur in the "max7456_event" function. if (max7456_osd_status == OSD_IDLE){ @@ -375,11 +375,11 @@ static bool_t _osd_sprintf(char* buffer, char* string, float value) { // Search for the prameter start and stop positions. while (*(string+x) != '\0'){ if (*(string+x) == '%'){ - param_start = x; + param_start = x; } - else + else if (*(string+x) == 'f') { - param_end = x; + param_end = x; break; } x++; @@ -413,30 +413,30 @@ static bool_t _osd_sprintf(char* buffer, char* string, float value) { to_asc[y] = (i_dec % 10) + 48; //Write at least one digit even if value is zero. i_dec /= 10; if (i_dec <= 0) { // This way the leading zero is ommited. - if(value < 0) { + if(value < 0) { y--; to_asc[y] = '-'; // Place the minus sign if needed. } break; } else y--; - } while(1); + } while(1); // Fill the buffer with the characters in the beggining of the string if any. for (x=0; x Date: Thu, 15 Aug 2013 18:52:19 +0200 Subject: [PATCH 084/309] [rotorcraft] define AHRS_FLOAT for float_cmpl_rmat --- .../subsystems/rotorcraft/ahrs_float_cmpl_rmat.makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_rmat.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_rmat.makefile index f8800de866..779c55006f 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_rmat.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_rmat.makefile @@ -7,7 +7,7 @@ USE_MAGNETOMETER ?= 1 -AHRS_CFLAGS = -DUSE_AHRS +AHRS_CFLAGS = -DUSE_AHRS -DAHRS_FLOAT AHRS_CFLAGS += -DUSE_AHRS_ALIGNER ifneq ($(USE_MAGNETOMETER),0) From 29bdf40d9a87381e3d5b39b8aa4a53ea7f043e59 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 15:09:36 +0200 Subject: [PATCH 085/309] [nps] datalink via ivy handling --- .../subsystems/fixedwing/fdm_jsbsim.makefile | 1 + .../subsystems/rotorcraft/fdm_jsbsim.makefile | 13 +- sw/simulator/nps/nps_autopilot_fixedwing.c | 3 +- sw/simulator/nps/nps_ivy.h | 1 + .../nps/{nps_ivy.c => nps_ivy_common.c} | 27 +--- sw/simulator/nps/nps_ivy_fixedwing.c | 151 ++---------------- sw/simulator/nps/nps_ivy_rotorcraft.c | 58 +++++++ 7 files changed, 85 insertions(+), 169 deletions(-) rename sw/simulator/nps/{nps_ivy.c => nps_ivy_common.c} (85%) create mode 100644 sw/simulator/nps/nps_ivy_rotorcraft.c diff --git a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile index a62460df79..688d5b7cb4 100644 --- a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile @@ -56,6 +56,7 @@ nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_radio_control_joystick.c \ $(NPSDIR)/nps_radio_control_spektrum.c \ $(NPSDIR)/nps_autopilot_fixedwing.c \ + $(NPSDIR)/nps_ivy_common.c \ $(NPSDIR)/nps_ivy_fixedwing.c \ $(NPSDIR)/nps_flightgear.c \ diff --git a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile index f57c246e8c..14a04e502f 100644 --- a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile @@ -38,7 +38,7 @@ else endif -nps.srcs += $(NPSDIR)/nps_main.c \ +nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_fdm_jsbsim.c \ $(NPSDIR)/nps_random.c \ $(NPSDIR)/nps_sensors.c \ @@ -51,17 +51,18 @@ nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_radio_control.c \ $(NPSDIR)/nps_radio_control_joystick.c \ $(NPSDIR)/nps_radio_control_spektrum.c \ - $(NPSDIR)/nps_autopilot_rotorcraft.c \ - $(NPSDIR)/nps_ivy.c \ + $(NPSDIR)/nps_autopilot_rotorcraft.c \ + $(NPSDIR)/nps_ivy_common.c \ + $(NPSDIR)/nps_ivy_rotorcraft.c \ $(NPSDIR)/nps_flightgear.c \ nps.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) -DPERIPHERALS_AUTO_INIT -nps.srcs += firmwares/rotorcraft/main.c -nps.srcs += mcu.c -nps.srcs += $(SRC_ARCH)/mcu_arch.c +nps.srcs += firmwares/rotorcraft/main.c +nps.srcs += mcu.c +nps.srcs += $(SRC_ARCH)/mcu_arch.c nps.srcs += mcu_periph/i2c.c nps.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c diff --git a/sw/simulator/nps/nps_autopilot_fixedwing.c b/sw/simulator/nps/nps_autopilot_fixedwing.c index 0e58a7ee02..09bed64681 100644 --- a/sw/simulator/nps/nps_autopilot_fixedwing.c +++ b/sw/simulator/nps/nps_autopilot_fixedwing.c @@ -85,11 +85,12 @@ void nps_autopilot_run_systime_step( void ) { void nps_autopilot_run_step(double time __attribute__ ((unused))) { +#ifdef RADIO_CONTROL_TYPE_PPM if (nps_radio_control_available(time)) { radio_control_feed(); Fbw(event_task); - Ap(event_task); } +#endif if (nps_sensors_gyro_available()) { imu_feed_gyro_accel(); diff --git a/sw/simulator/nps/nps_ivy.h b/sw/simulator/nps/nps_ivy.h index 64011b7a1f..db8b993365 100644 --- a/sw/simulator/nps/nps_ivy.h +++ b/sw/simulator/nps/nps_ivy.h @@ -1,6 +1,7 @@ #ifndef NPS_IVY #define NPS_IVY +extern void nps_ivy_common_init(char* ivy_bus); extern void nps_ivy_init(char* ivy_bus); extern void nps_ivy_display(void); diff --git a/sw/simulator/nps/nps_ivy.c b/sw/simulator/nps/nps_ivy_common.c similarity index 85% rename from sw/simulator/nps/nps_ivy.c rename to sw/simulator/nps/nps_ivy_common.c index 93847c425c..90766d756e 100644 --- a/sw/simulator/nps/nps_ivy.c +++ b/sw/simulator/nps/nps_ivy_common.c @@ -10,7 +10,6 @@ #include "nps_fdm.h" #include "nps_sensors.h" #include "subsystems/ins.h" -#include "firmwares/rotorcraft/navigation.h" #ifdef RADIO_CONTROL_TYPE_DATALINK #include "subsystems/radio_control.h" @@ -36,10 +35,6 @@ static void on_DL_BLOCK(IvyClientPtr app __attribute__ ((unused)), void *user_data __attribute__ ((unused)), int argc __attribute__ ((unused)), char *argv[]); -static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]); - #ifdef RADIO_CONTROL_TYPE_DATALINK static void on_DL_RC_3CH(IvyClientPtr app __attribute__ ((unused)), void *user_data __attribute__ ((unused)), @@ -50,7 +45,7 @@ static void on_DL_RC_4CH(IvyClientPtr app __attribute__ ((unused)), int argc __attribute__ ((unused)), char *argv[]); #endif -void nps_ivy_init(char* ivy_bus) { +void nps_ivy_common_init(char* ivy_bus) { const char* agent_name = AIRFRAME_NAME"_NPS"; const char* ready_msg = AIRFRAME_NAME"_NPS Ready"; IvyInit(agent_name, ready_msg, NULL, NULL, NULL, NULL); @@ -58,7 +53,6 @@ void nps_ivy_init(char* ivy_bus) { IvyBindMsg(on_DL_SETTING, NULL, "^(\\S*) DL_SETTING (\\S*) (\\S*) (\\S*)"); IvyBindMsg(on_DL_GET_SETTING, NULL, "^(\\S*) GET_DL_SETTING (\\S*) (\\S*)"); IvyBindMsg(on_DL_BLOCK, NULL, "^(\\S*) BLOCK (\\S*) (\\S*)"); - IvyBindMsg(on_DL_MOVE_WP, NULL, "^(\\S*) MOVE_WP (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); #ifdef RADIO_CONTROL_TYPE_DATALINK IvyBindMsg(on_DL_RC_3CH, NULL, "^(\\S*) RC_3CH (\\S*) (\\S*) (\\S*) (\\S*)"); @@ -117,25 +111,6 @@ static void on_DL_BLOCK(IvyClientPtr app __attribute__ ((unused)), printf("goto block %d\n", block); } -static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]) { - uint8_t wp_id = atoi(argv[1]); - - struct LlaCoor_i lla; - struct EnuCoor_i enu; - lla.lat = INT32_RAD_OF_DEG(atoi(argv[3])); - lla.lon = INT32_RAD_OF_DEG(atoi(argv[4])); - lla.alt = atoi(argv[5])*10 - ins_ltp_def.hmsl + ins_ltp_def.lla.alt; - enu_of_lla_point_i(&enu,&ins_ltp_def,&lla); - enu.x = POS_BFP_OF_REAL(enu.x)/100; - enu.y = POS_BFP_OF_REAL(enu.y)/100; - enu.z = POS_BFP_OF_REAL(enu.z)/100; - VECT3_ASSIGN(waypoints[wp_id], enu.x, enu.y, enu.z); - DOWNLINK_SEND_WP_MOVED_ENU(DefaultChannel, DefaultDevice, &wp_id, &enu.x, &enu.y, &enu.z); - printf("move wp id=%d x=%d y=%d z=%d\n", wp_id, enu.x, enu.y, enu.z); -} - #ifdef RADIO_CONTROL_TYPE_DATALINK static void on_DL_RC_3CH(IvyClientPtr app __attribute__ ((unused)), void *user_data __attribute__ ((unused)), diff --git a/sw/simulator/nps/nps_ivy_fixedwing.c b/sw/simulator/nps/nps_ivy_fixedwing.c index 386f35ad5e..a7bd73cbba 100644 --- a/sw/simulator/nps/nps_ivy_fixedwing.c +++ b/sw/simulator/nps/nps_ivy_fixedwing.c @@ -2,114 +2,45 @@ #include #include -#include #include "generated/airframe.h" #include "math/pprz_algebra_double.h" -#include "nps_autopilot.h" -#include "nps_fdm.h" -#include "nps_sensors.h" #include "subsystems/ins.h" #include "subsystems/navigation/common_nav.h" -#include NPS_SENSORS_PARAMS - - -/* Datalink Ivy functions */ -static void on_DL_SETTING(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]); - -static void on_DL_GET_SETTING(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]); - -static void on_DL_PING(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]); - -static void on_DL_BLOCK(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]); - -static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]); +/* fixedwing specific Datalink Ivy functions */ +void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), + void *user_data __attribute__ ((unused)), + int argc __attribute__ ((unused)), char *argv[]); void nps_ivy_init(char* ivy_bus) { - const char* agent_name = AIRFRAME_NAME"_NPS"; - const char* ready_msg = AIRFRAME_NAME"_NPS Ready"; - IvyInit(agent_name, ready_msg, NULL, NULL, NULL, NULL); - IvyBindMsg(on_DL_PING, NULL, "^(\\S*) DL_PING"); - IvyBindMsg(on_DL_SETTING, NULL, "^(\\S*) DL_SETTING (\\S*) (\\S*) (\\S*)"); - IvyBindMsg(on_DL_GET_SETTING, NULL, "^(\\S*) GET_DL_SETTING (\\S*) (\\S*)"); - IvyBindMsg(on_DL_BLOCK, NULL, "^(\\S*) BLOCK (\\S*) (\\S*)"); - IvyBindMsg(on_DL_MOVE_WP, NULL, "^(\\S*) MOVE_WP (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); + /* init ivy and bind some messages common to fw and rotorcraft */ + nps_ivy_common_init(ivy_bus); -#ifdef __APPLE__ - const char* default_ivy_bus = "224.255.255.255"; -#else - const char* default_ivy_bus = "127.255.255.255"; -#endif - if (ivy_bus == NULL) { - IvyStart(default_ivy_bus); - } else { - IvyStart(ivy_bus); - } + IvyBindMsg(on_DL_MOVE_WP, NULL, "^(\\S*) MOVE_WP (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); } -//TODO use datalink parsing from booz or fw instead of doing it here explicitly -//FIXME currently parsed correctly for booz only - +//TODO use datalink parsing from fixedwing instead of doing it here explicitly #include "generated/settings.h" #include "dl_protocol.h" #include "subsystems/datalink/downlink.h" -static void on_DL_SETTING(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]) { - uint8_t index = atoi(argv[2]); - float value = atof(argv[3]); - DlSetting(index, value); - DOWNLINK_SEND_DL_VALUE(DefaultChannel, DefaultDevice, &index, &value); - printf("setting %d %f\n", index, value); -} -static void on_DL_GET_SETTING(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]) { - uint8_t index = atoi(argv[2]); - float value = settings_get_value(index); - DOWNLINK_SEND_DL_VALUE(DefaultChannel, DefaultDevice, &index, &value); - printf("get setting %d %f\n", index, value); -} +#define MOfCm(_x) (((float)(_x))/100.) -static void on_DL_PING(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[] __attribute__ ((unused))) { - DOWNLINK_SEND_PONG(DefaultChannel, DefaultDevice); -} - -static void on_DL_BLOCK(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]){ - int block = atoi(argv[1]); - nav_goto_block(block); - printf("goto block %d\n", block); -} - -static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), - void *user_data __attribute__ ((unused)), - int argc __attribute__ ((unused)), char *argv[]) { +void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), + void *user_data __attribute__ ((unused)), + int argc __attribute__ ((unused)), char *argv[]) { if (atoi(argv[2]) == AC_ID) { uint8_t wp_id = atoi(argv[1]); - float a = atoi(argv[5]) * 0.1; + float a = MOfCm(atoi(argv[5])); /* Computes from (lat, long) in the referenced UTM zone */ struct LlaCoor_f lla; lla.lat = RadOfDeg((float)(atoi(argv[3]) / 1e7)); lla.lon = RadOfDeg((float)(atoi(argv[4]) / 1e7)); + //printf("move wp id=%d lat=%f lon=%f alt=%f\n", wp_id, lla.lat, lla.lon, a); struct UtmCoor_f utm; utm.zone = nav_utm_zone0; utm_of_lla_f(&utm, &lla); @@ -120,58 +51,6 @@ static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), utm.east = waypoints[wp_id].x + nav_utm_east0; utm.north = waypoints[wp_id].y + nav_utm_north0; DOWNLINK_SEND_WP_MOVED(DefaultChannel, DefaultDevice, &wp_id, &utm.east, &utm.north, &a, &nav_utm_zone0); - printf("move wp id=%d east=%f north=%f alt=%f\n", wp_id, utm.east, utm.north, a); + printf("move wp id=%d east=%f north=%f zone=%i alt=%f\n", wp_id, utm.east, utm.north, utm.zone, a); } } - - -void nps_ivy_display(void) { - IvySendMsg("%d NPS_RATE_ATTITUDE %f %f %f %f %f %f", - AC_ID, - DegOfRad(fdm.body_ecef_rotvel.p), - DegOfRad(fdm.body_ecef_rotvel.q), - DegOfRad(fdm.body_ecef_rotvel.r), - DegOfRad(fdm.ltp_to_body_eulers.phi), - DegOfRad(fdm.ltp_to_body_eulers.theta), - DegOfRad(fdm.ltp_to_body_eulers.psi)); - IvySendMsg("%d NPS_POS_LLH %f %f %f %f %f %f %f %f %f", - AC_ID, - (fdm.lla_pos_pprz.lat), - (fdm.lla_pos_geod.lat), - (fdm.lla_pos_geoc.lat), - (fdm.lla_pos_pprz.lon), - (fdm.lla_pos_geod.lon), - (fdm.lla_pos_pprz.alt), - (fdm.lla_pos_geod.alt), - (fdm.agl), - (fdm.hmsl)); - IvySendMsg("%d NPS_SPEED_POS %f %f %f %f %f %f %f %f %f", - AC_ID, - (fdm.ltpprz_ecef_accel.x), - (fdm.ltpprz_ecef_accel.y), - (fdm.ltpprz_ecef_accel.z), - (fdm.ltpprz_ecef_vel.x), - (fdm.ltpprz_ecef_vel.y), - (fdm.ltpprz_ecef_vel.z), - (fdm.ltpprz_pos.x), - (fdm.ltpprz_pos.y), - (fdm.ltpprz_pos.z)); - IvySendMsg("%d NPS_GYRO_BIAS %f %f %f", - AC_ID, - DegOfRad(RATE_FLOAT_OF_BFP(sensors.gyro.bias_random_walk_value.x)+sensors.gyro.bias_initial.x), - DegOfRad(RATE_FLOAT_OF_BFP(sensors.gyro.bias_random_walk_value.y)+sensors.gyro.bias_initial.y), - DegOfRad(RATE_FLOAT_OF_BFP(sensors.gyro.bias_random_walk_value.z)+sensors.gyro.bias_initial.z)); - - /* transform magnetic field to body frame */ - struct DoubleVect3 h_body; - FLOAT_QUAT_VMULT(h_body, fdm.ltp_to_body_quat, fdm.ltp_h); - - IvySendMsg("%d NPS_SENSORS_SCALED %f %f %f %f %f %f", - AC_ID, - ((sensors.accel.value.x - sensors.accel.neutral.x)/NPS_ACCEL_SENSITIVITY_XX), - ((sensors.accel.value.y - sensors.accel.neutral.y)/NPS_ACCEL_SENSITIVITY_YY), - ((sensors.accel.value.z - sensors.accel.neutral.z)/NPS_ACCEL_SENSITIVITY_ZZ), - h_body.x, - h_body.y, - h_body.z); -} diff --git a/sw/simulator/nps/nps_ivy_rotorcraft.c b/sw/simulator/nps/nps_ivy_rotorcraft.c new file mode 100644 index 0000000000..bf0ef5562b --- /dev/null +++ b/sw/simulator/nps/nps_ivy_rotorcraft.c @@ -0,0 +1,58 @@ +#include "nps_ivy.h" + +#include +#include + +#include "generated/airframe.h" +#include "math/pprz_algebra_double.h" +#include "nps_autopilot.h" +#include "nps_fdm.h" +#include "nps_sensors.h" +#include "subsystems/ins.h" +#include "firmwares/rotorcraft/navigation.h" + +#ifdef RADIO_CONTROL_TYPE_DATALINK +#include "subsystems/radio_control.h" +#endif + +#include NPS_SENSORS_PARAMS + + +/* rotorcraft specificDatalink Ivy functions */ +static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), + void *user_data __attribute__ ((unused)), + int argc __attribute__ ((unused)), char *argv[]); + +void nps_ivy_init(char* ivy_bus) { + /* init ivy and bind some messages common to fw and rotorcraft */ + nps_ivy_common_init(ivy_bus); + + IvyBindMsg(on_DL_MOVE_WP, NULL, "^(\\S*) MOVE_WP (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)"); + +} + +//TODO use datalink parsing from rotorcraft instead of doing it here explicitly + +#include "generated/settings.h" +#include "dl_protocol.h" +#include "subsystems/datalink/downlink.h" +static void on_DL_MOVE_WP(IvyClientPtr app __attribute__ ((unused)), + void *user_data __attribute__ ((unused)), + int argc __attribute__ ((unused)), char *argv[]) { + if (atoi(argv[2]) == AC_ID) { + uint8_t wp_id = atoi(argv[1]); + + struct LlaCoor_i lla; + struct EnuCoor_i enu; + lla.lat = INT32_RAD_OF_DEG(atoi(argv[3])); + lla.lon = INT32_RAD_OF_DEG(atoi(argv[4])); + lla.alt = atoi(argv[5])*10 - ins_ltp_def.hmsl + ins_ltp_def.lla.alt; + enu_of_lla_point_i(&enu,&ins_ltp_def,&lla); + enu.x = POS_BFP_OF_REAL(enu.x)/100; + enu.y = POS_BFP_OF_REAL(enu.y)/100; + enu.z = POS_BFP_OF_REAL(enu.z)/100; + VECT3_ASSIGN(waypoints[wp_id], enu.x, enu.y, enu.z); + DOWNLINK_SEND_WP_MOVED_ENU(DefaultChannel, DefaultDevice, &wp_id, &enu.x, &enu.y, &enu.z); + printf("move wp id=%d x=%d y=%d z=%d\n", wp_id, enu.x, enu.y, enu.z); + } +} From bfcbb9e15eae59952a74e49c13d5356336b50745 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 16:58:08 +0200 Subject: [PATCH 086/309] [nps][conf] add needed sources/flags for imu/ahrs in fw nps --- .../subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile | 3 +++ conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile | 4 +++- .../subsystems/fixedwing/ahrs_int_cmpl_quat.makefile | 5 +++++ conf/firmwares/subsystems/shared/imu_nps.makefile | 2 +- 4 files changed, 12 insertions(+), 2 deletions(-) diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile index fa70116214..6d82542b6c 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile @@ -27,6 +27,9 @@ AHRS_SRCS += subsystems/ahrs/ahrs_aligner.c ap.CFLAGS += $(AHRS_CFLAGS) ap.srcs += $(AHRS_SRCS) +# +# NPS uses the real algorithm +# nps.CFLAGS += $(AHRS_CFLAGS) nps.srcs += $(AHRS_SRCS) diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile index 0223edbc82..6427993c02 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile @@ -25,10 +25,12 @@ endif ap.CFLAGS += $(AHRS_CFLAGS) ap.srcs += $(AHRS_SRCS) +# +# NPS uses the real algorithm +# nps.CFLAGS += $(AHRS_CFLAGS) nps.srcs += $(AHRS_SRCS) - # # Simple simulation of the AHRS result # diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile index ca4c99ecdb..5bea385eaa 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile @@ -36,6 +36,11 @@ ap.srcs += $(AHRS_SRCS) #ap.CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY) #endif +# +# NPS uses the real algorithm +# +nps.CFLAGS += $(AHRS_CFLAGS) +nps.srcs += $(AHRS_SRCS) # # Simple simulation of the AHRS result diff --git a/conf/firmwares/subsystems/shared/imu_nps.makefile b/conf/firmwares/subsystems/shared/imu_nps.makefile index e26d035cd4..a84003b6d6 100644 --- a/conf/firmwares/subsystems/shared/imu_nps.makefile +++ b/conf/firmwares/subsystems/shared/imu_nps.makefile @@ -20,5 +20,5 @@ #
# -nps.CFLAGS += -DIMU_TYPE_H=\"imu/imu_nps.h\" +nps.CFLAGS += -DIMU_TYPE_H=\"imu/imu_nps.h\" -DUSE_IMU nps.srcs += $(SRC_SUBSYSTEMS)/imu.c $(SRC_SUBSYSTEMS)/imu/imu_nps.c From 19afae8cee924c5cb079ae0948f599fef2b91d08 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 19:30:41 +0200 Subject: [PATCH 087/309] [nps] configurable jsbsim model and initial conditions from flight plan If NPS_JSBSIM_MODEL is not defined, it defaults to the AIRCRAFT_NAME (previous behavior). If NPS_JSBSIM_INIT is defined, that ic file is used, otherwise uses flight plan location. NPS_INITIAL_CONDITITONS is not used anymore. --- sw/simulator/nps/nps_fdm_jsbsim.c | 70 +++++++++++++++++++++++++++---- 1 file changed, 63 insertions(+), 7 deletions(-) diff --git a/sw/simulator/nps/nps_fdm_jsbsim.c b/sw/simulator/nps/nps_fdm_jsbsim.c index c33307c82d..4487ae8c14 100644 --- a/sw/simulator/nps/nps_fdm_jsbsim.c +++ b/sw/simulator/nps/nps_fdm_jsbsim.c @@ -26,22 +26,41 @@ * This is an FDM for NPS that uses JSBSim as the simulation engine. */ +#include +#include +#include + #include #include #include #include #include -#include + #include "nps_fdm.h" -#include "generated/airframe.h" #include "math/pprz_geodetic.h" #include "math/pprz_geodetic_double.h" #include "math/pprz_geodetic_float.h" #include "math/pprz_algebra.h" #include "math/pprz_algebra_float.h" +#include "generated/airframe.h" +#include "generated/flight_plan.h" + /// Macro to convert from feet to metres #define MetersOfFeet(_f) ((_f)/3.2808399) +#define FeetOfMeters(_m) ((_m)*3.2808399) + +/** Name of the JSBSim model. + * Defaults to the AIRFRAME_NAME + */ +#ifndef NPS_JSBSIM_MODEL +#define NPS_JSBSIM_MODEL AIRFRAME_NAME +#endif + +#ifdef NPS_INITIAL_CONDITITONS +#warning NPS_INITIAL_CONDITITONS was replaced by NPS_JSBSIM_INIT! +#warning Defaulting to flight plan location. +#endif /** Minimum JSBSim timestep * Around 1/10000 seems to be good for ground impacts @@ -49,6 +68,7 @@ #define MIN_DT (1.0/10240.0) using namespace JSBSim; +using namespace std; static void feed_jsbsim(double* commands); static void fetch_state(void); @@ -294,9 +314,18 @@ static void init_jsbsim(double dt) { char buf[1024]; string rootdir; + string jsbsim_ic_name; sprintf(buf,"%s/conf/simulator/jsbsim/",getenv("PAPARAZZI_HOME")); rootdir = string(buf); + + /* if jsbsim initial conditions are defined, use them + * otherwise use flightplan location + */ +#ifdef NPS_JSBSIM_INIT + jsbsim_ic_name = NPS_JSBSIM_INIT; +#endif + FDMExec = new FGFDMExec(); FDMExec->Setsim_time(0.); @@ -308,7 +337,7 @@ static void init_jsbsim(double dt) { if ( ! FDMExec->LoadModel( rootdir + "aircraft", rootdir + "engine", rootdir + "systems", - AIRFRAME_NAME, + NPS_JSBSIM_MODEL, false)){ #ifdef DEBUG cerr << " JSBSim could not be started" << endl << endl; @@ -321,12 +350,39 @@ static void init_jsbsim(double dt) { FDMExec->GetPropulsion()->InitRunning(-1); JSBSim::FGInitialCondition *IC = FDMExec->GetIC(); - if ( ! IC->Load(NPS_INITIAL_CONDITITONS)) { + if(!jsbsim_ic_name.empty()) { + if ( ! IC->Load(jsbsim_ic_name)) { #ifdef DEBUG - cerr << "Initialization unsuccessful" << endl; + cerr << "Initialization unsuccessful" << endl; #endif - delete FDMExec; - exit(-1); + delete FDMExec; + exit(-1); + } + } + else { + // FGInitialCondition::SetAltitudeASLFtIC + // requires this function to be called + // before itself + IC->SetVgroundFpsIC(0.); + + // Use flight plan initial conditions + // convert geodetic lat from flight plan to geocentric + double gd_lat = RadOfDeg(NAV_LAT0 / 1e7); + double gc_lat = gc_of_gd_lat_d(gd_lat, GROUND_ALT); + IC->SetLatitudeDegIC(DegOfRad(gc_lat)); + IC->SetLongitudeDegIC(NAV_LON0 / 1e7); + + IC->SetAltitudeASLFtIC(FeetOfMeters(GROUND_ALT + 2.0)); + IC->SetTerrainElevationFtIC(FeetOfMeters(GROUND_ALT)); + IC->SetPsiDegIC(QFU); + IC->SetVgroundFpsIC(0.); + + //initRunning for all engines + FDMExec->GetPropulsion()->InitRunning(-1); + if (!FDMExec->RunIC()) { + cerr << "Initialization from flight plan unsuccessful" << endl; + exit(-1); + } } // calculate vehicle max radius in m From 2c8e58d879c2c8f851eb7dfdaa7e18fdc5e29156 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 19:40:36 +0200 Subject: [PATCH 088/309] [conf][nps] replace INITIAL_CONDITITONS with JSBSIM_INIT in all airframes --- conf/airframes/ENAC/quadrotor/booz2_g1.xml | 2 +- conf/airframes/NoVa_L.xml | 2 +- conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml | 2 +- conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml | 2 +- conf/airframes/ardrone2_raw.xml | 2 +- conf/airframes/booz2_flixr.xml | 2 +- conf/airframes/esden/cocto_lm2a2.xml | 2 +- conf/airframes/esden/gain_scheduling_example.xml | 2 +- conf/airframes/esden/hexy_ll11a2pwm.xml | 2 +- conf/airframes/esden/hexy_lm2a2pwm.xml | 2 +- conf/airframes/esden/lisa2_hex.xml | 2 +- conf/airframes/esden/qs_asp22.xml | 2 +- conf/airframes/esden/quady_ll11a2pwm.xml | 2 +- conf/airframes/esden/quady_lm1a1pwm.xml | 2 +- conf/airframes/esden/quady_lm2a2pwm.xml | 2 +- conf/airframes/esden/quady_lm2a2pwmppm.xml | 2 +- conf/airframes/examples/MentorEnergy.xml | 4 ++-- conf/airframes/examples/booz2.xml | 2 +- conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml | 2 +- conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml | 2 +- conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml | 2 +- conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml | 2 +- conf/airframes/examples/lisa_asctec.xml | 2 +- conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml | 2 +- .../examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml | 2 +- conf/airframes/examples/quadrotor_lisa_m_mkk.xml | 2 +- conf/airframes/examples/quadrotor_mlkf.xml | 2 +- conf/airframes/examples/quadrotor_navgo.xml | 2 +- conf/airframes/examples/quadshot_asp21_spektrum.xml | 2 +- conf/airframes/fraser_lisa_m_rotorcraft.xml | 2 +- conf/airframes/obsolete/ENAC/g1_vision.xml | 2 +- conf/airframes/obsolete/Poine/booz2_a1.xml | 2 +- conf/airframes/obsolete/Poine/booz2_a7.xml | 2 +- conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml | 2 +- conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml | 2 +- conf/airframes/obsolete/UofAdelaide/booz2_a1000.xml | 2 +- conf/airframes/obsolete/booz2_a1p.xml | 2 +- conf/airframes/obsolete/booz2_s1.xml | 2 +- conf/airframes/obsolete/example_heli_lisam.xml | 2 +- conf/airframes/obsolete/mm/rotor/qmk1.xml | 2 +- conf/airframes/obsolete/mm/rotor/quadrotor_lisa_l_mkk.xml | 2 +- conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_1_pwm.xml | 2 +- conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_2_pwm.xml | 2 +- 43 files changed, 44 insertions(+), 44 deletions(-) diff --git a/conf/airframes/ENAC/quadrotor/booz2_g1.xml b/conf/airframes/ENAC/quadrotor/booz2_g1.xml index ae5f73a8eb..834132e720 100644 --- a/conf/airframes/ENAC/quadrotor/booz2_g1.xml +++ b/conf/airframes/ENAC/quadrotor/booz2_g1.xml @@ -260,7 +260,7 @@
- +
diff --git a/conf/airframes/NoVa_L.xml b/conf/airframes/NoVa_L.xml index affb520b20..aaf45e3e27 100644 --- a/conf/airframes/NoVa_L.xml +++ b/conf/airframes/NoVa_L.xml @@ -228,7 +228,7 @@
- +
diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml index 87f9e38388..ee9e0848ac 100644 --- a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml +++ b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml @@ -253,7 +253,7 @@
- +
diff --git a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml index f9d1c22a70..06f2f97307 100644 --- a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml +++ b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml @@ -253,7 +253,7 @@
- +
diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 29a86dda84..26dca39651 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -218,7 +218,7 @@
- +
diff --git a/conf/airframes/booz2_flixr.xml b/conf/airframes/booz2_flixr.xml index d7467c3203..a62ace8aee 100644 --- a/conf/airframes/booz2_flixr.xml +++ b/conf/airframes/booz2_flixr.xml @@ -232,7 +232,7 @@
- +
diff --git a/conf/airframes/esden/cocto_lm2a2.xml b/conf/airframes/esden/cocto_lm2a2.xml index 6d77ad1dcb..609e7295bd 100644 --- a/conf/airframes/esden/cocto_lm2a2.xml +++ b/conf/airframes/esden/cocto_lm2a2.xml @@ -207,7 +207,7 @@ B2L -> CW
- +
diff --git a/conf/airframes/esden/gain_scheduling_example.xml b/conf/airframes/esden/gain_scheduling_example.xml index b38357f11f..02f574bd9f 100644 --- a/conf/airframes/esden/gain_scheduling_example.xml +++ b/conf/airframes/esden/gain_scheduling_example.xml @@ -189,7 +189,7 @@
- +
diff --git a/conf/airframes/esden/hexy_ll11a2pwm.xml b/conf/airframes/esden/hexy_ll11a2pwm.xml index 55412a313b..f796f42c68 100644 --- a/conf/airframes/esden/hexy_ll11a2pwm.xml +++ b/conf/airframes/esden/hexy_ll11a2pwm.xml @@ -205,7 +205,7 @@
- +
diff --git a/conf/airframes/esden/hexy_lm2a2pwm.xml b/conf/airframes/esden/hexy_lm2a2pwm.xml index 53292099a9..73554f3209 100644 --- a/conf/airframes/esden/hexy_lm2a2pwm.xml +++ b/conf/airframes/esden/hexy_lm2a2pwm.xml @@ -166,7 +166,7 @@
- +
diff --git a/conf/airframes/esden/lisa2_hex.xml b/conf/airframes/esden/lisa2_hex.xml index ce6a348d5f..b21dddffcb 100644 --- a/conf/airframes/esden/lisa2_hex.xml +++ b/conf/airframes/esden/lisa2_hex.xml @@ -177,7 +177,7 @@
- +
diff --git a/conf/airframes/esden/qs_asp22.xml b/conf/airframes/esden/qs_asp22.xml index f47a8715d1..c4ef62b938 100644 --- a/conf/airframes/esden/qs_asp22.xml +++ b/conf/airframes/esden/qs_asp22.xml @@ -200,7 +200,7 @@
- +
diff --git a/conf/airframes/esden/quady_ll11a2pwm.xml b/conf/airframes/esden/quady_ll11a2pwm.xml index 876ee4a2c3..ca80e5a5d2 100644 --- a/conf/airframes/esden/quady_ll11a2pwm.xml +++ b/conf/airframes/esden/quady_ll11a2pwm.xml @@ -201,7 +201,7 @@
- +
diff --git a/conf/airframes/esden/quady_lm1a1pwm.xml b/conf/airframes/esden/quady_lm1a1pwm.xml index e94f7008ae..406734e757 100644 --- a/conf/airframes/esden/quady_lm1a1pwm.xml +++ b/conf/airframes/esden/quady_lm1a1pwm.xml @@ -162,7 +162,7 @@
- +
diff --git a/conf/airframes/esden/quady_lm2a2pwm.xml b/conf/airframes/esden/quady_lm2a2pwm.xml index 6b8b5da46d..e87c817b3e 100644 --- a/conf/airframes/esden/quady_lm2a2pwm.xml +++ b/conf/airframes/esden/quady_lm2a2pwm.xml @@ -164,7 +164,7 @@
- +
diff --git a/conf/airframes/esden/quady_lm2a2pwmppm.xml b/conf/airframes/esden/quady_lm2a2pwmppm.xml index f33377fe79..31fd65c39d 100644 --- a/conf/airframes/esden/quady_lm2a2pwmppm.xml +++ b/conf/airframes/esden/quady_lm2a2pwmppm.xml @@ -162,7 +162,7 @@
- +
diff --git a/conf/airframes/examples/MentorEnergy.xml b/conf/airframes/examples/MentorEnergy.xml index 20861aca00..f282305020 100644 --- a/conf/airframes/examples/MentorEnergy.xml +++ b/conf/airframes/examples/MentorEnergy.xml @@ -257,8 +257,8 @@
- - + +
diff --git a/conf/airframes/examples/booz2.xml b/conf/airframes/examples/booz2.xml index dca8389581..e93ccf9d2c 100644 --- a/conf/airframes/examples/booz2.xml +++ b/conf/airframes/examples/booz2.xml @@ -194,7 +194,7 @@
- +
diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml b/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml index 36e979ea40..f2e83c928f 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_hexa_mkk.xml @@ -230,7 +230,7 @@
- +
diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml b/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml index 40786c6218..d8f1ef72fb 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_okto_mkk.xml @@ -233,7 +233,7 @@
- +
diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml b/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml index 0b31cd058e..6eab4e9e70 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_quad_mkk.xml @@ -222,7 +222,7 @@
- +
diff --git a/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml b/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml index 9f3d371545..0f79321840 100644 --- a/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml +++ b/conf/airframes/examples/krooz_sd/krooz_sd_quad_pwm.xml @@ -217,7 +217,7 @@
- +
diff --git a/conf/airframes/examples/lisa_asctec.xml b/conf/airframes/examples/lisa_asctec.xml index 75f60ddfdf..f9c6dc3e8e 100644 --- a/conf/airframes/examples/lisa_asctec.xml +++ b/conf/airframes/examples/lisa_asctec.xml @@ -178,7 +178,7 @@
- +
diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index 2d507056ae..d9b8144442 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -200,7 +200,7 @@
- +
diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml index 90932d24e5..06a69c6cf2 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml @@ -204,7 +204,7 @@
- +
diff --git a/conf/airframes/examples/quadrotor_lisa_m_mkk.xml b/conf/airframes/examples/quadrotor_lisa_m_mkk.xml index 42fcb6b0d0..614240efa6 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_mkk.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_mkk.xml @@ -193,7 +193,7 @@
- +
diff --git a/conf/airframes/examples/quadrotor_mlkf.xml b/conf/airframes/examples/quadrotor_mlkf.xml index 7a858bf286..2f63c01469 100644 --- a/conf/airframes/examples/quadrotor_mlkf.xml +++ b/conf/airframes/examples/quadrotor_mlkf.xml @@ -204,7 +204,7 @@
- + diff --git a/conf/airframes/examples/quadrotor_navgo.xml b/conf/airframes/examples/quadrotor_navgo.xml index 143f5fb701..98df961abd 100644 --- a/conf/airframes/examples/quadrotor_navgo.xml +++ b/conf/airframes/examples/quadrotor_navgo.xml @@ -265,7 +265,7 @@
- +
diff --git a/conf/airframes/examples/quadshot_asp21_spektrum.xml b/conf/airframes/examples/quadshot_asp21_spektrum.xml index 1c3262b131..819109bcfa 100644 --- a/conf/airframes/examples/quadshot_asp21_spektrum.xml +++ b/conf/airframes/examples/quadshot_asp21_spektrum.xml @@ -231,7 +231,7 @@ More information on the Quadshot can be found at transition-robotics.com -->
- +
diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index 877f496e66..8a1447d69c 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -237,7 +237,7 @@
- +
diff --git a/conf/airframes/obsolete/ENAC/g1_vision.xml b/conf/airframes/obsolete/ENAC/g1_vision.xml index 71ca37d27a..d24b588c2e 100644 --- a/conf/airframes/obsolete/ENAC/g1_vision.xml +++ b/conf/airframes/obsolete/ENAC/g1_vision.xml @@ -194,7 +194,7 @@
- +
diff --git a/conf/airframes/obsolete/Poine/booz2_a1.xml b/conf/airframes/obsolete/Poine/booz2_a1.xml index 8d66978f1b..5823e29e03 100644 --- a/conf/airframes/obsolete/Poine/booz2_a1.xml +++ b/conf/airframes/obsolete/Poine/booz2_a1.xml @@ -189,7 +189,7 @@
- +
diff --git a/conf/airframes/obsolete/Poine/booz2_a7.xml b/conf/airframes/obsolete/Poine/booz2_a7.xml index 59f3bb2082..d3f23c31fd 100644 --- a/conf/airframes/obsolete/Poine/booz2_a7.xml +++ b/conf/airframes/obsolete/Poine/booz2_a7.xml @@ -201,7 +201,7 @@
- +
diff --git a/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml b/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml index 4061167138..10b61e41a0 100644 --- a/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml +++ b/conf/airframes/obsolete/UofAdelaide/A1000_BOOZ.xml @@ -263,7 +263,7 @@ second attempt
- +
diff --git a/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml b/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml index 564e7dbcc4..406d6de2c0 100644 --- a/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml +++ b/conf/airframes/obsolete/UofAdelaide/A1000_NOVA.xml @@ -216,7 +216,7 @@
- +
diff --git a/conf/airframes/obsolete/UofAdelaide/booz2_a1000.xml b/conf/airframes/obsolete/UofAdelaide/booz2_a1000.xml index 06ea8ce8ad..82f499852b 100644 --- a/conf/airframes/obsolete/UofAdelaide/booz2_a1000.xml +++ b/conf/airframes/obsolete/UofAdelaide/booz2_a1000.xml @@ -265,7 +265,7 @@ second attempt
- +
diff --git a/conf/airframes/obsolete/booz2_a1p.xml b/conf/airframes/obsolete/booz2_a1p.xml index f5906c89d6..18ff3d98f8 100644 --- a/conf/airframes/obsolete/booz2_a1p.xml +++ b/conf/airframes/obsolete/booz2_a1p.xml @@ -193,7 +193,7 @@
- +
diff --git a/conf/airframes/obsolete/booz2_s1.xml b/conf/airframes/obsolete/booz2_s1.xml index 17b8eaf5b5..4cf6bb4bbe 100644 --- a/conf/airframes/obsolete/booz2_s1.xml +++ b/conf/airframes/obsolete/booz2_s1.xml @@ -180,7 +180,7 @@
- +
diff --git a/conf/airframes/obsolete/example_heli_lisam.xml b/conf/airframes/obsolete/example_heli_lisam.xml index e3dbdfd842..79e8d519ac 100644 --- a/conf/airframes/obsolete/example_heli_lisam.xml +++ b/conf/airframes/obsolete/example_heli_lisam.xml @@ -217,7 +217,7 @@ AP_MODE_NAV
- +
diff --git a/conf/airframes/obsolete/mm/rotor/qmk1.xml b/conf/airframes/obsolete/mm/rotor/qmk1.xml index 8066ee667d..37b3b6c07a 100644 --- a/conf/airframes/obsolete/mm/rotor/qmk1.xml +++ b/conf/airframes/obsolete/mm/rotor/qmk1.xml @@ -174,7 +174,7 @@
- +
diff --git a/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_l_mkk.xml b/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_l_mkk.xml index 93991b0de9..5d1b3e397d 100644 --- a/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_l_mkk.xml +++ b/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_l_mkk.xml @@ -218,7 +218,7 @@
- +
diff --git a/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_1_pwm.xml b/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_1_pwm.xml index 7fabac6e96..5343031357 100644 --- a/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_1_pwm.xml +++ b/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_1_pwm.xml @@ -180,7 +180,7 @@
- +
diff --git a/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_2_pwm.xml b/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_2_pwm.xml index ed99bdefa5..2ba487a784 100644 --- a/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_2_pwm.xml +++ b/conf/airframes/obsolete/mm/rotor/quadrotor_lisa_m_2_pwm.xml @@ -187,7 +187,7 @@
- +
From 0959c0428ffa1e07469cd308e2a394eeedbe5de2 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 8 Aug 2013 19:41:52 +0200 Subject: [PATCH 089/309] [conf] ground alt for versatile flight plans --- conf/flight_plans/versatile.xml | 2 +- conf/flight_plans/versatile_airspeed.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/conf/flight_plans/versatile.xml b/conf/flight_plans/versatile.xml index dcf3d90931..f08147adaa 100644 --- a/conf/flight_plans/versatile.xml +++ b/conf/flight_plans/versatile.xml @@ -1,6 +1,6 @@ - +
#include "subsystems/datalink/datalink.h"
diff --git a/conf/flight_plans/versatile_airspeed.xml b/conf/flight_plans/versatile_airspeed.xml index 1427adf72c..d98264c6e6 100644 --- a/conf/flight_plans/versatile_airspeed.xml +++ b/conf/flight_plans/versatile_airspeed.xml @@ -1,6 +1,6 @@ - +
#include "firmwares/fixedwing/guidance/energy_ctrl.h" #include "subsystems/datalink/datalink.h" From 7f73f615fda4c355ace0ae03e3f2cba2d26be210 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Aug 2013 15:24:21 +0200 Subject: [PATCH 090/309] [nps] set ahrs in float --- sw/simulator/nps/nps_autopilot_fixedwing.c | 18 +++++++++--------- sw/simulator/nps/nps_autopilot_rotorcraft.c | 17 ++++++++--------- 2 files changed, 17 insertions(+), 18 deletions(-) diff --git a/sw/simulator/nps/nps_autopilot_fixedwing.c b/sw/simulator/nps/nps_autopilot_fixedwing.c index 09bed64681..5cf695e12c 100644 --- a/sw/simulator/nps/nps_autopilot_fixedwing.c +++ b/sw/simulator/nps/nps_autopilot_fixedwing.c @@ -38,6 +38,8 @@ #include "nps_sensors.h" #include "nps_radio_control.h" +#include "nps_fdm.h" + #include "subsystems/radio_control.h" #include "subsystems/imu.h" #include "subsystems/sensors/baro.h" @@ -48,6 +50,7 @@ #include "subsystems/commands.h" + struct NpsAutopilot autopilot; bool_t nps_bypass_ahrs; @@ -130,17 +133,14 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { } -#include "nps_fdm.h" -#include "subsystems/ahrs.h" -#include "math/pprz_algebra.h" void sim_overwrite_ahrs(void) { - struct Int32Quat quat; - QUAT_BFP_OF_REAL(quat, fdm.ltp_to_body_quat); - stateSetNedToBodyQuat_i(&quat); + struct FloatQuat quat_f; + QUAT_COPY(quat_f, fdm.ltp_to_body_quat); + stateSetNedToBodyQuat_f(&quat_f); - struct Int32Rates rates; - RATES_BFP_OF_REAL(rates, fdm.body_ecef_rotvel); - stateSetBodyRates_i(&rates); + struct FloatRates rates_f; + RATES_COPY(rates_f, fdm.body_ecef_rotvel); + stateSetBodyRates_f(&rates_f); } diff --git a/sw/simulator/nps/nps_autopilot_rotorcraft.c b/sw/simulator/nps/nps_autopilot_rotorcraft.c index f87e000747..b309bf37b9 100644 --- a/sw/simulator/nps/nps_autopilot_rotorcraft.c +++ b/sw/simulator/nps/nps_autopilot_rotorcraft.c @@ -24,6 +24,8 @@ #include "firmwares/rotorcraft/main.h" #include "nps_sensors.h" #include "nps_radio_control.h" +#include "nps_fdm.h" + #include "subsystems/radio_control.h" #include "subsystems/imu.h" #include "subsystems/sensors/baro.h" @@ -107,17 +109,14 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { } -#include "nps_fdm.h" -#include "subsystems/ahrs.h" -#include "math/pprz_algebra.h" void sim_overwrite_ahrs(void) { - struct Int32Quat quat; - QUAT_BFP_OF_REAL(quat, fdm.ltp_to_body_quat); - stateSetNedToBodyQuat_i(&quat); + struct FloatQuat quat_f; + QUAT_COPY(quat_f, fdm.ltp_to_body_quat); + stateSetNedToBodyQuat_f(&quat_f); - struct Int32Rates rates; - RATES_BFP_OF_REAL(rates, fdm.body_ecef_rotvel); - stateSetBodyRates_i(&rates); + struct FloatRates rates_f; + RATES_COPY(rates_f, fdm.body_ecef_rotvel); + stateSetBodyRates_f(&rates_f); } From cf574d8a2ac0b812bf970db1217801422727108c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Aug 2013 15:27:07 +0200 Subject: [PATCH 091/309] [fixedwing][nps] fix for ahrs and bypass --- sw/airborne/firmwares/fixedwing/main_ap.c | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 2450b05e97..b772c2ca74 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -556,7 +556,7 @@ void sensors_task( void ) { #endif // USE_IMU //FIXME: this is just a kludge -#if USE_AHRS && defined SITL +#if USE_AHRS && defined SITL && !USE_NPS ahrs_propagate(); #endif @@ -702,10 +702,6 @@ static inline void on_gyro_event( void ) { ahrs_propagate(); ahrs_update_accel(); -#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP - new_ins_attitude = 1; -#endif - #else //PERIODIC_FREQUENCY static uint8_t _reduced_propagation_rate = 0; static uint8_t _reduced_correction_rate = 0; @@ -718,6 +714,7 @@ static inline void on_gyro_event( void ) { _reduced_propagation_rate++; if (_reduced_propagation_rate < (PERIODIC_FREQUENCY / AHRS_PROPAGATE_FREQUENCY)) { + return; } else { @@ -739,13 +736,17 @@ static inline void on_gyro_event( void ) { ImuScaleAccel(imu); ahrs_update_accel(); } - -#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP - new_ins_attitude = 1; -#endif } #endif //PERIODIC_FREQUENCY +#if defined SITL && USE_NPS + if (nps_bypass_ahrs) sim_overwrite_ahrs(); +#endif + +#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP + new_ins_attitude = 1; +#endif + } static inline void on_mag_event(void) From 9d74943fc0d5160e0d380830689720f83e4797b1 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Aug 2013 15:48:38 +0200 Subject: [PATCH 092/309] [conf] udev rules: add dfu devices to plugdev group --- conf/system/udev/rules/50-paparazzi.rules | 3 +++ 1 file changed, 3 insertions(+) diff --git a/conf/system/udev/rules/50-paparazzi.rules b/conf/system/udev/rules/50-paparazzi.rules index 4a8f7ef37e..6d50b0b908 100644 --- a/conf/system/udev/rules/50-paparazzi.rules +++ b/conf/system/udev/rules/50-paparazzi.rules @@ -27,6 +27,9 @@ ATTRS{idVendor}=="0403", ATTRS{idProduct}=="cff8", GROUP="plugdev" # FTDI 2232 based jtag for Lisa/L and usb upload ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0666", GROUP="plugdev" +# dfu devices +ATTRS{idVendor}=="0483", ATTRS{idProduct}=="df11", MODE="0666", GROUP="plugdev" + # all (fake VID 0x7070) LPCUSB devices (access through libusb) ATTRS{idVendor}=="7070", GROUP="plugdev" From bfb05205022b40a9ef28047d4dca1daab2bfa68d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Aug 2013 16:50:22 +0200 Subject: [PATCH 093/309] [ahrs] remove old ekf/lkf algos --- .../subsystems/rotorcraft/ahrs_lkf.makefile | 13 - .../subsystems/rotorcraft/fdm_jsbsim.makefile | 16 - conf/settings/estimation/booz2_ahrs_lkf.xml | 14 - sw/airborne/firmwares/rotorcraft/telemetry.h | 66 -- sw/airborne/subsystems/ahrs/ahrs_float_ekf.c | 164 ---- sw/airborne/subsystems/ahrs/ahrs_float_ekf.h | 35 - sw/airborne/subsystems/ahrs/ahrs_float_lkf.c | 857 ------------------ sw/airborne/subsystems/ahrs/ahrs_float_lkf.h | 76 -- 8 files changed, 1241 deletions(-) delete mode 100644 conf/firmwares/subsystems/rotorcraft/ahrs_lkf.makefile delete mode 100644 conf/settings/estimation/booz2_ahrs_lkf.xml delete mode 100644 sw/airborne/subsystems/ahrs/ahrs_float_ekf.c delete mode 100644 sw/airborne/subsystems/ahrs/ahrs_float_ekf.h delete mode 100644 sw/airborne/subsystems/ahrs/ahrs_float_lkf.c delete mode 100644 sw/airborne/subsystems/ahrs/ahrs_float_lkf.h diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_lkf.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_lkf.makefile deleted file mode 100644 index 2c942a23cf..0000000000 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_lkf.makefile +++ /dev/null @@ -1,13 +0,0 @@ -# -# Error State Space Kalman filter for attitude estimation -# - -ap.CFLAGS += -DUSE_AHRS_LKF -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED) -ap.srcs += $(SRC_SUBSYSTEMS)/ahrs.c -ap.srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_aligner.c -ap.srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_float_lkf.c - -nps.CFLAGS += -DUSE_AHRS_LKF -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED) -nps.srcs += $(SRC_SUBSYSTEMS)/ahrs.c -nps.srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_aligner.c -nps.srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_float_lkf.c diff --git a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile index 4785cbc075..6304c5a47e 100644 --- a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile @@ -103,12 +103,6 @@ nps.srcs += $(SRC_FIRMWARE)/autopilot.c nps.srcs += state.c -# -# in makefile section of airframe xml -# include $(CFG_BOOZ)/subsystems/booz2_ahrs_lkf.makefile -# or -# include $(CFG_BOOZ)/subsystems/booz2_ahrs_cmpl.makefile -# nps.srcs += $(SRC_FIRMWARE)/stabilization.c nps.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_rate.c @@ -121,16 +115,6 @@ nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v.c nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_ref.c nps.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_adapt.c -# -# INS choice -# -# include subsystems/rotorcraft/ins.makefile -# or -# include subsystems/rotorcraft/ins_extended.makefile -# -# extra: -# include subsystems/rotorcraft/ins_hff.makefile -# nps.srcs += $(SRC_FIRMWARE)/navigation.c nps.srcs += $(SRC_SUBSYSTEMS)/navigation/common_flight_plan.c diff --git a/conf/settings/estimation/booz2_ahrs_lkf.xml b/conf/settings/estimation/booz2_ahrs_lkf.xml deleted file mode 100644 index a49a4f318b..0000000000 --- a/conf/settings/estimation/booz2_ahrs_lkf.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index d50d022a38..48a914b5f5 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -396,72 +396,6 @@ #define PERIODIC_SEND_AHRS_GYRO_BIAS_INT(_trans, _dev) {} #endif -#if USE_AHRS_LKF -#include "subsystems/ahrs.h" -#include "ahrs/ahrs_float_lkf.h" -#define PERIODIC_SEND_AHRS_LKF(_trans, _dev) { \ - DOWNLINK_SEND_AHRS_LKF(&bafl_eulers.phi, \ - _trans, _dev, \ - &bafl_eulers.theta, \ - &bafl_eulers.psi, \ - &bafl_quat.qi, \ - &bafl_quat.qx, \ - &bafl_quat.qy, \ - &bafl_quat.qz, \ - &bafl_rates.p, \ - &bafl_rates.q, \ - &bafl_rates.r, \ - &bafl_accel_measure.x, \ - &bafl_accel_measure.y, \ - &bafl_accel_measure.z, \ - &bafl_mag.x, \ - &bafl_mag.y, \ - &bafl_mag.z); \ - } -#define PERIODIC_SEND_AHRS_LKF_DEBUG(_trans, _dev) { \ - DOWNLINK_SEND_AHRS_LKF_DEBUG(_trans, _dev, \ - &bafl_X[0], \ - &bafl_X[1], \ - &bafl_X[2], \ - &bafl_bias.p, \ - &bafl_bias.q, \ - &bafl_bias.r, \ - &bafl_qnorm, \ - &bafl_phi_accel, \ - &bafl_theta_accel, \ - &bafl_P[0][0], \ - &bafl_P[1][1], \ - &bafl_P[2][2], \ - &bafl_P[3][3], \ - &bafl_P[4][4], \ - &bafl_P[5][5]); \ - } -#define PERIODIC_SEND_AHRS_LKF_ACC_DBG(_trans, _dev) { \ - DOWNLINK_SEND_AHRS_LKF_ACC_DBG(_trans, _dev, \ - &bafl_q_a_err.qi, \ - &bafl_q_a_err.qx, \ - &bafl_q_a_err.qy, \ - &bafl_q_a_err.qz, \ - &bafl_b_a_err.p, \ - &bafl_b_a_err.q, \ - &bafl_b_a_err.r); \ - } -#define PERIODIC_SEND_AHRS_LKF_MAG_DBG(_trans, _dev) { \ - DOWNLINK_SEND_AHRS_LKF_MAG_DBG(_trans, _dev, \ - &bafl_q_m_err.qi, \ - &bafl_q_m_err.qx, \ - &bafl_q_m_err.qy, \ - &bafl_q_m_err.qz, \ - &bafl_b_m_err.p, \ - &bafl_b_m_err.q, \ - &bafl_b_m_err.r); \ - } -#else -#define PERIODIC_SEND_AHRS_LKF(_trans, _dev) {} -#define PERIODIC_SEND_AHRS_LKF_DEBUG(_trans, _dev) {} -#define PERIODIC_SEND_AHRS_LKF_MAG_DBG(_trans, _dev) {} -#define PERIODIC_SEND_AHRS_LKF_ACC_DBG(_trans, _dev) {} -#endif #if defined STABILIZATION_ATTITUDE_TYPE_QUAT && defined STABILIZATION_ATTITUDE_TYPE_INT #define PERIODIC_SEND_AHRS_REF_QUAT(_trans, _dev) { \ diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_ekf.c b/sw/airborne/subsystems/ahrs/ahrs_float_ekf.c deleted file mode 100644 index 6ec8fb4eaf..0000000000 --- a/sw/airborne/subsystems/ahrs/ahrs_float_ekf.c +++ /dev/null @@ -1,164 +0,0 @@ -/* - * Copyright (C) 2008-2009 Antoine Drouin - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - -#include "math/pprz_algebra_float.h" - -/* our estimated attitude */ -struct FloatQuat bafe_quat; -/* our estimated gyro biases */ -struct FloatRates bafe_bias; -/* we get unbiased body rates as byproduct */ -struct FloatRates bafe_rates; -/* maintain a euler angles representation */ -struct FloatEulers bafe_eulers; -/* maintains a rotation matrix representation */ -struct FloatEulers bafe_dcm; -/* time derivative of our quaternion */ -struct FloatQuat bafe_qdot; - -#define BAFE_SSIZE 7 -/* covariance matrix and its time derivative */ -float bafe_P[BAFE_SSIZE][BAFE_SSIZE]; -float bafe_Pdot[BAFE_SSIZE][BAFE_SSIZE]; - -/* - * F represents the Jacobian of the derivative of the system with respect - * its states. We do not allocate the bottom three rows since we know that - * the derivatives of bias_dot are all zero. - */ -float bafe_F[4][7]; - -/* - * Kalman filter variables. - */ -float bafe_PHt[7]; -float bafe_K[7]; -float bafe_E; -/* - * H represents the Jacobian of the measurements of the attitude - * with respect to the states of the filter. We do not allocate the bottom - * three rows since we know that the attitude measurements have no - * relationship to gyro bias. - */ -float bafe_H[4]; -/* temporary variable used during state covariance update */ -float bafe_FP[4][7]; - -/* - * Q is our estimate noise variance. It is supposed to be an NxN - * matrix, but with elements only on the diagonals. Additionally, - * since the quaternion has no expected noise (we can't directly measure - * it), those are zero. For the gyro, we expect around 5 deg/sec noise, - * which is 0.08 rad/sec. The variance is then 0.08^2 ~= 0.0075. - */ -/* I measured about 0.009 rad/s noise */ -#define bafe_Q_gyro 8e-03 - -/* - * R is our measurement noise estimate. Like Q, it is supposed to be - * an NxN matrix with elements on the diagonals. However, since we can - * not directly measure the gyro bias, we have no estimate for it. - * We only have an expected noise in the pitch and roll accelerometers - * and in the compass. - */ -#define BAFE_R_PHI 1.3 * 1.3 -#define BAFE_R_THETA 1.3 * 1.3 -#define BAFE_R_PSI 2.5 * 2.5 - -#ifndef BAFE_DT -#define BAFE_DT (1./512.) -#endif - -extern void ahrs_init(void); -extern void ahrs_align(void); - - -/* - * Propagate our dynamic system - * - * quat_dot = Wxq(pqr) * quat - * bias_dot = 0 - * - * Wxq is the quaternion omega matrix: - * - * [ 0, -p, -q, -r ] - * 1/2 * [ p, 0, r, -q ] - * [ q, -r, 0, p ] - * [ r, q, -p, 0 ] - * - * - * - * - * [ 0 -p -q -r q1 q2 q3] - * F = 1/2 * [ p 0 r -q -q0 q3 -q2] - * [ q -r 0 p -q3 -q0 q1] - * [ r q -p 0 q2 -q1 -q0] - * [ 0 0 0 0 0 0 0] - * [ 0 0 0 0 0 0 0] - * [ 0 0 0 0 0 0 0] - * - */ - -void ahrs_propagate(void) { - /* compute unbiased rates */ - RATES_FLOAT_OF_BFP(bafe_rates, imu.gyro); - RATES_SUB(bafe_rates, bafe_bias); - - /* compute F - F is only needed later on to update the state covariance P. - However, its [0:3][0:3] region is actually the Wxq(pqr) which is needed to - compute the time derivative of the quaternion, so we compute F now - */ - - /* Fill in Wxq(pqr) into F */ - bafe_F[0][0] = bafe_F[1][1] = bafe_F[2][2] = bafe_F[3][3] = 0; - bafe_F[1][0] = bafe_F[2][3] = bafe_rates.p * 0.5; - bafe_F[2][0] = bafe_F[3][1] = bafe_rates.q * 0.5; - bafe_F[3][0] = bafe_F[1][2] = bafe_rates.r * 0.5; - - bafe_F[0][1] = bafe_F[3][2] = -bafe_F[1][0]; - bafe_F[0][2] = bafe_F[1][3] = -bafe_F[2][0]; - bafe_F[0][3] = bafe_F[2][1] = -bafe_F[3][0]; - /* Fill in [4:6][0:3] region */ - bafe_F[0][4] = bafe_F[2][6] = bafe_quat.qx * 0.5; - bafe_F[0][5] = bafe_F[3][4] = bafe_quat.qy * 0.5; - bafe_F[0][6] = bafe_F[1][5] = bafe_quat.qz * 0.5; - - bafe_F[1][4] = bafe_F[2][5] = bafe_F[3][6] = bafe_quat.qi * -0.5; - bafe_F[3][5] = -bafe_F[0][4]; - bafe_F[1][6] = -bafe_F[0][5]; - bafe_F[2][4] = -bafe_F[0][6]; - /* quat_dot = Wxq(pqr) * quat */ - bafe_qdot.qi= bafe_F[0][1]*bafe_quat.qx+bafe_F[0][2]*bafe_quat.qy+bafe_F[0][3] * bafe_quat.qz; - bafe_qdot.qx= bafe_F[1][0]*bafe_quat.qi +bafe_F[1][2]*bafe_quat.qy+bafe_F[1][3] * bafe_quat.qz; - bafe_qdot.qy= bafe_F[2][0]*bafe_quat.qi+bafe_F[2][1]*bafe_quat.qx +bafe_F[2][3] * bafe_quat.qz; - bafe_qdot.qz= bafe_F[3][0]*bafe_quat.qi+bafe_F[3][1]*bafe_quat.qx+bafe_F[3][2]*bafe_quat.qy ; - /* propagate quaternion */ - bafe_quat.qi += bafe_qdot.qi * BAFE_DT; - bafe_quat.qx += bafe_qdot.qx * BAFE_DT; - bafe_quat.qy += bafe_qdot.qy * BAFE_DT; - bafe_quat.qz += bafe_qdot.qz * BAFE_DT; - - -} - - -extern void ahrs_update(void); diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_ekf.h b/sw/airborne/subsystems/ahrs/ahrs_float_ekf.h deleted file mode 100644 index 6d173227ba..0000000000 --- a/sw/airborne/subsystems/ahrs/ahrs_float_ekf.h +++ /dev/null @@ -1,35 +0,0 @@ -/* - * Copyright (C) 2008-2009 Antoine Drouin - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - -#ifndef AHRS_FLOAT_EKF_H -#define AHRS_FLOAT_EKF_H - - - -extern void ahrs_init(void); -extern void ahrs_align(void); -extern void ahrs_propagate(void); -extern void ahrs_update(void); - - - - -#endif /* AHRS_FLOAT_EKF_H */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_lkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_lkf.c deleted file mode 100644 index e3e38086dc..0000000000 --- a/sw/airborne/subsystems/ahrs/ahrs_float_lkf.c +++ /dev/null @@ -1,857 +0,0 @@ -/* - * Copyright (C) 2009 Felix Ruess - * Copyright (C) 2009 Antoine Drouin - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - -/** - * @file subsystems/ahrs/ahrs_float_lkf.c - * - * Linearized Kalman Filter for attitude estimation. - * - */ - -#include "ahrs_float_lkf.h" - -#include "subsystems/imu.h" -#include "subsystems/ahrs/ahrs_aligner.h" - -#include "generated/airframe.h" -#include "math/pprz_algebra_float.h" - -#include - - -#define BAFL_DEBUG - -static void ahrs_do_update_accel(void); -static void ahrs_do_update_mag(void); - - -/* our estimated attitude (ltp <-> imu) */ -struct FloatQuat bafl_quat; -/* our estimated gyro biases */ -struct FloatRates bafl_bias; -/* we get unbiased body rates as byproduct */ -struct FloatRates bafl_rates; -/* maintain a euler angles representation */ -struct FloatEulers bafl_eulers; -/* C n->b rotation matrix representation */ -struct FloatRMat bafl_dcm; - -/* estimated attitude errors from accel update */ -struct FloatQuat bafl_q_a_err; -/* estimated attitude errors from mag update */ -struct FloatQuat bafl_q_m_err; -/* our estimated gyro bias errors from accel update */ -struct FloatRates bafl_b_a_err; -/* our estimated gyro bias errors from mag update */ -struct FloatRates bafl_b_m_err; -/* temporary quaternion */ -struct FloatQuat bafl_qtemp; -/* correction quaternion of strapdown computation */ -struct FloatQuat bafl_qr; -/* norm of attitude quaternion */ -float bafl_qnorm; - -/* pseude measured angles for debug */ -float bafl_phi_accel; -float bafl_theta_accel; - -#ifndef BAFL_SSIZE -#define BAFL_SSIZE 6 -#endif -/* error covariance matrix */ -float bafl_P[BAFL_SSIZE][BAFL_SSIZE]; -/* filter state */ -float bafl_X[BAFL_SSIZE]; - -/* - * F represents the Jacobian of the derivative of the system with respect - * its states. We do not allocate the bottom three rows since we know that - * the derivatives of bias_dot are all zero. - */ -float bafl_F[3][3]; -/* - * T represents the discrete state transition matrix - * T = e^(F * dt) - */ -float bafl_T[6][6]; - -/* - * Kalman filter variables. - */ -float bafl_Pprio[BAFL_SSIZE][BAFL_SSIZE]; -/* temporary variable used during state covariance update */ -float bafl_tempP[BAFL_SSIZE][BAFL_SSIZE]; -float bafl_K[6][3]; -float bafl_tempK[6][3]; -float bafl_S[3][3]; -float bafl_tempS[3][6]; -float bafl_invS[3][3]; -struct FloatVect3 bafl_ya; -struct FloatVect3 bafl_ym; - -/* - * H represents the Jacobian of the measurements of the attitude - * with respect to the states of the filter. We do not allocate the bottom - * three rows since we know that the attitude measurements have no - * relationship to gyro bias. - * The last three columns always stay zero. - */ -float bafl_H[3][3]; - -/* low pass of accel measurements */ -struct FloatVect3 bafl_accel_measure; -struct FloatVect3 bafl_accel_last; - -struct FloatVect3 bafl_mag; - -/* temporary variables for the strapdown computation */ -float bafl_qom[4][4]; - -#define BAFL_g 9.81 - -#define BAFL_hx 1.0 -#define BAFL_hy 0.0 -#define BAFL_hz 1.0 -struct FloatVect3 bafl_h; - -/* - * Q is our estimate noise variance. It is supposed to be an NxN - * matrix, but with elements only on the diagonals. Additionally, - * since the quaternion has no expected noise (we can't directly measure - * it), those are zero. For the gyro, we expect around 5 deg/sec noise, - * which is 0.08 rad/sec. The variance is then 0.08^2 ~= 0.0075. - */ -/* I measured about 0.009 rad/s noise */ -#define BAFL_Q_GYRO 1e-04 -#define BAFL_Q_ATT 0 -float bafl_Q_gyro; -float bafl_Q_att; - -/* - * R is our measurement noise estimate. Like Q, it is supposed to be - * an NxN matrix with elements on the diagonals. However, since we can - * not directly measure the gyro bias, we have no estimate for it. - * We only have an expected noise in the pitch and roll accelerometers - * and in the compass. - */ -#define BAFL_SIGMA_ACCEL 1000.0 -#define BAFL_SIGMA_MAG 20. -float bafl_sigma_accel; -float bafl_sigma_mag; -float bafl_R_accel; -float bafl_R_mag; - -#ifndef BAFL_DT -#define BAFL_DT (1./512.) -#endif - - -#define FLOAT_MAT33_INVERT(_mo, _mi) { \ - float _det = 0.; \ - _det = _mi[0][0] * (_mi[2][2] * _mi[1][1] - _mi[2][1] * _mi[1][2]) \ - - _mi[1][0] * (_mi[2][2] * _mi[0][1] - _mi[2][1] * _mi[0][2]) \ - + _mi[2][0] * (_mi[1][2] * _mi[0][1] - _mi[1][1] * _mi[0][2]); \ - if (_det != 0.) { /* ? test for zero? */ \ - _mo[0][0] = (_mi[1][1] * _mi[2][2] - _mi[1][2] * _mi[2][1]) / _det; \ - _mo[0][1] = (_mi[0][2] * _mi[2][1] - _mi[0][1] * _mi[2][2]) / _det; \ - _mo[0][2] = (_mi[0][1] * _mi[1][2] - _mi[0][2] * _mi[1][1]) / _det; \ - \ - _mo[1][0] = (_mi[1][2] * _mi[2][0] - _mi[1][0] * _mi[2][2]) / _det; \ - _mo[1][1] = (_mi[0][0] * _mi[2][2] - _mi[0][2] * _mi[2][0]) / _det; \ - _mo[1][2] = (_mi[0][2] * _mi[1][0] - _mi[0][0] * _mi[1][2]) / _det; \ - \ - _mo[2][0] = (_mi[1][0] * _mi[2][1] - _mi[1][1] * _mi[2][0]) / _det; \ - _mo[2][1] = (_mi[0][1] * _mi[2][0] - _mi[0][0] * _mi[2][1]) / _det; \ - _mo[2][2] = (_mi[0][0] * _mi[1][1] - _mi[0][1] * _mi[1][0]) / _det; \ - } else { \ - printf("ERROR! Not invertible!\n"); \ - for (int _i=0; _i<3; _i++) { \ - for (int _j=0; _j<3; _j++) { \ - _mo[_i][_j] = 0.0; \ - } \ - } \ - } \ - } - -#define AHRS_TO_BFP() { \ - /* IMU rate */ \ - RATES_BFP_OF_REAL(ahrs.imu_rate, bafl_rates); \ - /* LTP to IMU eulers */ \ - EULERS_BFP_OF_REAL(ahrs.ltp_to_imu_euler, bafl_eulers); \ - /* LTP to IMU quaternion */ \ - QUAT_BFP_OF_REAL(ahrs.ltp_to_imu_quat, bafl_quat); \ - /* LTP to IMU rotation matrix */ \ - RMAT_BFP_OF_REAL(ahrs.ltp_to_imu_rmat, bafl_dcm); \ - } - -#define AHRS_LTP_TO_BODY() { \ - /* Compute LTP to BODY quaternion */ \ - INT32_QUAT_COMP_INV(ahrs.ltp_to_body_quat, ahrs.ltp_to_imu_quat, imu.body_to_imu_quat); \ - /* Compute LTP to BODY rotation matrix */ \ - INT32_RMAT_COMP_INV(ahrs.ltp_to_body_rmat, ahrs.ltp_to_imu_rmat, imu.body_to_imu_rmat); \ - /* compute LTP to BODY eulers */ \ - INT32_EULERS_OF_RMAT(ahrs.ltp_to_body_euler, ahrs.ltp_to_body_rmat); \ - /* compute body rates */ \ - INT32_RMAT_TRANSP_RATEMULT(ahrs.body_rate, imu.body_to_imu_rmat, ahrs.imu_rate); \ - } - - -void ahrs_init(void) { - int i, j; - - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_T[i][j] = 0.; - bafl_P[i][j] = 0.; - } - /* Insert the diagonal elements of the T-Matrix. These will never change. */ - bafl_T[i][i] = 1.0; - /* initial covariance values */ - if (i<3) { - bafl_P[i][i] = 1.0; - } else { - bafl_P[i][i] = 0.1; - } - } - - FLOAT_QUAT_ZERO(bafl_quat); - - ahrs.status = AHRS_UNINIT; - INT_EULERS_ZERO(ahrs.ltp_to_body_euler); - INT_EULERS_ZERO(ahrs.ltp_to_imu_euler); - INT32_QUAT_ZERO(ahrs.ltp_to_body_quat); - INT32_QUAT_ZERO(ahrs.ltp_to_imu_quat); - INT_RATES_ZERO(ahrs.body_rate); - INT_RATES_ZERO(ahrs.imu_rate); - - ahrs_float_lkf_SetRaccel(BAFL_SIGMA_ACCEL); - ahrs_float_lkf_SetRmag(BAFL_SIGMA_MAG); - - bafl_Q_att = BAFL_Q_ATT; - bafl_Q_gyro = BAFL_Q_GYRO; - - FLOAT_VECT3_ASSIGN(bafl_h, BAFL_hx,BAFL_hy, BAFL_hz); - -} - -void ahrs_align(void) { - RATES_FLOAT_OF_BFP(bafl_bias, ahrs_aligner.lp_gyro); - ACCELS_FLOAT_OF_BFP(bafl_accel_measure, ahrs_aligner.lp_accel); - ahrs.status = AHRS_RUNNING; -} - -static inline void ahrs_lowpass_accel(void) { - // get latest measurement - ACCELS_FLOAT_OF_BFP(bafl_accel_last, imu.accel); - // low pass it - VECT3_ADD(bafl_accel_measure, bafl_accel_last); - VECT3_SDIV(bafl_accel_measure, bafl_accel_measure, 2); - -#ifdef BAFL_DEBUG - bafl_phi_accel = atan2f( -bafl_accel_measure.y, -bafl_accel_measure.z); - bafl_theta_accel = atan2f(bafl_accel_measure.x, sqrtf(bafl_accel_measure.y*bafl_accel_measure.y + bafl_accel_measure.z*bafl_accel_measure.z)); -#endif -} - -/* - * Propagate our dynamic system in time - * - * Run the strapdown computation and the predict step of the filter - * - * - * quat_dot = Wxq(pqr) * quat - * bias_dot = 0 - * - * Wxq is the quaternion omega matrix: - * - * [ 0, -p, -q, -r ] - * 1/2 * [ p, 0, r, -q ] - * [ q, -r, 0, p ] - * [ r, q, -p, 0 ] - * - */ -void ahrs_propagate(void) { - int i, j, k; - - ahrs_lowpass_accel(); - - /* compute unbiased rates */ - RATES_FLOAT_OF_BFP(bafl_rates, imu.gyro); - RATES_SUB(bafl_rates, bafl_bias); - - - /* run strapdown computation - * - */ - - /* multiplicative quaternion update */ - /* compute correction quaternion */ - QUAT_ASSIGN(bafl_qr, 1., bafl_rates.p * BAFL_DT / 2, bafl_rates.q * BAFL_DT / 2, bafl_rates.r * BAFL_DT / 2); - /* normalize it. maybe not necessary?? */ - float q_sq; - q_sq = (bafl_qr.qx * bafl_qr.qx +bafl_qr.qy * bafl_qr.qy + bafl_qr.qz * bafl_qr.qz) / 4; - if (q_sq > 1) { /* this should actually never happen */ - FLOAT_QUAT_SMUL(bafl_qr, bafl_qr, 1 / sqrtf(1 + q_sq)); - } else { - bafl_qr.qi = sqrtf(1 - q_sq); - } - /* propagate correction quaternion */ - FLOAT_QUAT_COMP(bafl_qtemp, bafl_quat, bafl_qr); - FLOAT_QUAT_COPY(bafl_quat, bafl_qtemp); - - bafl_qnorm = FLOAT_QUAT_NORM(bafl_quat); - //TODO check if broot force normalization is good, use lagrange normalization? - FLOAT_QUAT_NORMALIZE(bafl_quat); - - - /* - * compute all representations - */ - /* maintain rotation matrix representation */ - FLOAT_RMAT_OF_QUAT(bafl_dcm, bafl_quat); - /* maintain euler representation */ - FLOAT_EULERS_OF_RMAT(bafl_eulers, bafl_dcm); - AHRS_TO_BFP(); - AHRS_LTP_TO_BODY(); - - - /* error KF-Filter - * propagate only the error covariance matrix since error is corrected after each measurement - * - * F = [ 0 0 0 ] - * [ 0 0 0 -Cbn ] - * [ 0 0 0 ] - * [ 0 0 0 0 0 0 ] - * [ 0 0 0 0 0 0 ] - * [ 0 0 0 0 0 0 ] - * - * T = e^(dt * F) - * - * T = [ 1 0 0 ] - * [ 0 1 0 -Cbn*dt ] - * [ 0 0 1 ] - * [ 0 0 0 1 0 0 ] - * [ 0 0 0 0 1 0 ] - * [ 0 0 0 0 0 1 ] - * - * P_prio = T * P * T_T + Q - * - */ - - /* - * compute state transition matrix T - * - * diagonal elements of T are always one - */ - for (i = 0; i < 3; i++) { - for (j = 0; j < 3; j++) { - bafl_T[i][j + 3] = -RMAT_ELMT(bafl_dcm, j, i); /* inverted bafl_dcm */ - } - } - - - /* - * estimate the a priori error covariance matrix P_k = T * P_k-1 * T_T + Q - */ - /* Temporary multiplication temp(6x6) = T(6x6) * P(6x6) */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_tempP[i][j] = 0.; - for (k = 0; k < BAFL_SSIZE; k++) { - bafl_tempP[i][j] += bafl_T[i][k] * bafl_P[k][j]; - } - } - } - - /* P_k(6x6) = temp(6x6) * T_T(6x6) + Q */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_P[i][j] = 0.; - for (k = 0; k < BAFL_SSIZE; k++) { - bafl_P[i][j] += bafl_tempP[i][k] * bafl_T[j][k]; //T[j][k] = T_T[k][j] - } - } - if (i<3) { - bafl_P[i][i] += bafl_Q_att; - } else { - bafl_P[i][i] += bafl_Q_gyro; - } - } - -#ifdef LKF_PRINT_P - printf("Pp ="); - for (i = 0; i < 6; i++) { - printf("["); - for (j = 0; j < 6; j++) { - printf("%f\t", bafl_P[i][j]); - } - printf("]\n "); - } - printf("\n"); -#endif -} - -void ahrs_update_accel(void) { - RunOnceEvery(50, ahrs_do_update_accel()); -} - -static void ahrs_do_update_accel(void) { - int i, j, k; - -#ifdef BAFL_DEBUG2 - printf("Accel update.\n"); -#endif - - /* P_prio = P */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_Pprio[i][j] = bafl_P[i][j]; - } - } - - /* - * set up measurement matrix - * - * g = 9.81 - * gx = [ 0 -g 0 - * g 0 0 - * 0 0 0 ] - * H = [ 0 0 0 ] - * [ -Cnb*gx 0 0 0 ] - * [ 0 0 0 ] - * - * */ - bafl_H[0][0] = -RMAT_ELMT(bafl_dcm, 0, 1) * BAFL_g; - bafl_H[0][1] = RMAT_ELMT(bafl_dcm, 0, 0) * BAFL_g; - bafl_H[1][0] = -RMAT_ELMT(bafl_dcm, 1, 1) * BAFL_g; - bafl_H[1][1] = RMAT_ELMT(bafl_dcm, 1, 0) * BAFL_g; - bafl_H[2][0] = -RMAT_ELMT(bafl_dcm, 2, 1) * BAFL_g; - bafl_H[2][1] = RMAT_ELMT(bafl_dcm, 2, 0) * BAFL_g; - /* rest is zero - bafl_H[0][2] = 0.; - bafl_H[1][2] = 0.; - bafl_H[2][2] = 0.;*/ - - /********************************************** - * compute Kalman gain K - * - * K = P_prio * H_T * inv(S) - * S = H * P_prio * HT + R - * - * K = P_prio * HT * inv(H * P_prio * HT + R) - * - **********************************************/ - - /* covariance residual S = H * P_prio * HT + R */ - - /* temp_S(3x6) = H(3x6) * P_prio(6x6) - * last 4 columns of H are zero - */ - for (i = 0; i < 3; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_tempS[i][j] = bafl_H[i][0] * bafl_Pprio[0][j]; - bafl_tempS[i][j] += bafl_H[i][1] * bafl_Pprio[1][j]; - } - } - - /* S(3x3) = temp_S(3x6) * HT(6x3) + R(3x3) - * - * bottom 4 rows of HT are zero - */ - for (i = 0; i < 3; i++) { - for (j = 0; j < 3; j++) { - bafl_S[i][j] = bafl_tempS[i][0] * bafl_H[j][0]; /* H[j][0] = HT[0][j] */ - bafl_S[i][j] += bafl_tempS[i][1] * bafl_H[j][1]; /* H[j][0] = HT[0][j] */ - } - bafl_S[i][i] += bafl_R_accel; - } - - /* invert S - */ - FLOAT_MAT33_INVERT(bafl_invS, bafl_S); - - - /* temp_K(6x3) = P_prio(6x6) * HT(6x3) - * - * bottom 4 rows of HT are zero - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < 3; j++) { - /* not computing zero elements */ - bafl_tempK[i][j] = bafl_Pprio[i][0] * bafl_H[j][0]; /* H[j][0] = HT[0][j] */ - bafl_tempK[i][j] += bafl_Pprio[i][1] * bafl_H[j][1]; /* H[j][1] = HT[1][j] */ - } - } - - /* K(6x3) = temp_K(6x3) * invS(3x3) - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < 3; j++) { - bafl_K[i][j] = bafl_tempK[i][0] * bafl_invS[0][j]; - bafl_K[i][j] += bafl_tempK[i][1] * bafl_invS[1][j]; - bafl_K[i][j] += bafl_tempK[i][2] * bafl_invS[2][j]; - } - } - - /********************************************** - * Update filter state. - * - * The a priori filter state is zero since the errors are corrected after each update. - * - * X = X_prio + K (y - H * X_prio) - * X = K * y - **********************************************/ - - /*printf("R = "); - for (i = 0; i < 3; i++) { - printf("["); - for (j = 0; j < 3; j++) { - printf("%f\t", RMAT_ELMT(bafl_dcm, i, j)); - } - printf("]\n "); - } - printf("\n");*/ - - /* innovation - * y = Cnb * -[0; 0; g] - accel - */ - bafl_ya.x = -RMAT_ELMT(bafl_dcm, 0, 2) * BAFL_g - bafl_accel_measure.x; - bafl_ya.y = -RMAT_ELMT(bafl_dcm, 1, 2) * BAFL_g - bafl_accel_measure.y; - bafl_ya.z = -RMAT_ELMT(bafl_dcm, 2, 2) * BAFL_g - bafl_accel_measure.z; - - /* X(6) = K(6x3) * y(3) - */ - for (i = 0; i < BAFL_SSIZE; i++) { - bafl_X[i] = bafl_K[i][0] * bafl_ya.x; - bafl_X[i] += bafl_K[i][1] * bafl_ya.y; - bafl_X[i] += bafl_K[i][2] * bafl_ya.z; - } - - /********************************************** - * Update the filter covariance. - * - * P = P_prio - K * H * P_prio - * P = ( I - K * H ) * P_prio - * - **********************************************/ - - /* temp(6x6) = I(6x6) - K(6x3)*H(3x6) - * - * last 4 columns of H are zero - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - if (i == j) { - bafl_tempP[i][j] = 1.; - } else { - bafl_tempP[i][j] = 0.; - } - if (j < 2) { /* omit the parts where H is zero */ - for (k = 0; k < 3; k++) { - bafl_tempP[i][j] -= bafl_K[i][k] * bafl_H[k][j]; - } - } - } - } - - /* P(6x6) = temp(6x6) * P_prio(6x6) - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_P[i][j] = bafl_tempP[i][0] * bafl_Pprio[0][j]; - for (k = 1; k < BAFL_SSIZE; k++) { - bafl_P[i][j] += bafl_tempP[i][k] * bafl_Pprio[k][j]; - } - } - } - -#ifdef LKF_PRINT_P - printf("Pua="); - for (i = 0; i < 6; i++) { - printf("["); - for (j = 0; j < 6; j++) { - printf("%f\t", bafl_P[i][j]); - } - printf("]\n "); - } - printf("\n"); -#endif - - /********************************************** - * Correct errors. - * - * - **********************************************/ - - /* Error quaternion. - */ - QUAT_ASSIGN(bafl_q_a_err, 1.0, bafl_X[0]/2, bafl_X[1]/2, bafl_X[2]/2); - FLOAT_QUAT_INVERT(bafl_q_a_err, bafl_q_a_err); - - /* normalize - * Is this needed? Or is the approximation good enough?*/ - float q_sq; - q_sq = bafl_q_a_err.qx * bafl_q_a_err.qx + bafl_q_a_err.qy * bafl_q_a_err.qy + bafl_q_a_err.qz * bafl_q_a_err.qz; - if (q_sq > 1) { /* this should actually never happen */ - FLOAT_QUAT_SMUL(bafl_q_a_err, bafl_q_a_err, 1 / sqrtf(1 + q_sq)); - printf("Accel error quaternion q_sq > 1!!\n"); - } else { - bafl_q_a_err.qi = sqrtf(1 - q_sq); - } - - /* correct attitude - */ - FLOAT_QUAT_COMP(bafl_qtemp, bafl_q_a_err, bafl_quat); - FLOAT_QUAT_COPY(bafl_quat, bafl_qtemp); - - - /* correct gyro bias - */ - RATES_ASSIGN(bafl_b_a_err, bafl_X[3], bafl_X[4], bafl_X[5]); - RATES_SUB(bafl_bias, bafl_b_a_err); - - /* - * compute all representations - */ - /* maintain rotation matrix representation */ - FLOAT_RMAT_OF_QUAT(bafl_dcm, bafl_quat); - /* maintain euler representation */ - FLOAT_EULERS_OF_RMAT(bafl_eulers, bafl_dcm); - AHRS_TO_BFP(); - AHRS_LTP_TO_BODY(); -} - - -void ahrs_update_mag(void) { - RunOnceEvery(10, ahrs_do_update_mag()); -} - -static void ahrs_do_update_mag(void) { - int i, j, k; - -#ifdef BAFL_DEBUG2 - printf("Mag update.\n"); -#endif - - MAGS_FLOAT_OF_BFP(bafl_mag, imu.mag); - - /* P_prio = P */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_Pprio[i][j] = bafl_P[i][j]; - } - } - - /* - * set up measurement matrix - * - * h = [236.; -2.; 396.]; - * hx = [ h(2); -h(1); 0]; //only psi (phi and theta = 0) - * Hm = Cnb * hx; - * H = [ 0 0 0 0 0 - * 0 0 Cnb*hx 0 0 0 - * 0 0 0 0 0 ]; - * */ - /*bafl_H[0][2] = RMAT_ELMT(bafl_dcm, 0, 0) * bafl_h.y - RMAT_ELMT(bafl_dcm, 0, 1) * bafl_h.x; - bafl_H[1][2] = RMAT_ELMT(bafl_dcm, 1, 0) * bafl_h.y - RMAT_ELMT(bafl_dcm, 1, 1) * bafl_h.x; - bafl_H[2][2] = RMAT_ELMT(bafl_dcm, 2, 0) * bafl_h.y - RMAT_ELMT(bafl_dcm, 2, 1) * bafl_h.x;*/ - bafl_H[0][2] = -RMAT_ELMT(bafl_dcm, 0, 1); - bafl_H[1][2] = -RMAT_ELMT(bafl_dcm, 1, 1); - bafl_H[2][2] = -RMAT_ELMT(bafl_dcm, 2, 1); - //rest is zero - - /********************************************** - * compute Kalman gain K - * - * K = P_prio * H_T * inv(S) - * S = H * P_prio * HT + R - * - * K = P_prio * HT * inv(H * P_prio * HT + R) - * - **********************************************/ - - /* covariance residual S = H * P_prio * HT + R */ - - /* temp_S(3x6) = H(3x6) * P_prio(6x6) - * - * only third column of H is non-zero - */ - for (i = 0; i < 3; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_tempS[i][j] = bafl_H[i][2] * bafl_Pprio[2][j]; - } - } - - /* S(3x3) = temp_S(3x6) * HT(6x3) + R(3x3) - * - * only third row of HT is non-zero - */ - for (i = 0; i < 3; i++) { - for (j = 0; j < 3; j++) { - bafl_S[i][j] = bafl_tempS[i][2] * bafl_H[j][2]; /* H[j][2] = HT[2][j] */ - } - bafl_S[i][i] += bafl_R_mag; - } - - /* invert S - */ - FLOAT_MAT33_INVERT(bafl_invS, bafl_S); - - /* temp_K(6x3) = P_prio(6x6) * HT(6x3) - * - * only third row of HT is non-zero - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < 3; j++) { - /* not computing zero elements */ - bafl_tempK[i][j] = bafl_Pprio[i][2] * bafl_H[j][2]; /* H[j][2] = HT[2][j] */ - } - } - - /* K(6x3) = temp_K(6x3) * invS(3x3) - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < 3; j++) { - bafl_K[i][j] = bafl_tempK[i][0] * bafl_invS[0][j]; - bafl_K[i][j] += bafl_tempK[i][1] * bafl_invS[1][j]; - bafl_K[i][j] += bafl_tempK[i][2] * bafl_invS[2][j]; - } - } - - /********************************************** - * Update filter state. - * - * The a priori filter state is zero since the errors are corrected after each update. - * - * X = X_prio + K (y - H * X_prio) - * X = K * y - **********************************************/ - - /* innovation - * y = Cnb * [hx; hy; hz] - mag - */ - FLOAT_RMAT_VECT3_MUL(bafl_ym, bafl_dcm, bafl_h); //can be optimized - FLOAT_VECT3_SUB(bafl_ym, bafl_mag); - - /* X(6) = K(6x3) * y(3) - */ - for (i = 0; i < BAFL_SSIZE; i++) { - bafl_X[i] = bafl_K[i][0] * bafl_ym.x; - bafl_X[i] += bafl_K[i][1] * bafl_ym.y; - bafl_X[i] += bafl_K[i][2] * bafl_ym.z; - } - - /********************************************** - * Update the filter covariance. - * - * P = P_prio - K * H * P_prio - * P = ( I - K * H ) * P_prio - * - **********************************************/ - - /* temp(6x6) = I(6x6) - K(6x3)*H(3x6) - * - * last 3 columns of H are zero - */ - for (i = 0; i < 6; i++) { - for (j = 0; j < 6; j++) { - if (i == j) { - bafl_tempP[i][j] = 1.; - } else { - bafl_tempP[i][j] = 0.; - } - if (j == 2) { /* omit the parts where H is zero */ - for (k = 0; k < 3; k++) { - bafl_tempP[i][j] -= bafl_K[i][k] * bafl_H[k][j]; - } - } - } - } - - /* P(6x6) = temp(6x6) * P_prio(6x6) - */ - for (i = 0; i < BAFL_SSIZE; i++) { - for (j = 0; j < BAFL_SSIZE; j++) { - bafl_P[i][j] = bafl_tempP[i][0] * bafl_Pprio[0][j]; - for (k = 1; k < BAFL_SSIZE; k++) { - bafl_P[i][j] += bafl_tempP[i][k] * bafl_Pprio[k][j]; - } - } - } - -#ifdef LKF_PRINT_P - printf("Pum="); - for (i = 0; i < 6; i++) { - printf("["); - for (j = 0; j < 6; j++) { - printf("%f\t", bafl_P[i][j]); - } - printf("]\n "); - } - printf("\n"); -#endif - - /********************************************** - * Correct errors. - * - * - **********************************************/ - - /* Error quaternion. - */ - QUAT_ASSIGN(bafl_q_m_err, 1.0, bafl_X[0]/2, bafl_X[1]/2, bafl_X[2]/2); - FLOAT_QUAT_INVERT(bafl_q_m_err, bafl_q_m_err); - /* normalize */ - float q_sq; - q_sq = bafl_q_m_err.qx * bafl_q_m_err.qx + bafl_q_m_err.qy * bafl_q_m_err.qy + bafl_q_m_err.qz * bafl_q_m_err.qz; - if (q_sq > 1) { /* this should actually never happen */ - FLOAT_QUAT_SMUL(bafl_q_m_err, bafl_q_m_err, 1 / sqrtf(1 + q_sq)); - printf("mag error quaternion q_sq > 1!!\n"); - } else { - bafl_q_m_err.qi = sqrtf(1 - q_sq); - } - - /* correct attitude - */ - FLOAT_QUAT_COMP(bafl_qtemp, bafl_q_m_err, bafl_quat); - FLOAT_QUAT_COPY(bafl_quat, bafl_qtemp); - - /* correct gyro bias - */ - RATES_ASSIGN(bafl_b_m_err, bafl_X[3], bafl_X[4], bafl_X[5]); - RATES_SUB(bafl_bias, bafl_b_m_err); - - /* - * compute all representations - */ - /* maintain rotation matrix representation */ - FLOAT_RMAT_OF_QUAT(bafl_dcm, bafl_quat); - /* maintain euler representation */ - FLOAT_EULERS_OF_RMAT(bafl_eulers, bafl_dcm); - AHRS_TO_BFP(); - AHRS_LTP_TO_BODY(); -} - -void ahrs_update(void) { - ahrs_update_accel(); - ahrs_update_mag(); -} diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_lkf.h b/sw/airborne/subsystems/ahrs/ahrs_float_lkf.h deleted file mode 100644 index 71afc6d3cf..0000000000 --- a/sw/airborne/subsystems/ahrs/ahrs_float_lkf.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * Copyright (C) 2009 Felix Ruess - * Copyright (C) 2008-2009 Antoine Drouin - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - -/** - * @file subsystems/ahrs/ahrs_float_lkf.h - * - * Linearized Kalman Filter for attitude estimation. - * - */ - -#ifndef AHRS_FLOAT_LKF_H -#define AHRS_FLOAT_LKF_H - -#include "subsystems/ahrs.h" -#include "std.h" -#include "math/pprz_algebra_int.h" - -extern struct FloatQuat bafl_quat; -extern struct FloatRates bafl_bias; -extern struct FloatRates bafl_rates; -extern struct FloatEulers bafl_eulers; -extern struct FloatRMat bafl_dcm; - -extern struct FloatQuat bafl_q_a_err; -extern struct FloatQuat bafl_q_m_err; -extern struct FloatRates bafl_b_a_err; -extern struct FloatRates bafl_b_m_err; -extern float bafl_qnorm; -extern float bafl_phi_accel; -extern float bafl_theta_accel; -extern struct FloatVect3 bafl_accel_measure; -extern struct FloatVect3 bafl_mag; - -#define BAFL_SSIZE 6 -extern float bafl_P[BAFL_SSIZE][BAFL_SSIZE]; -extern float bafl_X[BAFL_SSIZE]; - -extern float bafl_sigma_accel; -extern float bafl_sigma_mag; -extern float bafl_R_accel; -extern float bafl_R_mag; - -extern float bafl_Q_att; -extern float bafl_Q_gyro; - - -#define ahrs_float_lkf_SetRaccel(_v) { \ - bafl_sigma_accel = _v; \ - bafl_R_accel = _v * _v; \ -} -#define ahrs_float_lkf_SetRmag(_v) { \ - bafl_sigma_mag = _v; \ - bafl_R_mag = _v * _v; \ -} - -#endif /* AHRS_FLOAT_LKF_H */ - From d364421acf8c93870e0f8af9c9b0a52e2b0b6167 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Aug 2013 17:02:24 +0200 Subject: [PATCH 094/309] [conf] error instead of warning on stabilization euler --- .../subsystems/rotorcraft/stabilization_euler.makefile | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/conf/firmwares/subsystems/rotorcraft/stabilization_euler.makefile b/conf/firmwares/subsystems/rotorcraft/stabilization_euler.makefile index 70d8683f79..ee591b2a52 100644 --- a/conf/firmwares/subsystems/rotorcraft/stabilization_euler.makefile +++ b/conf/firmwares/subsystems/rotorcraft/stabilization_euler.makefile @@ -1,3 +1,2 @@ -$(warning Warning: The stabilization euler subsystem has been renamed, please replace with in your airframe file.) +$(error The stabilization euler subsystem has been renamed, please replace with in your airframe file.) -include $(PAPARAZZI_SRC)/conf/firmwares/subsystems/rotorcraft/stabilization_int_euler.makefile From f88f68b8eefbca877a3e20a78c15a009f6f37b14 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Aug 2013 19:29:21 +0200 Subject: [PATCH 095/309] [sim] add launch and noground options to pprzsim-launch --- sw/simulator/pprzsim-launch | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/sw/simulator/pprzsim-launch b/sw/simulator/pprzsim-launch index c126dc90bb..877c292948 100755 --- a/sw/simulator/pprzsim-launch +++ b/sw/simulator/pprzsim-launch @@ -56,6 +56,10 @@ def main(): help="Boot the aircraft on start") ocamlsim_opts.add_option("--norc", dest="norc", action="store_true", help="Hide the simulated RC") + ocamlsim_opts.add_option("--noground", dest="noground", action="store_true", + help="Disable ground detection") + ocamlsim_opts.add_option("--launch", dest="launch", action="store_true", + help="Launch the aircraft on startup") # special options for NPS nps_opts = OptionGroup(parser, "NPS Options", "These are only relevant to the NPS sim") @@ -94,6 +98,10 @@ def main(): simargs.append("-boot") if options.norc: simargs.append("-norc") + if options.noground: + simargs.append("-noground") + if options.launch: + simargs.append("-launch") if options.ivy_bus: simargs.append("-b") simargs.append(options.ivy_bus) From a7cc0724b13abc420bbb33e4e8d145fd86f73b32 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 20 Aug 2013 00:18:36 +0200 Subject: [PATCH 096/309] [paparazzi center] improve backup message --- sw/supervision/paparazzicenter.ml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sw/supervision/paparazzicenter.ml b/sw/supervision/paparazzicenter.ml index b3af7d514e..8ad6260c65 100644 --- a/sw/supervision/paparazzicenter.ml +++ b/sw/supervision/paparazzicenter.ml @@ -173,7 +173,8 @@ let () = if Sys.file_exists Utils.backup_xml_file then begin let rec question_box = fun () -> - match GToolbox.question_box ~title:"Backup" ~buttons:["Keep changes"; "Discard changes"; "View changes"] ~default:2 "Configuration changes made during the last session were not saved. ?" with + let message = "Configuration changes to conf/conf.xml were not saved during the last session.\nIf you made any manual changes to conf/conf.xml and choose [Discard changes] you will also lose these." in + match GToolbox.question_box ~title:"Backup" ~buttons:["Keep changes"; "Discard changes"; "View changes"] ~default:2 message with | 2 -> Sys.rename Utils.backup_xml_file Utils.conf_xml_file | 3 -> ignore (Sys.command (sprintf "meld %s %s" Utils.backup_xml_file Utils.conf_xml_file)); question_box () | _ -> Sys.remove Utils.backup_xml_file in From f2815056fd58d9e0f9f3177a1033d96a25c2fdfe Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Mon, 19 Aug 2013 10:34:31 -0600 Subject: [PATCH 097/309] [nps] Made joystick buttons/axes configurable --- conf/airframes/examples/quadrotor_mlkf.xml | 2 +- conf/airframes/fraser_lisa_m_rotorcraft.xml | 2 +- sw/simulator/nps/nps_radio_control_joystick.c | 115 ++++++++++++++---- 3 files changed, 96 insertions(+), 23 deletions(-) diff --git a/conf/airframes/examples/quadrotor_mlkf.xml b/conf/airframes/examples/quadrotor_mlkf.xml index 2f63c01469..9779fe055c 100644 --- a/conf/airframes/examples/quadrotor_mlkf.xml +++ b/conf/airframes/examples/quadrotor_mlkf.xml @@ -207,7 +207,7 @@ - +
diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index 8a1447d69c..8ef4c4e5c9 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -239,7 +239,7 @@ - +
diff --git a/sw/simulator/nps/nps_radio_control_joystick.c b/sw/simulator/nps/nps_radio_control_joystick.c index 746c04aed4..4b164777b2 100644 --- a/sw/simulator/nps/nps_radio_control_joystick.c +++ b/sw/simulator/nps/nps_radio_control_joystick.c @@ -27,13 +27,49 @@ * Simple DirectMedia Layer library is used for cross-platform support. * Joystick button and axes are mapped to RC commands directly with defines. * - * Currently it doesn't support different RC configurations. + * You must have a joystick with either: + * - 4 axes and 3 buttons, or + * - 5 axes + * + * First you should run sw/ground_segment/joystick/test_stick to determine + * the indices of the physical axes and buttons on your joystick (and to test + * that it actually works). Then you can assign each axis and button to a + * command in your airframe file. + * + * The default axes are Roll = 0, Pitch = 1, Yaw = 2 and Throttle = 3. + * The default buttons are Manual = 0, Auto1 = 1, Auto2 = 2. + * + * Example for 4 axes and 3 buttons using a joystick with 7 axes and 5 buttons: + * @verbatim + *
+ * ... + * + * + * + * + * + * + * + *
+ * @endverbatim + * + * One can define NPS_JS_AXIS_MODE to use an axis instead of buttons to change + * You will need a 5-axis joystick. + * + * If you need to reverse the direction of any axis, simply use: + * @verbatim + * + * + * @endverbatim + * + * At this point, no other functionality or channels are supported for R/C control. + * */ #include "nps_radio_control.h" #include "nps_radio_control_joystick.h" -// for NPS_JS_MODE_AXIS +// for NPS_JS_AXIS_MODE #include "generated/airframe.h" #include @@ -42,22 +78,37 @@ #include // axes indice -#define JS_ROLL 0 -#define JS_PITCH 1 -#define JS_YAW 2 -#define JS_THROTTLE 3 +#ifndef NPS_JS_AXIS_ROLL +#define NPS_JS_AXIS_ROLL 0 +#endif +#ifndef NPS_JS_AXIS_PITCH +#define NPS_JS_AXIS_PITCH 1 +#endif +#ifndef NPS_JS_AXIS_YAW +#define NPS_JS_AXIS_YAW 2 +#endif +#ifndef NPS_JS_AXIS_THROTTLE +#define NPS_JS_AXIS_THROTTLE 3 +#endif -#ifndef NPS_JS_MODE_AXIS +#ifndef NPS_JS_AXIS_MODE #define JS_NB_AXIS 4 #else #define JS_NB_AXIS 5 #endif // buttons to switch modes -#define JS_BUTTON_MODE_MANUAL 4 -#define JS_BUTTON_MODE_AUTO1 5 -#define JS_BUTTON_MODE_AUTO2 6 -#ifndef NPS_JS_MODE_AXIS +#ifndef NPS_JS_BUTTON_MODE_MANUAL +#define NPS_JS_BUTTON_MODE_MANUAL 1 +#endif +#ifndef NPS_JS_BUTTON_MODE_AUTO1 +#define NPS_JS_BUTTON_MODE_AUTO1 2 +#endif +#ifndef NPS_JS_BUTTON_MODE_AUTO2 +#define NPS_JS_BUTTON_MODE_AUTO2 3 +#endif + +#ifndef NPS_JS_AXIS_MODE #define JS_NB_BUTTONS 3 #else #define JS_NB_BUTTONS 0 @@ -132,6 +183,8 @@ int nps_radio_control_joystick_init(const char* device) { else if (SDL_JoystickNumAxes(sdl_joystick) < JS_NB_AXIS) { printf("Selected joystick does not support enough axes!\n"); + printf("Number of axes required: %i\n", JS_NB_AXIS); + printf("Number of axes available: %i\n",SDL_JoystickNumAxes(sdl_joystick)); SDL_JoystickClose(sdl_joystick); exit(-1); } @@ -155,13 +208,33 @@ int nps_radio_control_joystick_init(const char* device) { */ void nps_radio_control_joystick_update(void) { - nps_joystick.throttle = ((float)(SDL_JoystickGetAxis(sdl_joystick,JS_THROTTLE)) - 32767.)/-65534.; - nps_joystick.roll = (float)(SDL_JoystickGetAxis(sdl_joystick,JS_ROLL))/32767.; - nps_joystick.pitch = (float)(SDL_JoystickGetAxis(sdl_joystick,JS_PITCH))/32767.; - nps_joystick.yaw = (float)(SDL_JoystickGetAxis(sdl_joystick,JS_YAW))/32767.; +#if NPS_JS_AXIS_THROTTLE_REVERSED + nps_joystick.throttle = ((float)(-1 * SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_THROTTLE)) - 32767.)/-65534.; +#else + nps_joystick.throttle = ((float)(SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_THROTTLE)) - 32767.)/-65534.; +#endif +#if NPS_JS_AXIS_ROLL_REVERSED + nps_joystick.roll = (float)(-1 * SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_ROLL))/32767.; +#else + nps_joystick.roll = (float)(SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_ROLL))/32767.; +#endif +#if NPS_JS_AXIS_PITCH_REVERSED + nps_joystick.pitch = (float)(-1 * SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_PITCH))/32767.; +#else + nps_joystick.pitch = (float)(SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_PITCH))/32767.; +#endif +#if NPS_JS_AXIS_YAW_REVERSED + nps_joystick.yaw = (float)(-1 * SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_YAW))/32767.; +#else + nps_joystick.yaw = (float)(SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_YAW))/32767.; +#endif // if an axis is asigned to the mode, use it instead of the buttons -#ifdef NPS_JS_MODE_AXIS - nps_joystick.mode = (float)(SDL_JoystickGetAxis(sdl_joystick,NPS_JS_MODE_AXIS))/32767.; +#ifdef NPS_JS_AXIS_MODE +#if NPS_JS_AXIS_MODE_REVERSED + nps_joystick.mode = (float)(-1 * SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_MODE))/32767.; +#else + nps_joystick.mode = (float)(SDL_JoystickGetAxis(sdl_joystick,NPS_JS_AXIS_MODE))/32767.; +#endif #endif while(SDL_PollEvent(&sdl_event)) @@ -172,16 +245,16 @@ void nps_radio_control_joystick_update(void) { { switch(sdl_event.jbutton.button) { -#ifndef NPS_JS_MODE_AXIS - case JS_BUTTON_MODE_MANUAL: +#ifndef NPS_JS_AXIS_MODE + case NPS_JS_BUTTON_MODE_MANUAL: nps_joystick.mode = MODE_SWITCH_MANUAL; break; - case JS_BUTTON_MODE_AUTO1: + case NPS_JS_BUTTON_MODE_AUTO1: nps_joystick.mode = MODE_SWITCH_AUTO1; break; - case JS_BUTTON_MODE_AUTO2: + case NPS_JS_BUTTON_MODE_AUTO2: nps_joystick.mode = MODE_SWITCH_AUTO2; break; #endif From 6a145a3cbd69af3039680a6affc18b30358d9868 Mon Sep 17 00:00:00 2001 From: Stephen Dwyer Date: Mon, 19 Aug 2013 17:04:24 -0600 Subject: [PATCH 098/309] [pprz_center] Added Get Help dialogue to Help menu --- sw/supervision/paparazzicenter.glade | 10 ++++++++++ sw/supervision/paparazzicenter.ml | 5 +++++ 2 files changed, 15 insertions(+) diff --git a/sw/supervision/paparazzicenter.glade b/sw/supervision/paparazzicenter.glade index c59f210306..e68aa24f77 100644 --- a/sw/supervision/paparazzicenter.glade +++ b/sw/supervision/paparazzicenter.glade @@ -276,6 +276,16 @@ + + + True + False + False + _Get Help + True + + + diff --git a/sw/supervision/paparazzicenter.ml b/sw/supervision/paparazzicenter.ml index 8ad6260c65..966475d7c6 100644 --- a/sw/supervision/paparazzicenter.ml +++ b/sw/supervision/paparazzicenter.ml @@ -258,6 +258,11 @@ let () = ignore (GToolbox.message_box ~title:"About Paparazzi Center" ~icon:(GMisc.image ~pixbuf:paparazzi_pixbuf ())#coerce "Copyright (C) 2007-2008 ENAC, Pascal Brisset\nhttp://paparazzi.enac.fr") in ignore (gui#menu_item_about#connect#activate ~callback); + (* Help/Get Help menu entry *) + let callback = fun () -> + ignore (GToolbox.message_box ~title:"Getting Help with Paparazzi" ~icon:(GMisc.image ~pixbuf:paparazzi_pixbuf ())#coerce "The primary documentation for Paparazzi is on the wiki:\nhttp://paparazzi.enac.fr\n\nCommunity-based support is through the paparazzi-devel mailing list:\nhttp://paparazzi.enac.fr/wiki/Contact\n\nThe Paparazzi auto-generated developer documentation is found on GitHub:\nhttp://paparazzi.github.io/docs/\n\nThe Paparazzi sourcecode can be found on GitHub:\nhttps://github.com/paparazzi/paparazzi\n\nIf you think you have found a bug or would like to make a feature request, feel\nfree to visit the Issues page found on GitHub (link found on the above webpage).") in + ignore (gui#menu_item_get_help#connect#activate ~callback); + (* Read preferences *) if Sys.file_exists Env.gconf_file then begin read_preferences gui Env.gconf_file ac_combo session_combo target_combo From 53d1c1907beefe9b690ade45552c35713698071b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 20 Aug 2013 18:51:57 +0200 Subject: [PATCH 099/309] [math] remove ALGEBRA_x_USE_SLOW_FUNCTIONS --- sw/airborne/math/pprz_algebra_float.h | 59 ------------------------- sw/airborne/math/pprz_algebra_int.h | 63 +-------------------------- 2 files changed, 1 insertion(+), 121 deletions(-) diff --git a/sw/airborne/math/pprz_algebra_float.h b/sw/airborne/math/pprz_algebra_float.h index 06e024150e..b93cc056aa 100644 --- a/sw/airborne/math/pprz_algebra_float.h +++ b/sw/airborne/math/pprz_algebra_float.h @@ -381,37 +381,6 @@ struct FloatRates { /* C n->b rotation matrix */ -#ifdef ALGEBRA_FLOAT_USE_SLOW_FUNCTIONS -#define FLOAT_RMAT_OF_QUAT(_rm, _q) { \ - const float qx2 = (_q).qx*(_q).qx; \ - const float qy2 = (_q).qy*(_q).qy; \ - const float qz2 = (_q).qz*(_q).qz; \ - const float qiqx = (_q).qi*(_q).qx; \ - const float qiqy = (_q).qi*(_q).qy; \ - const float qiqz = (_q).qi*(_q).qz; \ - const float qxqy = (_q).qx*(_q).qy; \ - const float qxqz = (_q).qx*(_q).qz; \ - const float qyqz = (_q).qy*(_q).qz; \ - /* dcm00 = 1.0 - 2.*( qy2 + qz2 ); */ \ - RMAT_ELMT(_rm, 0, 0) = 1. - 2.*( qy2 + qz2 ); \ - /* dcm01 = 2.*( qxqy + qiqz ); */ \ - RMAT_ELMT(_rm, 0, 1) = 2.*( qxqy + qiqz ); \ - /* dcm02 = 2.*( qxqz - qiqy ); */ \ - RMAT_ELMT(_rm, 0, 2) = 2.*( qxqz - qiqy ); \ - /* dcm10 = 2.*( qxqy - qiqz ); */ \ - RMAT_ELMT(_rm, 1, 0) = 2.*( qxqy - qiqz ); \ - /* dcm11 = 1.0 - 2.*(qx2+qz2); */ \ - RMAT_ELMT(_rm, 1, 1) = 1.0 - 2.*(qx2+qz2); \ - /* dcm12 = 2.*( qyqz + qiqx ); */ \ - RMAT_ELMT(_rm, 1, 2) = 2.*( qyqz + qiqx ); \ - /* dcm20 = 2.*( qxqz + qiqy ); */ \ - RMAT_ELMT(_rm, 2, 0) = 2.*( qxqz + qiqy ); \ - /* dcm21 = 2.*( qyqz - qiqx ); */ \ - RMAT_ELMT(_rm, 2, 1) = 2.*( qyqz - qiqx ); \ - /* dcm22 = 1.0 - 2.*( qx2 + qy2 ); */ \ - RMAT_ELMT(_rm, 2, 2) = 1.0 - 2.*( qx2 + qy2 ); \ - } -#else #define FLOAT_RMAT_OF_QUAT(_rm, _q) { \ const float _a = M_SQRT2*(_q).qi; \ const float _b = M_SQRT2*(_q).qx; \ @@ -434,7 +403,6 @@ struct FloatRates { RMAT_ELMT(_rm, 2, 1) = cd-ab; \ RMAT_ELMT(_rm, 2, 2) = a2_1+_d*_d; \ } -#endif /* in place first order integration of a rotation matrix */ #define FLOAT_RMAT_INTEGRATE_FI(_rm, _omega, _dt ) { \ @@ -605,32 +573,6 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { } \ } -#ifdef ALGEBRA_FLOAT_USE_SLOW_FUNCTIONS -#define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ - const float qi2 = (q).qi*(q).qi; \ - const float qiqx = (q).qi*(q).qx; \ - const float qiqy = (q).qi*(q).qy; \ - const float qiqz = (q).qi*(q).qz; \ - const float qx2 = (q).qx*(q).qx; \ - const float qxqy = (q).qx*(q).qy; \ - const float qxqz = (q).qx*(q).qz; \ - const float qy2 = (q).qy*(q).qy; \ - const float qyqz = (q).qy*(q).qz; \ - const float qz2 = (q).qz*(q).qz; \ - const float m00 = qi2 + qx2 - qy2 - qz2; \ - const float m01 = 2 * ( qxqy + qiqz ); \ - const float m02 = 2 * ( qxqz - qiqy ); \ - const float m10 = 2 * ( qxqy - qiqz ); \ - const float m11 = qi2 - qx2 + qy2 - qz2; \ - const float m12 = 2 * ( qyqz + qiqx ); \ - const float m20 = 2 * ( qxqz + qiqy ); \ - const float m21 = 2 * ( qyqz - qiqx ); \ - const float m22 = qi2 - qx2 - qy2 + qz2; \ - (v_out).x = m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z; \ - (v_out).y = m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z; \ - (v_out).z = m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z; \ - } -#else #define FLOAT_QUAT_VMULT(v_out, q, v_in) { \ const float qi2_M1_2 = (q).qi*(q).qi - 0.5; \ const float qiqx = (q).qi*(q).qx; \ @@ -653,7 +595,6 @@ static inline float float_rmat_reorthogonalize(struct FloatRMat* rm) { (v_out).y = 2*(m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z); \ (v_out).z = 2*(m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z); \ } -#endif /* _qd = -0.5*omega(_r) * _q */ #define FLOAT_QUAT_DERIVATIVE(_qd, _r, _q) { \ diff --git a/sw/airborne/math/pprz_algebra_int.h b/sw/airborne/math/pprz_algebra_int.h index 4135dbb4cd..50f7a1e88c 100644 --- a/sw/airborne/math/pprz_algebra_int.h +++ b/sw/airborne/math/pprz_algebra_int.h @@ -381,40 +381,7 @@ struct Int64Vect3 { /* * http://www.mathworks.com/access/helpdesk_r13/help/toolbox/aeroblks/quaternionstodirectioncosinematrix.html */ -#ifdef ALGEBRA_INT_USE_SLOW_FUNCTIONS -#define INT32_RMAT_OF_QUAT(_rm, _q) { \ - const int32_t qx2 = INT_MULT_RSHIFT((_q).qx,(_q).qx, INT32_QUAT_FRAC); \ - const int32_t qy2 = INT_MULT_RSHIFT((_q).qy,(_q).qy, INT32_QUAT_FRAC); \ - const int32_t qz2 = INT_MULT_RSHIFT((_q).qz,(_q).qz, INT32_QUAT_FRAC); \ - const int32_t qiqx = INT_MULT_RSHIFT((_q).qi,(_q).qx, INT32_QUAT_FRAC); \ - const int32_t qiqy = INT_MULT_RSHIFT((_q).qi,(_q).qy, INT32_QUAT_FRAC); \ - const int32_t qiqz = INT_MULT_RSHIFT((_q).qi,(_q).qz, INT32_QUAT_FRAC); \ - const int32_t qxqy = INT_MULT_RSHIFT((_q).qx,(_q).qy, INT32_QUAT_FRAC); \ - const int32_t qxqz = INT_MULT_RSHIFT((_q).qx,(_q).qz, INT32_QUAT_FRAC); \ - const int32_t qyqz = INT_MULT_RSHIFT((_q).qy,(_q).qz, INT32_QUAT_FRAC); \ - const int32_t one = TRIG_BFP_OF_REAL( 1); \ - const int32_t two = TRIG_BFP_OF_REAL( 2); \ - /* dcm00 = 1.0 - 2.*( qy2 + qz2 ); */ \ - (_rm).m[0] = one - INT_MULT_RSHIFT( two, (qy2+qz2), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm01 = 2.*( qxqy + qiqz ); */ \ - (_rm).m[1] = INT_MULT_RSHIFT( two, (qxqy+qiqz), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm02 = 2.*( qxqz - qiqy ); */ \ - (_rm).m[2] = INT_MULT_RSHIFT( two, (qxqz-qiqy), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm10 = 2.*( qxqy - qiqz ); */ \ - (_rm).m[3] = INT_MULT_RSHIFT( two, (qxqy-qiqz), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm11 = 1.0 - 2.*(qx2+qz2); */ \ - (_rm).m[4] = one - INT_MULT_RSHIFT( two, (qx2+qz2), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm12 = 2.*( qyqz + qiqx ); */ \ - (_rm).m[5] = INT_MULT_RSHIFT( two, (qyqz+qiqx), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm20 = 2.*( qxqz + qiqy ); */ \ - (_rm).m[6] = INT_MULT_RSHIFT( two, (qxqz+qiqy), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm21 = 2.*( qyqz - qiqx ); */ \ - (_rm).m[7] = INT_MULT_RSHIFT( two, (qyqz-qiqx), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - /* dcm22 = 1.0 - 2.*( qx2 + qy2 ); */ \ - (_rm).m[8] = one - INT_MULT_RSHIFT( two, (qx2+qy2), INT32_TRIG_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC); \ - } -#else - #define INT32_RMAT_OF_QUAT(_rm, _q) { \ +#define INT32_RMAT_OF_QUAT(_rm, _q) { \ const int32_t _2qi2_m1 = INT_MULT_RSHIFT((_q).qi,(_q).qi, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1)-TRIG_BFP_OF_REAL( 1); \ (_rm).m[0] = INT_MULT_RSHIFT((_q).qx,(_q).qx, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ (_rm).m[4] = INT_MULT_RSHIFT((_q).qy,(_q).qy, INT32_QUAT_FRAC+INT32_QUAT_FRAC-INT32_TRIG_FRAC-1); \ @@ -437,7 +404,6 @@ struct Int64Vect3 { (_rm).m[5] += _2qiqx; \ (_rm).m[8] += _2qi2_m1; \ } -#endif /* @@ -643,32 +609,6 @@ struct Int64Vect3 { } -#ifdef ALGEBRA_INT_USE_SLOW_FUNCTIONS -#define INT32_QUAT_VMULT(v_out, q, v_in) { \ - const int32_t qi2 = ((q).qi*(q).qi)>>INT32_QUAT_FRAC; \ - const int32_t qx2 = ((q).qx*(q).qx)>>INT32_QUAT_FRAC; \ - const int32_t qy2 = ((q).qy*(q).qy)>>INT32_QUAT_FRAC; \ - const int32_t qz2 = ((q).qz*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t qiqx = ((q).qi*(q).qx)>>INT32_QUAT_FRAC; \ - const int32_t qiqy = ((q).qi*(q).qy)>>INT32_QUAT_FRAC; \ - const int32_t qiqz = ((q).qi*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t qxqy = ((q).qx*(q).qy)>>INT32_QUAT_FRAC; \ - const int32_t qxqz = ((q).qx*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t qyqz = ((q).qy*(q).qz)>>INT32_QUAT_FRAC; \ - const int32_t m00 = qi2 + qx2 - qy2 - qz2; \ - const int32_t m01 = 2 * (qxqy + qiqz ); \ - const int32_t m02 = 2 * (qxqz - qiqy ); \ - const int32_t m10 = 2 * (qxqy - qiqz ); \ - const int32_t m11 = qi2 - qx2 + qy2 - qz2; \ - const int32_t m12 = 2 * (qyqz + qiqx ); \ - const int32_t m20 = 2 * (qxqz + qiqy ); \ - const int32_t m21 = 2 * (qyqz - qiqx ); \ - const int32_t m22 = qi2 - qx2 - qy2 + qz2; \ - (v_out).x = (m00 * (v_in).x + m01 * (v_in).y + m02 * (v_in).z)>>INT32_QUAT_FRAC; \ - (v_out).y = (m10 * (v_in).x + m11 * (v_in).y + m12 * (v_in).z)>>INT32_QUAT_FRAC; \ - (v_out).z = (m20 * (v_in).x + m21 * (v_in).y + m22 * (v_in).z)>>INT32_QUAT_FRAC; \ - } -#else #define INT32_QUAT_VMULT(v_out, q, v_in) { \ const int32_t _2qi2_m1 = (((q).qi*(q).qi)>>(INT32_QUAT_FRAC-1)) - QUAT1_BFP_OF_REAL( 1); \ const int32_t _2qx2 = ((q).qx*(q).qx)>>(INT32_QUAT_FRAC-1); \ @@ -684,7 +624,6 @@ struct Int64Vect3 { (v_out).y = (_2qi2_m1*(v_in).y + m01 * (v_in).x -2*_2qiqz*(v_in).x + _2qy2 * (v_in).y + m12 * (v_in).z)>>INT32_QUAT_FRAC; \ (v_out).z = (_2qi2_m1*(v_in).z + m02 * (v_in).x +2*_2qiqy*(v_in).x+ m12 * (v_in).y -2*_2qiqx*(v_in).y+ _2qz2 * (v_in).z)>>INT32_QUAT_FRAC; \ } -#endif From 25609e0c5ac2aec44f261b07cadb49b41fc62934 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 20 Aug 2013 23:43:41 +0200 Subject: [PATCH 100/309] [rotorcraft][stabilization] calculate correct yaw from guidance psi setpoint Instead of using the psi setpoint angle to rotate around the body z-axis, calculate the real angle needed to align the projection of the body x-axis onto the horizontal plane with the psi setpoint. Only makes a few degrees of difference at high roll/pitch angles, but should be correc now. still needs to be optimized... --- .../stabilization_attitude_quat_float.c | 40 +++++++++++++++++- .../stabilization_attitude_quat_int.c | 42 ++++++++++++++++++- 2 files changed, 78 insertions(+), 4 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c index b99400c492..d6c83774b6 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c @@ -154,8 +154,44 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { struct FloatQuat q_rp; FLOAT_QUAT_OF_ORIENTATION_VECT(q_rp, ov); - /* quaternion with only heading setpoint */ - const float yaw2 = stab_att_sp_euler.psi / 2.0; + /// @todo optimize yaw angle calculation + + /* + * Instead of using the psi setpoint angle to rotate around the body z-axis, + * calculate the real angle needed to align the projection of the body x-axis + * onto the horizontal plane with the psi setpoint. + * + * angle between two vectors a and b: + * angle = atan2(norm(cross(a,b)), dot(a,b)) + */ + const struct FloatVect3 xaxis = {1.0, 0.0, 0.0}; + const struct FloatVect3 zaxis = {0.0, 0.0, 1.0}; + struct FloatVect3 a; + FLOAT_QUAT_VMULT(a, q_rp, xaxis); + + // desired heading vect in earth x-y plane + struct FloatVect3 psi_vect; + psi_vect.x = cosf(stab_att_sp_euler.psi); + psi_vect.y = sinf(stab_att_sp_euler.psi); + psi_vect.z = 0.0; + struct FloatVect3 normal; + FLOAT_QUAT_VMULT(normal, q_rp, zaxis); + // projection of desired heading onto body x-y plane + // b = v - dot(v,n)*n + float dot = FLOAT_VECT3_DOT_PRODUCT(psi_vect, normal); + struct FloatVect3 dotn; + FLOAT_VECT3_SMUL(dotn, normal, dot); + + struct FloatVect3 b; + FLOAT_VECT3_DIFF(b, psi_vect, dotn); + dot = FLOAT_VECT3_DOT_PRODUCT(a, b); + struct FloatVect3 cross; + VECT3_CROSS_PRODUCT(cross, a, b); + // norm of the cross product + float nc = FLOAT_VECT3_NORM(cross); + float yaw2 = atan2(nc, dot) / 2.0; + + /* quaternion with yaw command */ struct FloatQuat q_yaw; QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c index 1c889af5d0..b0b5b3ae6e 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c @@ -107,8 +107,46 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { struct FloatQuat q_rp; FLOAT_QUAT_OF_ORIENTATION_VECT(q_rp, ov); - /* quaternion with only heading setpoint */ - const float yaw2 = ANGLE_FLOAT_OF_BFP(sp_cmd->psi) / 2.0; + const float psi_sp = ANGLE_FLOAT_OF_BFP(sp_cmd->psi); + + /// @todo optimize yaw angle calculation + + /* + * Instead of using the psi setpoint angle to rotate around the body z-axis, + * calculate the real angle needed to align the projection of the body x-axis + * onto the horizontal plane with the psi setpoint. + * + * angle between two vectors a and b: + * angle = atan2(norm(cross(a,b)), dot(a,b)) + */ + const struct FloatVect3 xaxis = {1.0, 0.0, 0.0}; + const struct FloatVect3 zaxis = {0.0, 0.0, 1.0}; + struct FloatVect3 a; + FLOAT_QUAT_VMULT(a, q_rp, xaxis); + + // desired heading vect in earth x-y plane + struct FloatVect3 psi_vect; + psi_vect.x = cosf(psi_sp); + psi_vect.y = sinf(psi_sp); + psi_vect.z = 0.0; + struct FloatVect3 normal; + FLOAT_QUAT_VMULT(normal, q_rp, zaxis); + // projection of desired heading onto body x-y plane + // b = v - dot(v,n)*n + float dot = FLOAT_VECT3_DOT_PRODUCT(psi_vect, normal); + struct FloatVect3 dotn; + FLOAT_VECT3_SMUL(dotn, normal, dot); + + struct FloatVect3 b; + FLOAT_VECT3_DIFF(b, psi_vect, dotn); + dot = FLOAT_VECT3_DOT_PRODUCT(a, b); + struct FloatVect3 cross; + VECT3_CROSS_PRODUCT(cross, a, b); + // norm of the cross product + float nc = FLOAT_VECT3_NORM(cross); + float yaw2 = atan2(nc, dot) / 2.0; + + /* quaternion with yaw command */ struct FloatQuat q_yaw; QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); From 3ccb8ea475c29e3914fb0d8e27fbdf61a6226cc7 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 21 Aug 2013 13:43:05 +0200 Subject: [PATCH 101/309] [math] untabify --- sw/airborne/math/pprz_simple_matrix.h | 88 +++++++++++++-------------- 1 file changed, 44 insertions(+), 44 deletions(-) diff --git a/sw/airborne/math/pprz_simple_matrix.h b/sw/airborne/math/pprz_simple_matrix.h index 4b6fd9be8b..b74aa6dd26 100644 --- a/sw/airborne/math/pprz_simple_matrix.h +++ b/sw/airborne/math/pprz_simple_matrix.h @@ -13,38 +13,38 @@ // // C = A*B A:(i,k) B:(k,j) C:(i,j) // -#define MAT_MUL(_i, _k, _j, C, A, B) { \ - int l,c,m; \ - for (l=0; l<_i; l++) \ - for (c=0; c<_j; c++) { \ - C[l][c] = 0.; \ - for (m=0; m<_k; m++) \ - C[l][c] += A[l][m]*B[m][c]; \ - } \ +#define MAT_MUL(_i, _k, _j, C, A, B) { \ + int l,c,m; \ + for (l=0; l<_i; l++) \ + for (c=0; c<_j; c++) { \ + C[l][c] = 0.; \ + for (m=0; m<_k; m++) \ + C[l][c] += A[l][m]*B[m][c]; \ + } \ } // // C = A*B' A:(i,k) B:(j,k) C:(i,j) // -#define MAT_MUL_T(_i, _k, _j, C, A, B) { \ - int l,c,m; \ - for (l=0; l<_i; l++) \ - for (c=0; c<_j; c++) { \ - C[l][c] = 0.; \ - for (m=0; m<_k; m++) \ - C[l][c] += A[l][m]*B[c][m]; \ - } \ +#define MAT_MUL_T(_i, _k, _j, C, A, B) { \ + int l,c,m; \ + for (l=0; l<_i; l++) \ + for (c=0; c<_j; c++) { \ + C[l][c] = 0.; \ + for (m=0; m<_k; m++) \ + C[l][c] += A[l][m]*B[c][m]; \ + } \ } // // C = A-B // -#define MAT_SUB(_i, _j, C, A, B) { \ - int l,c; \ - for (l=0; l<_i; l++) \ - for (c=0; c<_j; c++) \ - C[l][c] = A[l][c] - B[l][c]; \ +#define MAT_SUB(_i, _j, C, A, B) { \ + int l,c; \ + for (l=0; l<_i; l++) \ + for (c=0; c<_j; c++) \ + C[l][c] = A[l][c] - B[l][c]; \ } @@ -53,31 +53,31 @@ // // invS = 1/det(S) com(S)' // -#define MAT_INV33(_invS, _S) { \ - const float m00 = _S[1][1]*_S[2][2] - _S[1][2]*_S[2][1]; \ - const float m10 = _S[0][1]*_S[2][2] - _S[0][2]*_S[2][1]; \ - const float m20 = _S[0][1]*_S[1][2] - _S[0][2]*_S[1][1]; \ - const float m01 = _S[1][0]*_S[2][2] - _S[1][2]*_S[2][0]; \ - const float m11 = _S[0][0]*_S[2][2] - _S[0][2]*_S[2][0]; \ - const float m21 = _S[0][0]*_S[1][2] - _S[0][2]*_S[1][0]; \ - const float m02 = _S[1][0]*_S[2][1] - _S[1][1]*_S[2][0]; \ - const float m12 = _S[0][0]*_S[2][1] - _S[0][1]*_S[2][0]; \ - const float m22 = _S[0][0]*_S[1][1] - _S[0][1]*_S[1][0]; \ - float det = _S[0][0]*m00 - _S[1][0]*m10 + _S[2][0]*m20; \ - if (fabs(det) < FLT_EPSILON) { \ +#define MAT_INV33(_invS, _S) { \ + const float m00 = _S[1][1]*_S[2][2] - _S[1][2]*_S[2][1]; \ + const float m10 = _S[0][1]*_S[2][2] - _S[0][2]*_S[2][1]; \ + const float m20 = _S[0][1]*_S[1][2] - _S[0][2]*_S[1][1]; \ + const float m01 = _S[1][0]*_S[2][2] - _S[1][2]*_S[2][0]; \ + const float m11 = _S[0][0]*_S[2][2] - _S[0][2]*_S[2][0]; \ + const float m21 = _S[0][0]*_S[1][2] - _S[0][2]*_S[1][0]; \ + const float m02 = _S[1][0]*_S[2][1] - _S[1][1]*_S[2][0]; \ + const float m12 = _S[0][0]*_S[2][1] - _S[0][1]*_S[2][0]; \ + const float m22 = _S[0][0]*_S[1][1] - _S[0][1]*_S[1][0]; \ + float det = _S[0][0]*m00 - _S[1][0]*m10 + _S[2][0]*m20; \ + if (fabs(det) < FLT_EPSILON) { \ /* If the determinant is too small then set it to epsilon preserving sign. */ \ warn_message("warning: %s:%d MAT_INV33 trying to invert non-invertable matrix '%s' and put result in '%s'.\n", __FILE__, __LINE__, #_S, #_invS); \ - det = copysignf(FLT_EPSILON, det); \ - } \ - _invS[0][0] = m00 / det; \ - _invS[1][0] = -m01 / det; \ - _invS[2][0] = m02 / det; \ - _invS[0][1] = -m10 / det; \ - _invS[1][1] = m11 / det; \ - _invS[2][1] = -m12 / det; \ - _invS[0][2] = m20 / det; \ - _invS[1][2] = -m21 / det; \ - _invS[2][2] = m22 / det; \ + det = copysignf(FLT_EPSILON, det); \ + } \ + _invS[0][0] = m00 / det; \ + _invS[1][0] = -m01 / det; \ + _invS[2][0] = m02 / det; \ + _invS[0][1] = -m10 / det; \ + _invS[1][1] = m11 / det; \ + _invS[2][1] = -m12 / det; \ + _invS[0][2] = m20 / det; \ + _invS[1][2] = -m21 / det; \ + _invS[2][2] = m22 / det; \ } From 6ce876235b6e9df191299935d823fd22e513ce67 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 21 Aug 2013 14:48:01 +0200 Subject: [PATCH 102/309] [ahrs] use FLOAT_QUAT_INTEGRATE in mlkf --- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c | 25 +++---------------- 1 file changed, 3 insertions(+), 22 deletions(-) diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c index 39414215ce..8cc175a819 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c @@ -161,28 +161,9 @@ static inline void propagate_ref(void) { RATES_COPY(ahrs_impl.imu_rate, gyro_float); #endif - - /* propagate reference quaternion only if rate is non null */ - const float no = FLOAT_RATES_NORM(ahrs_impl.imu_rate); - if (no > FLT_MIN) { - const float dt = 1. / (AHRS_PROPAGATE_FREQUENCY); - const float a = 0.5*no*dt; - const float ca = cosf(a); - const float sa_ov_no = sinf(a)/no; - const float dp = sa_ov_no*ahrs_impl.imu_rate.p; - const float dq = sa_ov_no*ahrs_impl.imu_rate.q; - const float dr = sa_ov_no*ahrs_impl.imu_rate.r; - const float qi = ahrs_impl.ltp_to_imu_quat.qi; - const float qx = ahrs_impl.ltp_to_imu_quat.qx; - const float qy = ahrs_impl.ltp_to_imu_quat.qy; - const float qz = ahrs_impl.ltp_to_imu_quat.qz; - ahrs_impl.ltp_to_imu_quat.qi = ca*qi - dp*qx - dq*qy - dr*qz; - ahrs_impl.ltp_to_imu_quat.qx = dp*qi + ca*qx + dr*qy - dq*qz; - ahrs_impl.ltp_to_imu_quat.qy = dq*qi - dr*qx + ca*qy + dp*qz; - ahrs_impl.ltp_to_imu_quat.qz = dr*qi + dq*qx - dp*qy + ca*qz; - - // printf("%f\n", ahrs_impl.ltp_to_imu_quat.qi); - } + /* propagate reference quaternion */ + const float dt = 1. / (AHRS_PROPAGATE_FREQUENCY); + FLOAT_QUAT_INTEGRATE(ahrs_impl.ltp_to_imu_quat, ahrs_impl.imu_rate, dt); } From e52daa73de58ac3022ce5228d3f2621c7efa94b6 Mon Sep 17 00:00:00 2001 From: jornanke Date: Mon, 18 Mar 2013 21:47:14 +0100 Subject: [PATCH 103/309] [fixedwing] add zamboni_survey --- .../fixedwing/navigation_extra.makefile | 1 + .../subsystems/navigation/zamboni_survey.c | 240 ++++++++++++++++++ .../subsystems/navigation/zamboni_survey.h | 13 + 3 files changed, 254 insertions(+) create mode 100644 sw/airborne/subsystems/navigation/zamboni_survey.c create mode 100644 sw/airborne/subsystems/navigation/zamboni_survey.h diff --git a/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile b/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile index c9d42eda7b..34fd909690 100644 --- a/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile +++ b/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile @@ -19,4 +19,5 @@ $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/spiral.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/poly_survey_adv.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/gls.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/border_line.c +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/zamboni_survey.c diff --git a/sw/airborne/subsystems/navigation/zamboni_survey.c b/sw/airborne/subsystems/navigation/zamboni_survey.c new file mode 100644 index 0000000000..1bbd3e3f4d --- /dev/null +++ b/sw/airborne/subsystems/navigation/zamboni_survey.c @@ -0,0 +1,240 @@ +#include "zamboni_survey.h" + +#include "subsystems/nav.h" +#include "autopilot.h" +#include "generated/flight_plan.h" + +#ifdef DIGITAL_CAM +#include "modules/digital_cam/dc.h" +#endif + +int counter; +/** +variables used to store values from the flight plan +**/ +float x_wp_center, y_wp_center; +float x_wp_dir, y_wp_dir; +float z_sweep_length; +float z_sweep_spacing; +int z_sweep_lines; +float z_shot_dist; +float z_altitude; + +/** +static variables, used for initial calculations +**/ +// properties for the filightpattern +float flight_angle, zamboni_return_angle; +float dx_sweep_width, dy_sweep_width; +float dx_flightline, dy_flightline; +float dx_flight_vec, dy_flight_vec; +float turnradius1, turnradius2; +int laps; + +// points for navigation +float x_seg_start, y_seg_start; +float x_seg_end, y_seg_end; +float x_turn_center1, y_turn_center1; +float x_turn_center2, y_turn_center2; +float x_ret_start, y_ret_start; +float x_ret_end, y_ret_end; + +// variables used for initial calculations + float dx_flight_wpts, dy_flight_wpts; + float len; + +// constant for storing value for pre-leave-angle, (leave turncircles a small angle before the 180deg turns are compleated to get a smoother transition to flight-lines) + int pre_leave_angle=2; + +z_survey_stage z_stage; +/* +z_stage starts at ENTRY and than circles trought the other +states until to rectangle is completely covered +ENTRY : getting in the right position and height for the first flyover +SEG : fly from seg_start to seg_end and take pictures, + then calculate navigation points of next flyover +TURN1 : do a 180° turn around seg_center1 +RET : fly from ret_start to ret_end +TURN2 : do a 180° turn around seg_center2 +*/ + +/** + initializes the variables needed for the survey to start + wp_center : the waypoint defining the center of the survey-rectangle + wp_dir : the waypoint defining the orientation of the survey-rectangle + sweep_length : the length of the survey-rectangle + sweep_spacing : distance between the sweeps + sweep_lines : number of sweep_lines to fly + altitude : the altitude that must be reached before the flyover starts +**/ +bool_t init_zamboni_survey(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing, int sweep_lines, float altitude) +{ + counter = 0; + // copy variables from the flight plan + x_wp_center = waypoints[center_wp].x; + y_wp_center = waypoints[center_wp].y; + x_wp_dir = waypoints[dir_wp].x; + y_wp_dir = waypoints[dir_wp].y; + z_sweep_length = sweep_length; + z_sweep_spacing = sweep_spacing; + z_sweep_lines = sweep_lines; + //z_shot_dist = shot_dist; + z_altitude = altitude; + + // if turning right leave circle before angle is reached, if turning left - leave after + if (z_sweep_spacing>0) pre_leave_angle -= pre_leave_angle; + + // calculate the flight_angle + dx_flight_wpts = x_wp_dir - x_wp_center; + dy_flight_wpts = y_wp_dir - y_wp_center; + if (dy_flight_wpts == 0) dy_flight_wpts = 0.01; // to avoid dividing by zero + flight_angle = 180*atan2(dx_flight_wpts, dy_flight_wpts)/M_PI; + zamboni_return_angle = flight_angle + 180; + if (zamboni_return_angle > 359) zamboni_return_angle -= 360; + + // calculate the flightline vector from start to end of one flightline, (delta x and delta y for one flightline) + // (used later to move the flight pattern one flightline up for each round) + len = sqrtf(dx_flight_wpts * dx_flight_wpts + dy_flight_wpts * dy_flight_wpts); + dx_flight_vec = dx_flight_wpts/len; + dy_flight_vec = dy_flight_wpts/len; + dx_flightline = dx_flight_vec * z_sweep_length; + dy_flightline = dy_flight_vec * z_sweep_length; + + // calculate the vector from one flightline perpendicular to the next flightline left, seen in the flightdirection. (Delta x and delta y betwen two adjecent flightlines) + // (used later to move the flight pattern one flightline up for each round) + dx_sweep_width = -(dy_flight_wpts/len) * z_sweep_spacing; + dy_sweep_width = +(dx_flight_wpts/len) * z_sweep_spacing; + + // calculate number of laps to fly and turning radius for each end + laps = (z_sweep_lines+1)/2; + turnradius1 = (laps-1) * z_sweep_spacing * 0.5; + turnradius2 = laps * z_sweep_spacing * 0.5; + + //CALCULATE THE NAVIGATION POINTS + //start and end of flight-line in flight-direction + x_seg_start = x_wp_center - dx_flightline * 0.5; + y_seg_start = y_wp_center - dy_flightline * 0.5; + x_seg_end = x_wp_center + dx_flightline * 0.5; + y_seg_end = y_wp_center + dy_flightline * 0.5; + + //start and end of flight-line in return-direction + x_ret_start = x_seg_end - dx_sweep_width * (laps-1); + y_ret_start = y_seg_end - dy_sweep_width * (laps-1); + x_ret_end = x_seg_start - dx_sweep_width * (laps-1); + y_ret_end = y_seg_start - dy_sweep_width * (laps-1); + + //turn-centers at both ends + x_turn_center1 = (x_seg_end + x_ret_start)/2; + y_turn_center1 = (y_seg_end + y_ret_start)/2; + x_turn_center2 = (x_seg_start + x_ret_end + dx_sweep_width) / 2; + y_turn_center2 = (y_seg_start + y_ret_end + dy_sweep_width) / 2; + + //fast climbing to desired altitude + NavVerticalAutoThrottleMode(100.0); + NavVerticalAltitudeMode(z_altitude, 0.0); + + z_stage = Z_ENTRY; + + return FALSE; +} + +/** + main navigation routine. This is called periodically evaluates the current + Position and stage and navigates accordingly. + Returns True until the survey is finished +**/ +bool_t zamboni_survey(void) +{ + // retain altitude + NavVerticalAutoThrottleMode(0.0); + NavVerticalAltitudeMode(z_altitude, 0.0); + + //go from center of field to end of field - (before starting the syrvey) + if (z_stage == Z_ENTRY) { + nav_route_xy(x_wp_center, y_wp_center, x_seg_end, y_seg_end); + if (nav_approaching_xy(x_seg_end, y_seg_end, x_wp_center, y_wp_center, CARROT)) { + z_stage = Z_TURN1; + NavVerticalAutoThrottleMode(0.0); + nav_init_stage(); + } + } + + //Turn from stage to return + else if (z_stage == Z_TURN1) { + nav_circle_XY(x_turn_center1, y_turn_center1, turnradius1); + if (NavCourseCloseTo(zamboni_return_angle+pre_leave_angle)){ + // && nav_approaching_xy(x_seg_end, y_seg_end, x_seg_start, y_seg_start, CARROT + //calculate SEG-points for the next flyover + x_seg_start = x_seg_start + dx_sweep_width; + y_seg_start = y_seg_start + dy_sweep_width; + x_seg_end = x_seg_end + dx_sweep_width; + y_seg_end = y_seg_end + dy_sweep_width; + + z_stage = Z_RET; + nav_init_stage(); + #ifdef DIGITAL_CAM + //dc_survey(z_shot_dist, x_ret_start - dx_flight_vec * z_shot_dist, y_ret_start - dy_flight_vec * z_shot_dist); + LINE_START_FUNCTION; + #endif + } + } + + //fly the segment until seg_end is reached + else if (z_stage == Z_RET) { + nav_route_xy(x_ret_start, y_ret_start, x_ret_end, y_ret_end); + if (nav_approaching_xy(x_ret_end, y_ret_end, x_ret_start, y_ret_start, 0)) { + counter = counter + 1; + #ifdef DIGITAL_CAM + //dc_stop(); + LINE_STOP_FUNCTION; + #endif + z_stage = Z_TURN2; + } + } + + //turn from stage to return + else if (z_stage == Z_TURN2) { + nav_circle_XY(x_turn_center2, y_turn_center2, turnradius2); + if (NavCourseCloseTo(flight_angle+pre_leave_angle)) { + //counter = counter + 1; + z_stage = Z_SEG; + nav_init_stage(); + #ifdef DIGITAL_CAM + //dc_survey(z_shot_dist, x_seg_start + dx_flight_vec * z_shot_dist, y_seg_start + dy_flight_vec * z_shot_dist); + LINE_START_FUNCTION; + #endif + } + + //return + } else if (z_stage == Z_SEG) { + nav_route_xy(x_seg_start, y_seg_start, x_seg_end, y_seg_end); + if (nav_approaching_xy(x_seg_end, y_seg_end, x_seg_start, y_seg_start, 0)) { + + // calculate the rest of the points for the next fly-over + x_ret_start = x_ret_start + dx_sweep_width; + y_ret_start = y_ret_start + dy_sweep_width; + x_ret_end = x_ret_end + dx_sweep_width; + y_ret_end = y_ret_end + dy_sweep_width; + x_turn_center1 = (x_seg_end + x_ret_start)/2; + y_turn_center1 = (y_seg_end + y_ret_start)/2; + x_turn_center2 = (x_seg_start + x_ret_end + dx_sweep_width) / 2; + y_turn_center2 = (y_seg_start + y_ret_end + dy_sweep_width) / 2; + + z_stage = Z_TURN1; + nav_init_stage(); + #ifdef DIGITAL_CAM + //dc_stop(); + LINE_STOP_FUNCTION; + #endif + } + } + if (counter >= laps) { + #ifdef DIGITAL_CAM + LINE_STOP_FUNCTION; + #endif + return FALSE; + } + else { + return TRUE; + } +} diff --git a/sw/airborne/subsystems/navigation/zamboni_survey.h b/sw/airborne/subsystems/navigation/zamboni_survey.h new file mode 100644 index 0000000000..607c36a2fa --- /dev/null +++ b/sw/airborne/subsystems/navigation/zamboni_survey.h @@ -0,0 +1,13 @@ +#ifndef ZAMBONI_H +#define ZAMBONI_H + +#include "std.h" + +//typedef struct {float x; float y;} point2d; +typedef enum {Z_ERR, Z_ENTRY, Z_SEG, Z_TURN1, Z_RET, Z_TURN2} z_survey_stage; + + +extern bool_t init_zamboni_survey(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing, int sweep_lines, float altitude); +extern bool_t zamboni_survey(void); + +#endif From ac925bb0bb05d3dd6af429e7cd6136a9727fbf4f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 21 Aug 2013 15:25:50 +0200 Subject: [PATCH 104/309] [fixedwing] refactor zamboni_survey --- sw/airborne/math/pprz_algebra_float.h | 5 + .../subsystems/navigation/zamboni_survey.c | 296 ++++++++---------- .../subsystems/navigation/zamboni_survey.h | 71 ++++- 3 files changed, 206 insertions(+), 166 deletions(-) diff --git a/sw/airborne/math/pprz_algebra_float.h b/sw/airborne/math/pprz_algebra_float.h index b93cc056aa..413a1c06fc 100644 --- a/sw/airborne/math/pprz_algebra_float.h +++ b/sw/airborne/math/pprz_algebra_float.h @@ -127,6 +127,11 @@ struct FloatRates { n = sqrtf((v).x*(v).x + (v).y*(v).y); \ } +#define FLOAT_VECT2_NORMALIZE(_v) { \ + const float n = sqrtf((_v).x*(_v).x + (_v).y*(_v).y); \ + FLOAT_VECT2_SMUL(_v, _v, 1./n); \ + } + /* * Dimension 3 Vectors diff --git a/sw/airborne/subsystems/navigation/zamboni_survey.c b/sw/airborne/subsystems/navigation/zamboni_survey.c index 1bbd3e3f4d..46923c326d 100644 --- a/sw/airborne/subsystems/navigation/zamboni_survey.c +++ b/sw/airborne/subsystems/navigation/zamboni_survey.c @@ -1,3 +1,30 @@ +/* + * Copyright (C) 2013 Jorn Anke, Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/navigation/zamboni_survey.c + * + * Zamboni pattern survey for fixedwings. + */ + #include "zamboni_survey.h" #include "subsystems/nav.h" @@ -8,230 +35,175 @@ #include "modules/digital_cam/dc.h" #endif -int counter; -/** -variables used to store values from the flight plan -**/ -float x_wp_center, y_wp_center; -float x_wp_dir, y_wp_dir; -float z_sweep_length; -float z_sweep_spacing; -int z_sweep_lines; -float z_shot_dist; -float z_altitude; + +struct ZamboniSurvey zs; /** -static variables, used for initial calculations -**/ -// properties for the filightpattern -float flight_angle, zamboni_return_angle; -float dx_sweep_width, dy_sweep_width; -float dx_flightline, dy_flightline; -float dx_flight_vec, dy_flight_vec; -float turnradius1, turnradius2; -int laps; - -// points for navigation -float x_seg_start, y_seg_start; -float x_seg_end, y_seg_end; -float x_turn_center1, y_turn_center1; -float x_turn_center2, y_turn_center2; -float x_ret_start, y_ret_start; -float x_ret_end, y_ret_end; - -// variables used for initial calculations - float dx_flight_wpts, dy_flight_wpts; - float len; - -// constant for storing value for pre-leave-angle, (leave turncircles a small angle before the 180deg turns are compleated to get a smoother transition to flight-lines) - int pre_leave_angle=2; - -z_survey_stage z_stage; -/* -z_stage starts at ENTRY and than circles trought the other -states until to rectangle is completely covered -ENTRY : getting in the right position and height for the first flyover -SEG : fly from seg_start to seg_end and take pictures, - then calculate navigation points of next flyover -TURN1 : do a 180° turn around seg_center1 -RET : fly from ret_start to ret_end -TURN2 : do a 180° turn around seg_center2 -*/ - -/** - initializes the variables needed for the survey to start - wp_center : the waypoint defining the center of the survey-rectangle - wp_dir : the waypoint defining the orientation of the survey-rectangle - sweep_length : the length of the survey-rectangle - sweep_spacing : distance between the sweeps - sweep_lines : number of sweep_lines to fly - altitude : the altitude that must be reached before the flyover starts -**/ + * initializes the variables needed for the survey to start. + * + * @param center_wp the waypoint defining the center of the survey-rectangle + * @param dir_wp the waypoint defining the orientation of the survey-rectangle + * @param sweep_length the length of the survey-rectangle + * @param sweep_spacing distance between the sweeps + * @param sweep_lines number of sweep_lines to fly + * @param altitude the altitude that must be reached before the flyover starts + */ bool_t init_zamboni_survey(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing, int sweep_lines, float altitude) { - counter = 0; + zs.current_laps = 0; + zs.pre_leave_angle = 2; + // copy variables from the flight plan - x_wp_center = waypoints[center_wp].x; - y_wp_center = waypoints[center_wp].y; - x_wp_dir = waypoints[dir_wp].x; - y_wp_dir = waypoints[dir_wp].y; - z_sweep_length = sweep_length; - z_sweep_spacing = sweep_spacing; - z_sweep_lines = sweep_lines; - //z_shot_dist = shot_dist; - z_altitude = altitude; + VECT2_COPY(zs.wp_center, waypoints[center_wp]); + VECT2_COPY(zs.wp_dir, waypoints[dir_wp]); + zs.altitude = altitude; // if turning right leave circle before angle is reached, if turning left - leave after - if (z_sweep_spacing>0) pre_leave_angle -= pre_leave_angle; + if (sweep_spacing > 0) { + zs.pre_leave_angle -= zs.pre_leave_angle; + } + + struct FloatVect2 flight_vec; + VECT2_DIFF(flight_vec, zs.wp_dir, zs.wp_center); + FLOAT_VECT2_NORMALIZE(flight_vec); // calculate the flight_angle - dx_flight_wpts = x_wp_dir - x_wp_center; - dy_flight_wpts = y_wp_dir - y_wp_center; - if (dy_flight_wpts == 0) dy_flight_wpts = 0.01; // to avoid dividing by zero - flight_angle = 180*atan2(dx_flight_wpts, dy_flight_wpts)/M_PI; - zamboni_return_angle = flight_angle + 180; - if (zamboni_return_angle > 359) zamboni_return_angle -= 360; + zs.flight_angle = DegOfRad(atan2(flight_vec.x, flight_vec.y)); + zs.return_angle = zs.flight_angle + 180; + if (zs.return_angle > 359) { + zs.return_angle -= 360; + } - // calculate the flightline vector from start to end of one flightline, (delta x and delta y for one flightline) + // calculate the vector from one flightline perpendicular to the next flightline left, + // seen in the flightdirection. (Delta x and delta y betwen two adjecent flightlines) // (used later to move the flight pattern one flightline up for each round) - len = sqrtf(dx_flight_wpts * dx_flight_wpts + dy_flight_wpts * dy_flight_wpts); - dx_flight_vec = dx_flight_wpts/len; - dy_flight_vec = dy_flight_wpts/len; - dx_flightline = dx_flight_vec * z_sweep_length; - dy_flightline = dy_flight_vec * z_sweep_length; - - // calculate the vector from one flightline perpendicular to the next flightline left, seen in the flightdirection. (Delta x and delta y betwen two adjecent flightlines) - // (used later to move the flight pattern one flightline up for each round) - dx_sweep_width = -(dy_flight_wpts/len) * z_sweep_spacing; - dy_sweep_width = +(dx_flight_wpts/len) * z_sweep_spacing; + zs.sweep_width.x = -flight_vec.y * sweep_spacing; + zs.sweep_width.y = +flight_vec.x * sweep_spacing; // calculate number of laps to fly and turning radius for each end - laps = (z_sweep_lines+1)/2; - turnradius1 = (laps-1) * z_sweep_spacing * 0.5; - turnradius2 = laps * z_sweep_spacing * 0.5; + zs.total_laps = (sweep_lines+1)/2; + zs.turnradius1 = (zs.total_laps-1) * sweep_spacing * 0.5; + zs.turnradius2 = zs.total_laps * sweep_spacing * 0.5; + + struct FloatVect2 flight_line; + VECT2_SMUL(flight_line, flight_vec, sweep_length * 0.5); //CALCULATE THE NAVIGATION POINTS //start and end of flight-line in flight-direction - x_seg_start = x_wp_center - dx_flightline * 0.5; - y_seg_start = y_wp_center - dy_flightline * 0.5; - x_seg_end = x_wp_center + dx_flightline * 0.5; - y_seg_end = y_wp_center + dy_flightline * 0.5; + VECT2_DIFF(zs.seg_start, zs.wp_center, flight_line); + VECT2_SUM(zs.seg_end, zs.wp_center, flight_line); + struct FloatVect2 sweep_span; + VECT2_SMUL(sweep_span, zs.sweep_width, zs.total_laps-1); //start and end of flight-line in return-direction - x_ret_start = x_seg_end - dx_sweep_width * (laps-1); - y_ret_start = y_seg_end - dy_sweep_width * (laps-1); - x_ret_end = x_seg_start - dx_sweep_width * (laps-1); - y_ret_end = y_seg_start - dy_sweep_width * (laps-1); + VECT2_DIFF(zs.ret_start, zs.seg_end, sweep_span); + VECT2_DIFF(zs.ret_end, zs.seg_start, sweep_span); //turn-centers at both ends - x_turn_center1 = (x_seg_end + x_ret_start)/2; - y_turn_center1 = (y_seg_end + y_ret_start)/2; - x_turn_center2 = (x_seg_start + x_ret_end + dx_sweep_width) / 2; - y_turn_center2 = (y_seg_start + y_ret_end + dy_sweep_width) / 2; + zs.turn_center1.x = (zs.seg_end.x + zs.ret_start.x) / 2.0; + zs.turn_center1.y = (zs.seg_end.y + zs.ret_start.y) / 2.0; + zs.turn_center2.x = (zs.seg_start.x + zs.ret_end.x + zs.sweep_width.x) / 2.0; + zs.turn_center2.y = (zs.seg_start.y + zs.ret_end.y + zs.sweep_width.y) / 2.0; //fast climbing to desired altitude NavVerticalAutoThrottleMode(100.0); - NavVerticalAltitudeMode(z_altitude, 0.0); + NavVerticalAltitudeMode(zs.altitude, 0.0); - z_stage = Z_ENTRY; + zs.stage = Z_ENTRY; return FALSE; } /** - main navigation routine. This is called periodically evaluates the current - Position and stage and navigates accordingly. - Returns True until the survey is finished -**/ + * main navigation routine. + * This is called periodically evaluates the current + * Position and stage and navigates accordingly. + * + * @returns TRUE until the survey is finished + */ bool_t zamboni_survey(void) { // retain altitude NavVerticalAutoThrottleMode(0.0); - NavVerticalAltitudeMode(z_altitude, 0.0); + NavVerticalAltitudeMode(zs.altitude, 0.0); //go from center of field to end of field - (before starting the syrvey) - if (z_stage == Z_ENTRY) { - nav_route_xy(x_wp_center, y_wp_center, x_seg_end, y_seg_end); - if (nav_approaching_xy(x_seg_end, y_seg_end, x_wp_center, y_wp_center, CARROT)) { - z_stage = Z_TURN1; + if (zs.stage == Z_ENTRY) { + nav_route_xy(zs.wp_center.x, zs.wp_center.y, zs.seg_end.x, zs.seg_end.y); + if (nav_approaching_xy(zs.seg_end.x, zs.seg_end.y, zs.wp_center.x, zs.wp_center.y, CARROT)) { + zs.stage = Z_TURN1; NavVerticalAutoThrottleMode(0.0); nav_init_stage(); } } //Turn from stage to return - else if (z_stage == Z_TURN1) { - nav_circle_XY(x_turn_center1, y_turn_center1, turnradius1); - if (NavCourseCloseTo(zamboni_return_angle+pre_leave_angle)){ - // && nav_approaching_xy(x_seg_end, y_seg_end, x_seg_start, y_seg_start, CARROT + else if (zs.stage == Z_TURN1) { + nav_circle_XY(zs.turn_center1.x, zs.turn_center1.y, zs.turnradius1); + if (NavCourseCloseTo(zs.return_angle + zs.pre_leave_angle)){ + // && nav_approaching_xy(zs.seg_end.x, zs.seg_end.y, zs.seg_start.x, zs.seg_start.y, CARROT //calculate SEG-points for the next flyover - x_seg_start = x_seg_start + dx_sweep_width; - y_seg_start = y_seg_start + dy_sweep_width; - x_seg_end = x_seg_end + dx_sweep_width; - y_seg_end = y_seg_end + dy_sweep_width; + VECT2_ADD(zs.seg_start, zs.sweep_width); + VECT2_ADD(zs.seg_end, zs.sweep_width); - z_stage = Z_RET; + zs.stage = Z_RET; nav_init_stage(); - #ifdef DIGITAL_CAM - //dc_survey(z_shot_dist, x_ret_start - dx_flight_vec * z_shot_dist, y_ret_start - dy_flight_vec * z_shot_dist); - LINE_START_FUNCTION; - #endif +#ifdef DIGITAL_CAM + LINE_START_FUNCTION; +#endif } } //fly the segment until seg_end is reached - else if (z_stage == Z_RET) { - nav_route_xy(x_ret_start, y_ret_start, x_ret_end, y_ret_end); - if (nav_approaching_xy(x_ret_end, y_ret_end, x_ret_start, y_ret_start, 0)) { - counter = counter + 1; - #ifdef DIGITAL_CAM - //dc_stop(); - LINE_STOP_FUNCTION; - #endif - z_stage = Z_TURN2; + else if (zs.stage == Z_RET) { + nav_route_xy(zs.ret_start.x, zs.ret_start.y, zs.ret_end.x, zs.ret_end.y); + if (nav_approaching_xy(zs.ret_end.x, zs.ret_end.y, zs.ret_start.x, zs.ret_start.y, 0)) { + zs.current_laps = zs.current_laps + 1; +#ifdef DIGITAL_CAM + //dc_stop(); + LINE_STOP_FUNCTION; +#endif + zs.stage = Z_TURN2; } } //turn from stage to return - else if (z_stage == Z_TURN2) { - nav_circle_XY(x_turn_center2, y_turn_center2, turnradius2); - if (NavCourseCloseTo(flight_angle+pre_leave_angle)) { - //counter = counter + 1; - z_stage = Z_SEG; + else if (zs.stage == Z_TURN2) { + nav_circle_XY(zs.turn_center2.x, zs.turn_center2.y, zs.turnradius2); + if (NavCourseCloseTo(zs.flight_angle + zs.pre_leave_angle)) { + //zs.current_laps = zs.current_laps + 1; + zs.stage = Z_SEG; nav_init_stage(); - #ifdef DIGITAL_CAM - //dc_survey(z_shot_dist, x_seg_start + dx_flight_vec * z_shot_dist, y_seg_start + dy_flight_vec * z_shot_dist); - LINE_START_FUNCTION; - #endif +#ifdef DIGITAL_CAM + LINE_START_FUNCTION; +#endif } - //return - } else if (z_stage == Z_SEG) { - nav_route_xy(x_seg_start, y_seg_start, x_seg_end, y_seg_end); - if (nav_approaching_xy(x_seg_end, y_seg_end, x_seg_start, y_seg_start, 0)) { + //return + } else if (zs.stage == Z_SEG) { + nav_route_xy(zs.seg_start.x, zs.seg_start.y, zs.seg_end.x, zs.seg_end.y); + if (nav_approaching_xy(zs.seg_end.x, zs.seg_end.y, zs.seg_start.x, zs.seg_start.y, 0)) { // calculate the rest of the points for the next fly-over - x_ret_start = x_ret_start + dx_sweep_width; - y_ret_start = y_ret_start + dy_sweep_width; - x_ret_end = x_ret_end + dx_sweep_width; - y_ret_end = y_ret_end + dy_sweep_width; - x_turn_center1 = (x_seg_end + x_ret_start)/2; - y_turn_center1 = (y_seg_end + y_ret_start)/2; - x_turn_center2 = (x_seg_start + x_ret_end + dx_sweep_width) / 2; - y_turn_center2 = (y_seg_start + y_ret_end + dy_sweep_width) / 2; + VECT2_ADD(zs.ret_start, zs.sweep_width); + VECT2_ADD(zs.ret_end, zs.sweep_width); + zs.turn_center1.x = (zs.seg_end.x + zs.ret_start.x)/2; + zs.turn_center1.y = (zs.seg_end.y + zs.ret_start.y)/2; + zs.turn_center2.x = (zs.seg_start.x + zs.ret_end.x + zs.sweep_width.x) / 2; + zs.turn_center2.y = (zs.seg_start.y + zs.ret_end.y + zs.sweep_width.y) / 2; - z_stage = Z_TURN1; + zs.stage = Z_TURN1; nav_init_stage(); - #ifdef DIGITAL_CAM - //dc_stop(); - LINE_STOP_FUNCTION; - #endif +#ifdef DIGITAL_CAM + //dc_stop(); + LINE_STOP_FUNCTION; +#endif } } - if (counter >= laps) { - #ifdef DIGITAL_CAM + if (zs.current_laps >= zs.total_laps) { +#ifdef DIGITAL_CAM LINE_STOP_FUNCTION; - #endif +#endif return FALSE; } else { diff --git a/sw/airborne/subsystems/navigation/zamboni_survey.h b/sw/airborne/subsystems/navigation/zamboni_survey.h index 607c36a2fa..54251c6303 100644 --- a/sw/airborne/subsystems/navigation/zamboni_survey.h +++ b/sw/airborne/subsystems/navigation/zamboni_survey.h @@ -1,13 +1,76 @@ -#ifndef ZAMBONI_H -#define ZAMBONI_H +/* + * Copyright (C) 2013 Jorn Anke, Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/navigation/zamboni_survey.h + * + * Zamboni pattern survey for fixedwings. + */ + +#ifndef ZAMBONI_SURVEY_H +#define ZAMBONI_SURVEY_H #include "std.h" +#include "math/pprz_algebra_float.h" -//typedef struct {float x; float y;} point2d; typedef enum {Z_ERR, Z_ENTRY, Z_SEG, Z_TURN1, Z_RET, Z_TURN2} z_survey_stage; +struct ZamboniSurvey { + /* variables used to store values from the flight plan */ + struct FloatVect2 wp_center; + struct FloatVect2 wp_dir; + struct FloatVect2 sweep_width; + float altitude; + + /** in degrees. Leave turncircles a small angle before the 180deg turns are completed + * to get a smoother transition to flight-lines + */ + int pre_leave_angle; + float flight_angle; ///< in degrees + float return_angle; ///< in degrees + int current_laps; + int total_laps; + float turnradius1; + float turnradius2; + struct FloatVect2 turn_center1; + struct FloatVect2 turn_center2; + struct FloatVect2 seg_start; + struct FloatVect2 seg_end; + struct FloatVect2 ret_start; + struct FloatVect2 ret_end; + /** + * z_stage starts at ENTRY and than circles trought the other + * states until to rectangle is completely covered + * ENTRY : getting in the right position and height for the first flyover + * SEG : fly from seg_start to seg_end and take pictures, + * then calculate navigation points of next flyover + * TURN1 : do a 180° turn around seg_center1 + * RET : fly from ret_start to ret_end + * TURN2 : do a 180° turn around seg_center2 + */ + z_survey_stage stage; +}; + extern bool_t init_zamboni_survey(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing, int sweep_lines, float altitude); extern bool_t zamboni_survey(void); -#endif +#endif //ZAMBONI_SURVEY_H From 9500cdfae50c5b2645c672759a34f36dcb6eee32 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 21 Aug 2013 17:29:14 +0200 Subject: [PATCH 105/309] [fixedwing][modules] convert zamboni_pattern to a module --- conf/flight_plans/zamboni_survey_test.xml | 82 +++++++++++++++++++ .../nav}/zamboni_survey.c | 4 +- .../nav}/zamboni_survey.h | 2 +- 3 files changed, 85 insertions(+), 3 deletions(-) create mode 100644 conf/flight_plans/zamboni_survey_test.xml rename sw/airborne/{subsystems/navigation => modules/nav}/zamboni_survey.c (98%) rename sw/airborne/{subsystems/navigation => modules/nav}/zamboni_survey.h (98%) diff --git a/conf/flight_plans/zamboni_survey_test.xml b/conf/flight_plans/zamboni_survey_test.xml new file mode 100644 index 0000000000..c8d138668f --- /dev/null +++ b/conf/flight_plans/zamboni_survey_test.xml @@ -0,0 +1,82 @@ + + + +
+#include "subsystems/datalink/datalink.h" +#include "modules/digital_cam/dc.h" +//#define LINE_START_FUNCTION dc_autoshoot = DC_AUTOSHOOT_DISTANCE; +//#define LINE_START_FUNCTION dc_Survey(dc_gps_dist); +#define LINE_START_FUNCTION dc_Survey(40); +#define LINE_STOP_FUNCTION dc_autoshoot = DC_AUTOSHOOT_STOP; +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/sw/airborne/subsystems/navigation/zamboni_survey.c b/sw/airborne/modules/nav/zamboni_survey.c similarity index 98% rename from sw/airborne/subsystems/navigation/zamboni_survey.c rename to sw/airborne/modules/nav/zamboni_survey.c index 46923c326d..4d45187bcd 100644 --- a/sw/airborne/subsystems/navigation/zamboni_survey.c +++ b/sw/airborne/modules/nav/zamboni_survey.c @@ -20,12 +20,12 @@ */ /** - * @file subsystems/navigation/zamboni_survey.c + * @file modules/nav/zamboni_survey.c * * Zamboni pattern survey for fixedwings. */ -#include "zamboni_survey.h" +#include "modules/nav/zamboni_survey.h" #include "subsystems/nav.h" #include "autopilot.h" diff --git a/sw/airborne/subsystems/navigation/zamboni_survey.h b/sw/airborne/modules/nav/zamboni_survey.h similarity index 98% rename from sw/airborne/subsystems/navigation/zamboni_survey.h rename to sw/airborne/modules/nav/zamboni_survey.h index 54251c6303..6bfe644ce7 100644 --- a/sw/airborne/subsystems/navigation/zamboni_survey.h +++ b/sw/airborne/modules/nav/zamboni_survey.h @@ -20,7 +20,7 @@ */ /** - * @file subsystems/navigation/zamboni_survey.h + * @file modules/nav/zamboni_survey.h * * Zamboni pattern survey for fixedwings. */ From 8e84c8ecbd3346b2876d78a08cc178a6b08a81ea Mon Sep 17 00:00:00 2001 From: Dino Hensen Date: Fri, 16 Aug 2013 00:33:17 +0200 Subject: [PATCH 106/309] [ardrone] Barometer bmp180 implementation added. Also fixed a bug in the navdata driver, where cropping was done twice. Baro still needs to be tested, because sometimes unexpected things happen. --- conf/airframes/ardrone2_raw.xml | 2 +- sw/airborne/boards/ardrone/baro_board.c | 70 +++++++++++++++++++++---- sw/airborne/boards/ardrone/baro_board.h | 2 +- sw/airborne/boards/ardrone/navdata.c | 61 +++++++++++++++++++-- sw/airborne/boards/ardrone/navdata.h | 26 ++++++++- 5 files changed, 144 insertions(+), 17 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 3e461ac70c..c2bf3cd45a 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -117,7 +117,7 @@
- +
diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index 7526ac485e..95d7b6bbf6 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2012 TU Delft Quatrotor Team 1 + * Copyright (C) 2013 TU Delft Quatrotor Team 1 * * This file is part of Paparazzi. * @@ -23,32 +23,82 @@ * @file boards/ardrone/baro_board.c * Paparazzi AR Drone 2 Baro Sensor implementation:. * - * These functions are mostly empty because of the calibration and calculations - * done by the Parrot Navigation board. + * Based on BMP180 implementation by C. de Wagter. */ #include "subsystems/sensors/baro.h" #include "baro_board.h" +#include "navdata.h" struct Baro baro; +// Over sample setting (0-3) +#define BMP180_OSS 0 + +int32_t pressure; +int32_t temperature; +int32_t pres_raw = 0; +int32_t tmp_raw = 0; +int32_t pr0 = 0; + void baro_init(void) { baro.status = BS_UNINITIALIZED; - baro.absolute = 0; - baro.differential = 0; + baro.absolute = 0; + baro.differential = 0; baro_data_available = 0; } +static inline int32_t baro_apply_calibration(int32_t raw) +{ + int32_t b6 = ((int32_t)baro_calibration.b5) - 4000L; + int32_t x1 = (((int32_t)baro_calibration.b2) * (b6 * b6 >> 12)) >> 11; + int32_t x2 = ((int32_t)baro_calibration.ac2) * b6 >> 11; + int32_t x3 = x1 + x2; + int32_t b3 = (((((int32_t)baro_calibration.ac1) * 4 + x3) << BMP180_OSS) + 2)/4; + x1 = ((int32_t)baro_calibration.ac3) * b6 >> 13; + x2 = (((int32_t)baro_calibration.b1) * (b6 * b6 >> 12)) >> 16; + x3 = ((x1 + x2) + 2) >> 2; + uint32_t b4 = (((int32_t)baro_calibration.ac4) * (uint32_t) (x3 + 32768L)) >> 15; + uint32_t b7 = (raw - b3) * (50000L >> BMP180_OSS); + int32_t p = b7 < 0x80000000L ? (b7 * 2) / b4 : (b7 / b4) * 2; + x1 = (p >> 8) * (p >> 8); + x1 = (x1 * 3038UL) >> 16; + x2 = (-7357L * p) >> 16; + return p + ((x1 + x2 + 3791L) >> 4); +} + +static inline void baro_read_temp(void) +{ + tmp_raw = (navdata->temperature_pressure & 0x00FF) << 8 | (navdata->temperature_pressure >> 8); + int32_t x1 = ((tmp_raw - ((int32_t)baro_calibration.ac6)) * ((int32_t)baro_calibration.ac5)) >> 15; + int32_t x2 = (((int32_t)baro_calibration.mc) << 11) / (x1 + ((int32_t)baro_calibration.md)); + baro_calibration.b5 = x1 + x2; + temperature = (baro_calibration.b5 + 8) >> 4; +} + +static inline void baro_read_pressure(void) +{ + pres_raw = navdata->pressure >> 8; + pres_raw = pres_raw >> (8 - BMP180_OSS); + pressure = baro_apply_calibration(pres_raw); + if ((pr0 != 0) && (pressure != 0)) + pr0 = pressure; + pressure -= pr0; +} + void baro_periodic(void) { - baro.status = BS_RUNNING; - if(navdata_baro_available == 1) { + if(baro.status == BS_RUNNING && navdata_baro_available == 1) { navdata_baro_available = 0; -// baro.absolute = navdata->pressure; // When this is un-commented the ardrone gets a pressure - // TODO do the right calculations for the right absolute pressure - baro.absolute = 0; + + baro_read_temp(); // first read temperature because pressure calibration depends on temperature + baro_read_pressure(); + baro.absolute = pressure; baro_data_available = TRUE; } else { baro_data_available = FALSE; + if (baro_calibrated == TRUE) { + baro.status = BS_RUNNING; + } } } diff --git a/sw/airborne/boards/ardrone/baro_board.h b/sw/airborne/boards/ardrone/baro_board.h index 7233f8b437..cf76b5e273 100644 --- a/sw/airborne/boards/ardrone/baro_board.h +++ b/sw/airborne/boards/ardrone/baro_board.h @@ -33,7 +33,7 @@ #if BOARD_HAS_BARO #include "navdata.h" -int baro_data_available; +int8_t baro_data_available; static inline void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)){ if (baro_data_available) { diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 8231957d70..005bda75cc 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2012 Dino Hensen, Vincent van Hoek + * Copyright (C) 2013 Dino Hensen, Vincent van Hoek * * This file is part of Paparazzi. * @@ -72,6 +72,9 @@ int navdata_init() uint8_t cmd=0x02; write(nav_fd, &cmd, 1); + baro_calibrated = 0; + acquire_baro_calibration(); + // start acquisition cmd=0x01; write(nav_fd, &cmd, 1); @@ -90,6 +93,59 @@ int navdata_init() return 0; } +void acquire_baro_calibration() +{ + read(nav_fd, NULL, 100); // read some potential dirt + + // start baro calibration acquisition + uint8_t cmd=0x17; // send cmd 23 + write(nav_fd, &cmd, 1); + + uint8_t calibBuffer[22]; + int calib_bytes_read, calib_bytes_left, readcount; + calib_bytes_read = 0; + calib_bytes_left = 22; + readcount = 0; + + while(calib_bytes_read != 22) { + readcount = read(nav_fd, calibBuffer+(22-calib_bytes_left), calib_bytes_left); + if (readcount > 0) { + calib_bytes_read += readcount; + calib_bytes_left -= readcount; + } + } + + baro_calibration.ac1 = calibBuffer[0] << 8 | calibBuffer[1]; + baro_calibration.ac2 = calibBuffer[2] << 8 | calibBuffer[3]; + baro_calibration.ac3 = calibBuffer[4] << 8 | calibBuffer[5]; + baro_calibration.ac4 = calibBuffer[6] << 8 | calibBuffer[7]; + baro_calibration.ac5 = calibBuffer[8] << 8 | calibBuffer[9]; + baro_calibration.ac6 = calibBuffer[10] << 8 | calibBuffer[11]; + baro_calibration.b1 = calibBuffer[12] << 8 | calibBuffer[13]; + baro_calibration.b2 = calibBuffer[14] << 8 | calibBuffer[15]; + baro_calibration.mb = calibBuffer[16] << 8 | calibBuffer[17]; + baro_calibration.mc = calibBuffer[18] << 8 | calibBuffer[19]; + baro_calibration.md = calibBuffer[20] << 8 | calibBuffer[21]; + + printf("Calibration bytes read: %d\n", calib_bytes_read); + + printf("Calibration AC1: %d\n", baro_calibration.ac1); + printf("Calibration AC2: %d\n", baro_calibration.ac2); + printf("Calibration AC3: %d\n", baro_calibration.ac3); + printf("Calibration AC4: %d\n", baro_calibration.ac4); + printf("Calibration AC5: %d\n", baro_calibration.ac5); + printf("Calibration AC6: %d\n", baro_calibration.ac6); + + printf("Calibration B1: %d\n", baro_calibration.b1); + printf("Calibration B2: %d\n", baro_calibration.b2); + + printf("Calibration MB: %d\n", baro_calibration.mb); + printf("Calibration MC: %d\n", baro_calibration.mc); + printf("Calibration MD: %d\n", baro_calibration.md); + + baro_calibrated = 1; +} + void navdata_close() { port->isOpen = 0; @@ -146,7 +202,6 @@ void navdata_update() pint = memchr(port->buffer, NAVDATA_START_BYTE, port->bytesRead); if (pint != NULL) { - port->bytesRead -= pint - port->buffer; navdata_CropBuffer(pint - port->buffer); } else { // if the start byte was not found, it means there is junk in the buffer @@ -160,7 +215,7 @@ void navdata_CropBuffer(int cropsize) { if (port->bytesRead - cropsize < 0) { // TODO think about why the amount of bytes read minus the cropsize gets below zero - printf("BytesRead - Cropsize may not be below zero..."); + printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%d\n", port->bytesRead, cropsize, port->buffer); return; } diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index cf149b2196..8c8149c622 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -1,5 +1,5 @@ /* - * Copyright (C) 2012 Dino Hensen, Vincent van Hoek + * Copyright (C) 2013 Dino Hensen, Vincent van Hoek * * This file is part of Paparazzi. * @@ -78,7 +78,7 @@ typedef struct uint16_t flag_echo_ini; - int32_t pressure; //long + int32_t pressure; int16_t temperature_pressure; int16_t mx; @@ -89,12 +89,32 @@ typedef struct } __attribute__ ((packed)) measures_t; +struct bmp180_baro_calibration +{ + int16_t ac1; + int16_t ac2; + int16_t ac3; + uint16_t ac4; + uint16_t ac5; + uint16_t ac6; + int16_t b1; + int16_t b2; + int16_t mb; + int16_t mc; + int16_t md; + + // These values are calculated + int32_t b5; +}; + measures_t* navdata; +struct bmp180_baro_calibration baro_calibration; navdata_port* port; uint16_t navdata_cks; uint8_t navdata_imu_available; uint8_t navdata_baro_available; int16_t previousUltrasoundHeight; +uint8_t baro_calibrated; int navdata_init(void); void navdata_close(void); @@ -106,4 +126,6 @@ void navdata_CropBuffer(int cropsize); uint16_t navdata_checksum(void); int16_t navdata_getHeight(void); +void acquire_baro_calibration(void); + #endif /* NAVDATA_H_ */ From 9a864d8927679280bfec45d7223992a41d5661a3 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 21 Aug 2013 14:38:34 +0200 Subject: [PATCH 107/309] [ardrone] Fixed Baro --- conf/airframes/ardrone2_raw.xml | 8 +++- conf/messages.xml | 2 +- sw/airborne/boards/ardrone/baro_board.c | 38 +++++-------------- sw/airborne/boards/ardrone/baro_board.h | 8 +++- sw/airborne/boards/ardrone/navdata.c | 18 +++++++-- sw/airborne/boards/ardrone/navdata.h | 2 +- sw/airborne/subsystems/imu/imu_ardrone2_raw.c | 16 ++------ sw/airborne/subsystems/imu/imu_ardrone2_raw.h | 13 +++++-- 8 files changed, 52 insertions(+), 53 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index c2bf3cd45a..09f5b3f97d 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -29,7 +29,11 @@ - + @@ -117,7 +121,7 @@
- +
diff --git a/conf/messages.xml b/conf/messages.xml index 5789a130bf..ab52141ce3 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -43,7 +43,7 @@ - + diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index 95d7b6bbf6..314a6f8f63 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -32,20 +32,12 @@ struct Baro baro; -// Over sample setting (0-3) -#define BMP180_OSS 0 - -int32_t pressure; -int32_t temperature; -int32_t pres_raw = 0; -int32_t tmp_raw = 0; -int32_t pr0 = 0; +#define BMP180_OSS 0 // Parrot ARDrone uses no oversampling void baro_init(void) { baro.status = BS_UNINITIALIZED; baro.absolute = 0; baro.differential = 0; - baro_data_available = 0; } static inline int32_t baro_apply_calibration(int32_t raw) @@ -67,36 +59,26 @@ static inline int32_t baro_apply_calibration(int32_t raw) return p + ((x1 + x2 + 3791L) >> 4); } -static inline void baro_read_temp(void) +static inline int32_t baro_apply_calibration_temp(int32_t tmp_raw) { - tmp_raw = (navdata->temperature_pressure & 0x00FF) << 8 | (navdata->temperature_pressure >> 8); int32_t x1 = ((tmp_raw - ((int32_t)baro_calibration.ac6)) * ((int32_t)baro_calibration.ac5)) >> 15; int32_t x2 = (((int32_t)baro_calibration.mc) << 11) / (x1 + ((int32_t)baro_calibration.md)); baro_calibration.b5 = x1 + x2; - temperature = (baro_calibration.b5 + 8) >> 4; + return (baro_calibration.b5 + 8) >> 4; } -static inline void baro_read_pressure(void) +void baro_periodic(void) { - pres_raw = navdata->pressure >> 8; - pres_raw = pres_raw >> (8 - BMP180_OSS); - pressure = baro_apply_calibration(pres_raw); - if ((pr0 != 0) && (pressure != 0)) - pr0 = pressure; - pressure -= pr0; } -void baro_periodic(void) { - if(baro.status == BS_RUNNING && navdata_baro_available == 1) { - navdata_baro_available = 0; - - baro_read_temp(); // first read temperature because pressure calibration depends on temperature - baro_read_pressure(); - baro.absolute = pressure; - baro_data_available = TRUE; +void process_ardrone_baro(void) +{ + if(baro.status == BS_RUNNING) { + // first read temperature because pressure calibration depends on temperature + baro.differential = baro_apply_calibration_temp(navdata->temperature_pressure); // We store the temperature in Baro-Diff + baro.absolute = baro_apply_calibration(navdata->pressure); } else { - baro_data_available = FALSE; if (baro_calibrated == TRUE) { baro.status = BS_RUNNING; } diff --git a/sw/airborne/boards/ardrone/baro_board.h b/sw/airborne/boards/ardrone/baro_board.h index cf76b5e273..d98a771108 100644 --- a/sw/airborne/boards/ardrone/baro_board.h +++ b/sw/airborne/boards/ardrone/baro_board.h @@ -33,10 +33,14 @@ #if BOARD_HAS_BARO #include "navdata.h" -int8_t baro_data_available; +void process_ardrone_baro(void); + static inline void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)){ - if (baro_data_available) { + if (navdata_baro_available) + { + navdata_baro_available = 0; + process_ardrone_baro(); b_abs_handler(); } } diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 005bda75cc..831a492367 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -170,7 +170,6 @@ void navdata_read() port->bytesRead += newbytes; port->totalBytesRead += newbytes; } - } void navdata_update() @@ -187,11 +186,24 @@ void navdata_update() // if ( navdata_checksum() == 0 ) { memcpy(navdata, port->buffer, NAVDATA_PACKET_SIZE); + + // Invert byte order so that TELEMETRY works better + uint8_t tmp; + uint8_t* p = (uint8_t*) &(navdata->pressure); + tmp = p[0]; + p[0] = p[1]; + p[1] = tmp; + p = (uint8_t*) &(navdata->temperature_pressure); + tmp = p[0]; + p[0] = p[1]; + p[1] = tmp; + navdata_imu_available = 1; navdata_baro_available = 1; + port->packetsRead++; // printf("CCRC=%d, GCRC=%d, error=%d\n", crc, navdata->chksum, abs(crc-navdata->chksum)); - navdata_getHeight(); + //navdata_getHeight(); } navdata_CropBuffer(60); } @@ -215,7 +227,7 @@ void navdata_CropBuffer(int cropsize) { if (port->bytesRead - cropsize < 0) { // TODO think about why the amount of bytes read minus the cropsize gets below zero - printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%d\n", port->bytesRead, cropsize, port->buffer); + printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%p\n", port->bytesRead, cropsize, port->buffer); return; } diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 8c8149c622..ec40241dcc 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -79,7 +79,7 @@ typedef struct uint16_t flag_echo_ini; int32_t pressure; - int16_t temperature_pressure; + uint16_t temperature_pressure; int16_t mx; int16_t my; diff --git a/sw/airborne/subsystems/imu/imu_ardrone2_raw.c b/sw/airborne/subsystems/imu/imu_ardrone2_raw.c index b43a6ab357..a16afa4938 100644 --- a/sw/airborne/subsystems/imu/imu_ardrone2_raw.c +++ b/sw/airborne/subsystems/imu/imu_ardrone2_raw.c @@ -30,23 +30,13 @@ #include "mcu_periph/uart.h" void imu_impl_init(void) { - imu_data_available = FALSE; navdata_init(); } void imu_periodic(void) { - navdata_update(); - //checks if the navboard has a new dataset ready - if (navdata_imu_available == TRUE) { - navdata_imu_available = FALSE; - RATES_ASSIGN(imu.gyro_unscaled, navdata->vx, navdata->vy, navdata->vz); - VECT3_ASSIGN(imu.accel_unscaled, navdata->ax, navdata->ay, navdata->az); - VECT3_ASSIGN(imu.mag_unscaled, navdata->mx, navdata->my, navdata->mz); - imu_data_available = TRUE; - } - else { - imu_data_available = FALSE; - } +} + +void navdata_event(void) { #ifdef USE_UART1 uart1_handler(); diff --git a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h index ce15a2c2d5..9688459bca 100644 --- a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h +++ b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h @@ -31,16 +31,23 @@ #include "generated/airframe.h" #include "navdata.h" -int imu_data_available; +void navdata_event(void); static inline void imu_ardrone2_event ( void (* _gyro_handler)(void), void (* _accel_handler)(void), void (* _mag_handler)(void)) { - if (imu_data_available) { - imu_data_available = FALSE; + navdata_update(); + //checks if the navboard has a new dataset ready + if (navdata_imu_available == TRUE) { + navdata_imu_available = FALSE; + RATES_ASSIGN(imu.gyro_unscaled, navdata->vx, navdata->vy, navdata->vz); + VECT3_ASSIGN(imu.accel_unscaled, navdata->ax, navdata->ay, navdata->az); + VECT3_ASSIGN(imu.mag_unscaled, navdata->mx, navdata->my, navdata->mz); + _gyro_handler(); _accel_handler(); _mag_handler(); } + navdata_event(); } #define ImuEvent(_gyro_handler, _accel_handler, _mag_handler) { \ From acbcce8303f7b9134290a4b68ddbf57d0a6d14d9 Mon Sep 17 00:00:00 2001 From: Dino Hensen Date: Wed, 21 Aug 2013 14:37:13 +0200 Subject: [PATCH 108/309] [ardrone] Rebuilt modules for ardrone firmware 2.4.3 and removed unneeded ones removed modules are already included in the firmware since 2.4.3 that we know of --- conf/Makefile.omap | 8 -------- sw/ext/ardrone2_drivers/cdc-acm.ko | Bin 192488 -> 192400 bytes sw/ext/ardrone2_drivers/cp210x.ko | Bin 146119 -> 0 bytes sw/ext/ardrone2_drivers/ftdi-sio.ko | Bin 280807 -> 0 bytes sw/ext/ardrone2_drivers/pl2303.ko | Bin 178489 -> 0 bytes sw/ext/ardrone2_drivers/usbserial.ko | Bin 510128 -> 0 bytes 6 files changed, 8 deletions(-) delete mode 100644 sw/ext/ardrone2_drivers/cp210x.ko delete mode 100644 sw/ext/ardrone2_drivers/ftdi-sio.ko delete mode 100644 sw/ext/ardrone2_drivers/pl2303.ko delete mode 100644 sw/ext/ardrone2_drivers/usbserial.ko diff --git a/conf/Makefile.omap b/conf/Makefile.omap index 361ea419ed..f53a726bc0 100644 --- a/conf/Makefile.omap +++ b/conf/Makefile.omap @@ -95,10 +95,6 @@ endif { \ echo "binary"; \ echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/cdc-acm.ko /$(SUB_DIR)/cdc-acm.ko"; \ - echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/usbserial.ko /$(SUB_DIR)/usbserial.ko"; \ - echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/pl2303.ko /$(SUB_DIR)/pl2303.ko"; \ - echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/ftdi-sio.ko /$(SUB_DIR)/ftdi-sio.ko"; \ - echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/cp210x.ko /$(SUB_DIR)/cp210x.ko"; \ echo "put $(OBJDIR)/$(TARGET).elf /$(SUB_DIR)/$(TARGET).elf"; \ echo "quit"; \ } | ftp -n $(HOST) @@ -107,10 +103,6 @@ endif -{ \ echo "cd $(TARGET_DIR)"; \ echo "insmod cdc-acm.ko"; \ - echo "insmod usbserial.ko"; \ - echo "insmod cp210x.ko"; \ - echo "insmod pl2303.ko"; \ - echo "insmod ftdi-sio.ko"; \ echo "chmod 777 $(TARGET).elf"; \ echo "./$(TARGET).elf > /dev/null 2>&1 &"; \ } | telnet $(HOST) diff --git a/sw/ext/ardrone2_drivers/cdc-acm.ko b/sw/ext/ardrone2_drivers/cdc-acm.ko index b8db911440a2aad9094daa5aa4300a5016648c20..9270b2795f6bf165ad489adc324d3fd2a5e69cab 100644 GIT binary patch literal 192400 zcmeFadwf*Y^*(&gnR6yXGMr2@69{40Imu)~0trkmK!8BP9TYI!6z_>72pS+JL9w+O zB_JYLRJ>HNq}E!i7O~RS`qdU&Z?$T@P;XUB5~d<*#XGhr@AK?^W)f__)!+O3GTsB2xlUmZL4t`_U+g>2n{+OA$bw!Wt`a2@z8>dkhp z=rL;>_J48gSdMi#uRB3M5VV&~`h9Or><_&f#x%5GFVvGtUZ&R7UDff(!2rezPobU` z_oksu)3&2r*Bj_~#FyQ#O!`;R&o^T`#;otzu4(&0bCC7??9T^GQneWQEb2{>^HpUp z%A|jSbHNxsYkL;^Qg{77TObqk-y`Q-+jX1{oTlw@y?$no)6^O7(0obV{I|Jk+R43I zeOEAB({fHYtFyRVer5;ONqtxEChcbU#YSm|0PLOJv8jjafo-tUp~L!3 z$@X>7OQ_|_9*=f%_mN}A9#UgWJ8q2NKpa+)<-=2yoC*Kb>y!+7T2?RR&4CZ~ zU#|&$bv15}(`KIfjr$XI17ld5Xa1qLrtWd9%^QweoBjRz>uvPqbZvi-`uk5~$@LN2 z*yD`pXRrT@vHbsK%^?2D^?WVXQNs5%_!wk6nD{)xSOz_r@Z)v$(yqNu%k}XUEwkXK z8~2;ejc=!5z4)?jh?|H}*|nY0hTegTdq0Eyj(`_^BEf@tUe}3u1-mBrSggm`fvL?+sE`6SU+L!W#0FZP<@F z_nKJ8j7zMSK8`gZW!IMU`8ep3KJK=AwI$v3ajb!dn%(}KXTpaQYmItM#9F5XF{-w% z2YT`y!T!W?n)}6Z%69-dOVAU)`ZY|uJoU9YZ-8sGGuh9Feyr=`gLaHX`C9S00%NYw zX7vQ1qee%~oo$z(tzgVP#Gzm>_R$;@daj3@I_ByNY_}+HBA&~3^yxxf31|}YcHDXS zHRWfC`LgfV^@IIFE5T1Keiq~BbNX^^S9c|RnQ?uE*4A5Hzb#&cbpZW8-3*)$xsZb# zGEgo@J@>$2sMBDtp~P70tOIZ40jivZvL1UG`dQS=IPce#jR!a{BObpTHyYP>Yb|m= zN*yxhFS5Tyo?~u^dt-mVejn`RTI3qwJQAN;(}wu$82kiKSy5;cJjMA`%12BC<6aH_~9C%J~YJR?C0n8v^vNBe!<=k z{;utZPdi)VCTwRP=;}5yuEE&X#SQ00%x7zScln#$CffZDcmr>$(0c>;%!{f0X)gj? z_VZhN0$evIskI;2eQmrFV`$L5gYgXQ^xjY{<4A2!cK!A7B5i9tgL*`LU~gA2ymxCB z_Vk=I$e+{)bJbeJA%v$P$K3%!}wtj%yR@qkh27IC4kq zS0^*S$uXf*KVnw_0C*NTDh@CoDl;g< zzIXwA0^_Ilr#+yod^Wn~$1nQ=*|Gtgrn~+-rt+#&Jeot-Z ze(K@5W5=H6n9vpc|1|b}owi7Y4(X>BbWME>!Z_5S8G9+tF+R|hzS&MX@~7U9rl^>N z^>oM+cr~7|tBJA(+63m<$S;HB{f4fkat|n@4Qn@GA3vVwy)I8Pc4KmUbNAIA>O4Wq zu{VM4M&u}@^Y4Xi;UAuDUEQ9puI_C3iO1Qp-xGKde)(eD6VRcn1--w=JUX;M@8)C2 zz)L&SqTTm*=DkK&*Zsz}t{=f5hqB>wCCue9@At9aWjnXQZ;%6Orv-lw*){FdUT;TN z2K*6c5-sO0ow~X?Zb4V6=;NiFkST%JfQL7R{S^A}VE)_(ZiO6;=)<_f+~F2r)44fr zLS7wmo^$NjEoR_`IQ8xCx-RZV{+a4@b(d`0+>;GIcroxg*7$b;~8 z`@mkTVd#c?j~=+Z#{rE;>g^X8tFD*%7vwvX@Rx)gr+bwh*J3W!iO)*Zt74x?|$-rM5Wc|7|A(5(}=Exyj|lrb?JMQ;3fXWWNe$%y?v7#`D^6+~WL zfU$izQ$1DC8Gi;p0kq#dW@r57=+1a3t22HCIXCV97(VymXWrz_9_G!jqWlJa+Clp~ z`n6>3jMwU&?`SRHfwgsXdS`rpWf#U)=YG5#`BDQvCjC4n7a?cUN&^SZg*#o*45S9s9}!S7f9!0t`fUi z<{h-Frd`e0AZ?rN42|nuC-j73L*v=IPwZhI(sMkndFF5*(?7a4_XL1(Xiv@FeRa>< zGT-m&eID^w(bn~v#^(5I@SiHgcpWq*=35o(i2J5)j)%}c4ErJOcOOPhW9~-mfSe)N zfn%1qbGrV7$o>~=)+c41?zuYt7hMuf?xFF|uFkoNLp$DZUQ&#=f1yxo&w9HhOGJw->aYN4NAAwRFVi20G%G1b4<` zdpqLV-mcze%%d9R7SxAhH_14MHSN)zsYWorOV?uidmEjO_!*!>s6IrV?OH9nolPB{kowg7L6-6C}s!2Va|Tpu@`EAY8KzNL0^JR9?V9CmQJ5dW}V zQ#BO>`T0hs@;lnqtna!X`QQVsIQNFIW;E>#tRKdpH?TgDi)yt=y*9%?n74$WcP;h; z{9{^A3;fA+UN~SnQzcyp_Tm_qU<^;}#dtf~leWefY-{W{zOHF^Cvw$n@GXK2^~gsI z?S=RXCme4?zL$-kEK-nP!c4&moG-rSB8TjPb{dGya0y#}B+Bgr!GY5Xf zJe_+)m+tDaZfiWB`igExTvq3c2fjS^?v0bWdLPF6^}(-xU-?-4M8pk0{3r!BbwDq3 zCdgk>aTd#KYq>C!=KEqt_-Zl;E}J6HPzil9|G@W3NnT7j@y<57uAH9TnthH|L z2Zr-#w;yH9v)iL}=@$D&JESjY*w@NoQw)2E`CS;fZ3@QM9h^N~8E`Ly^8sa8B=6#~ z-7@n@@;~~r(|L_KrxL|Lo>!G{}eZOh`JCLtZkGEhACgi!0V|-1f4%mmb zfuHBlKY16~U#^S3W{3C6lpPM@lXmD&``_*qH{t%wuicom=N*#I#(0#>JoUx0qY z&JOGe3wyCHJ-SwFWMUn2KWNm}$GIn9Egte)I3t4>`8fUgfF{9*;|3rH_X?K#?;~Hg zRpQPRX9S%6v8P~tQ~!)hhzWN~Th?Q2bK}7d*p+v&^aa|MdN(^Z#5-VD>c78j@!aE3 zfBfHcoVm5LhvWFVHsRiTQTKZ65C7@;1IPHLHO|;@c$Ryot0M{<4wjU7w0k<;qfFIX@2@?Y-c(LZ^woQP$Nga4=Fa=dKoF}bfL_*~}l znTEz)&?s>R!yQMoDf&*e( zEprU+46!$muZeSw^b5op<{{i8uK(AucTdE#j{$+LJ$~c@DabjPBS?M1&v4J1Ismx? zeeV(H&F=KroAHNDbxzvjJl?H=-Wz*7o&tN2AM=_^!SgcrPU!O)*e~jEH)7yEu0!z+ zAigaw-x)W`*6%mn`;hNqoP@sC$+C)bJ3wm`UD3M(&mKI8ZT|Ys9t-&n<4<_X1~j5sw}+q4yIm#oavaIhl`SJ1=3)U4iFee~|PETj^%&-W`VC`CM%dXcPChnRs?E zhiAh59X;EyUQDN}dpkcdpAP7hw&}#@rURYvE%;$f3GMCb?YINa38t0o=ktzB|GcHg z+`Bn`;76Co59*i4J09zduX_y7EpX2EV|{*voQ!;AU&z17+#bJnTAu9tT<+z_^E=`N zo-5)-y?BljLSMwj5YDuEzrI{oT1@G`67x53#;By8p#OyKeUM%H2yFY`p65Up$2|+9 zJ(O=D7p&XgJKMcOpYN`I8~wdB2CwgqC>A}6?3#%`8Plo_L0_Mtr2Eo;s;=??+z z+P-*Fez%C;agO)?<$`YP)n< z{#qUt;G9|ze>%E)Z=O}OzcawQn+5V7O-Ea2Y!mJ*w#Rvowhqs|_#Deq-<9Wel+HWq zH+^G_=AMYij623fJ$lQPndvPlnLUX4|7&c=`rU_Im-CvAzS6d}UAIc^85&`#3m5QCI8W_soy^EUpN5Fo`>qZ{o*$ zcFKpG{!qQ6?!tK&%{%b5sMl(7-s+c2{kJ`mbNAME{RsQ?q0HL-T>po%@Ci>mg!*pA zi6gFW(*NeoukE1^np)_9)DdC^a>2XznOVvE_I;IE@~*woy=#xb?^|ls-dU8zxhL+_ zy1M63Uf90~_fcFs3AzFZkON^jW;6DtQ0wr=r7OCOE_2X zs@odJq4izHj{eVn|KC0nT;C%jhFkI?o~=FWIp{eDj=bp0@VZ3XtG z2kUmmAFSVrXG9&iFU1{X9qz4Az7uv^j8EEcDLy^;+%tABVrWWI4FKEPN@n@oVeC;m-FIR?Np{S1`n;fFfPuH6~uKBCrMA7APUb-062eNyh% zFWm*j?vt`*Q>s6U;yLa#IxWxT@5T8Hu-QQ6F0eA1dtE1Wdd{BPg-O&LVcJIEs zV-FU}?%nrxEXCxAJK+rXpx;yYWPJ#Wiv6qI&qjQb?-q&g?Qozh($)FUFXjG@dMwD@ zcUc{e@$)`^hl7VXcX{sb=)x!e9l@vMhs(L$yLWYL!^H-%4^LqDS%=TN)9>$S#=}U& zW$geSrf^%cU&3K4}n5kXju>S6j!|vynJWab7GPe2#)g*mrq(vCVQu@0HLa7Tw60pY z+L^f)RqZ8CUBiW7F|T3Sil*~RoD?y%4ucO#!QWk9TOWrZhBc&c}3+oP0e#{+c^_1 z9MLkOaYW;?5shv5X&JF{S*(0z8-KOL#*X-wgk!!fVdb|atoXKs<=>XD>^Q=*sZ*!6 z#A30Ew8*vj%T-%Og|TJ`NoE5AKy*|#9A zidD2!#KwOMS>?3GL0jK~>y&9TTFS(mAAyo zzm*TnsG8nV@vVFyM$&KTSykg=B>mr%)!5Y1w7Rivl7{8Hs^Q#~%O;hN8at|@eAM{T zbITeV%NoiXoR-$6rd2KN3@~S}UEREDp-+uZIP*XNX`m933VBHkg8wKgqpYHeD* ztf?)vAM4YaTGu$uO{>oZn{Om;JAY+M%gWW~I_EaDp3`t{Q-4PD*0eS`?TB^Gn$=Ct z+SLeP{TP-w$-bjTjq2ZT@rspgAiNO4&sl~@xu)G|T!T_`a~n80E8FpL(dtpooOTC< zY;I8Tm|Q9o8k)c6KMdL4)YeXE8OE12FwnO{V`{AaofEO2@x8I3y}?#&V9U+h#kuzJfHusBZ7tJgqk@LCRwJJ>8;F+fuY zR62Rp+V-Y(TJ_k(gxcFLo-%D-v~hymfKcp{JLwiv*0!%{StUJTEm&g{5X{xuj ztZ~`dgkb9yCpZ_zMwO49@PEJerD_*VTeB9M=Ec*nJGN;n`=NzR&C{W4?VMH98d@68 zS=qd@eI-bcMrlZyXy4;@|!Mq3-ejP{-WxoBr+nCW3F#&S5-Si?5%E zay}kytBrIp`H$_aE3QaZxpY^Uo_?|_x?5B5K2!3as(UWgz`-{0PmTLrs_#G4W&B&+ zgZWxZqNnDL>+#*dMB4qQ#%Q(j@DMEVFHu+UAL@$!t?t2m#F^v%d9+rm_}}RMXXw}U z($T-dFgUFCwK}Pxuhq$3U#p`VeZ4QT?|-X9#{JFz63gV9DgS?pZ=(SkhesD0Zr1!I z+M)A2m!15R@y7-~a=ZW2-7inuxoqGTJwuP$!8DIO)XvZs>Px%TNhw5)reR@t>m69RzjemgULGy!xARN9hM}vD7|o*TZ(J0E2aybzSgv~ zfoc9Uj-2PxNR{O$CnDKJf>197K{)1|B*4mwnu+;Jvce*?g>f-5JXtSwS>%of)_vm@ zOWT3T2#n?HQ`$&ZSCV5%pWvES+9$TAjdG18$ws^8#{6(WPzVnz>+9GzWI2b_w2I^u zFrP{QA8jj zvogT;)PCHg;ZI`)0}&*EtDfG!9WPChx2By*VekTrlnEo9-8Yidr5vZePv4w)Lx09p z%sKrkApbHl<3t+MFuJBSshN{zrVvpOatNPuqa!^;0i+o}ZYy zrZsaEGG8?ebt)h=vxfDYjZ#Dl>ox6yQLcfMzqEosqal2Xqqp^+5}CIr$>msU zT?d8lD?Mr2g?$p%__-=C%EMw_=hlL+s=c^>1&7j(+c`3Ixo`As7@ow2VJ0>VE3sjC z)rOJMf5Y(gZ5RXkZy2flH;A;ppvLg&R~rQOkp4S>t@f_;#6}S43#4)fVK~ZETS+h( zGo|N+60tNZSud9Wc8~r$&fw&DvKRId87`nHxtqvV#x2>J(-#!kIyABWh1LFtJwyd| z+Dh~fskuo$QijC-0hj9wu6cbsSAHV2M-tmwLH`Xf+BXGFEBv~}htuLk{S8b%DDESp zy+`!H8tLiUhF6g(peM5fX1n_1xDP!acbtiTRWcIT%WXdk4MzgEq6qu->dj z&3#KzGkAxrNqJ~EYQ}<@f53@|O61vTFrr=li@SOMGEZ%*DA)Wka!p;!Vj0<`wvDaS{1s%Ex|YRC^6`yF z7B8DMWpFeho2lY-@6Nu`zWbRtF#t1Z;eJx4qJUc#Jp@F#XVMsVy>+H z^LP~V7J`Rw_H+~@viM;b#R5q%a}YF?d6(b~{HOL3;k+N7c2E}rU?E4r4 zrDy(<#e1Nl^sHyeeNH}#gDI@92hykKoXTPe43eIUSKl?CKMlqFbc3cdUWf60{&A=& zxR;Ihzy#^hU$b}?d?CI3_bgt6bR~UaBa5pzQtcWR+iet2_zsJI!|c*GkEAF!vUs&D z9)-2i@4A+?%a@>dx0LlHC?)*?IhkK$`ssUQ@i9z4{WsLK&nQFj;aec!Kr{WfPvXDwqsCp9#wzt0mm1q%HVAfPMd4uCQm(uMKoEhVaRTeJgx7BZoyW$h@$jS<4v8 zDH##dz8ure2rJ~Xt8oC$7^aZl*5MHu0^eu_Wx&qC!-tGq#U&fUlL|8Czt15~j-WB} zg(TJN-$Dl&1%u$Q9HL_;P?2Ke(}JI8LQ9!8TkYMm5JS^xD^BfSc|ZYrAi7}$avm7U z71LND}0It+U-yee3r zV5eaph8)2n1veS?nGRsFf?MEJFQVIAFp^G|s|_81fQNBnO{g0@d^U*74p5k2E|jz- zIKG49e_D%*2`plK&76w%Z3!Ovc;(h1Y0W)J(%J-R_?~n&&3O(@iu(z2p!~sLcp`ad z!Bvwq?ZM!p6fXvv00RdXv&e~FJ{@SuFd$4+xBr2K7(BT`!ri(OgN<@3>GHQ*OB#ti z@;9bUk*6hUb;b_%d6^ zX@=Ce5%FiXR%u35wFEL-$7@ER0-?;dX3ZF`Kz8Qx7R``mF(Tp2HUMc9BjRMXEYpk; zimbqX81d2=Nnwmgk!G^`Uwv}tWRz;!LBlA23qBwhqfw!J6>AE6r%{>k@dg;t7{e(W z5ue=)vl(N*fOkS-`vCNAj6+@o6v$lGvQ{&yT$ydWtf(2|U7_uAN;6@;#$k zYMX0cng&#zCb`tvU(E-aq-3eLZ&?U5nN~LouEii^rODFV1c6)5D z6Jt7E-xJwuX~PD<%#J7YJCouHzKjyuYhJgJtTfR!2Jlg{SenQbOA#DGzc-&Di-=D! zI)(lqjg5JVXHElr%!L7QDcPn4d1L84KEOlY6-*@{}$P<7sW^ z?~;`#@{BIJG2hVJ=EiKcKd+0|Kp6VOJOIUdBKvglE>>vhQ}dmRiQmw3SFO@QpPRGV z2@mVymoQiof1-;iP-N(za$26q5nU9F2mY6fkLu##lltKfL(IlQd(ZIFG<}LdPUF^;}P6i{XsG))rC=%+!Uf+DR!4x!O#9n5;SlUK8@VRbf`;wybQ_ zLO$ys7{U|TW{7FnKSBdsyxkB_!reky77g!-+-wLN-*gBKa`6sBbk79Nv6O1M4DkT$ z9vbT6y9`m}0Eb=r-G=yts*Skqdkj&?xfZziVI%jP_BJgv!n#eG>M=uDC!oF5`mw}M z86vv|c$7>3o*`;*s}+h_?|+x_ePW1;EZ{QhGYkV=8v@s_TBzK`M-8!)@>g2vYuVo6 z5!cW*3Eb%szrZp{;!PfrO4mrVZ}Er^>E2`9{@Xm_1!{S$i?@43-rRopW{>cc0FSe{ z3O$h>9&sgIJb}AB;wj2sWpShQMDFm2HPe8{yZBy@_&5)EqT7FuNBkN-nZyrz#01JW z$-4hC_TTFf#aM@-$<|BoP`Iu~{FII{#rh7m5l`fxM-U%+4c1>I{i~+P2M(Zj${C-nZ(7h7)peb%z0^H=bA2!8#G~aS- znq0|8Oz}T4;1#a8n=GModMmAQ@Mnmb z!1r5k$@W(*VKXW};Og@YOYDK&Lwl?PvVFfLM#1kxzqI}+?R&ryKc&1+Schdh@GH1B z4n6HI_k)(WpZ5NfbyT(=w!{lut}k2MZLs{U+}34lwa_cpGcs}?vBa-%lnK3Iy)cFC z9bWO{;lRCCv(!(gSNx3jeb1F|n^)Y2g&KO_#oN8&LoTNetbtPhH+#j$U=*^v?sE1b zHRQG*;`WW4^cbR~xe6v9ifPI)o34cyPC#W=?qpQuHMFim(n@O&9s$~{ynldL3yz8+ zq0TBe7bNzs5va%2uH0Ph2Vw85Lb78*9o$X#%qspq360Tc8o`Cg%;=mJEo&s}NoR5} zE-@(s{%*k>FE;S3QH;`R05_f1?8i<6mom@QA+rn8z+gqWJ|rjr1j?*oFO;He}<^t%a)gCH9myC2Z^UAS`gR(h82as=5S;df9Q zEM5Q$3~@$5H8R;7l81;Tm9QBm8xrAyrzUs61BVoljLF_a_{Wea)k01Bc3}oXhK)y~ z*Q~+sA@T%y7D|5ki!9}hfS>F@^cII6Hy@%5Dc=e*`)b66Ar+h>^)K01D)yjRfOFoE zv5laU2iUt%kdA;y1_xk6bJzv?>!>UIIh;!?JemgIE!>9+qi`9Phfz2R%squ~)PfY( z6YrwMFMrW5Ak2rT2)+kZJ2^$QAeDN^DOO&i*_STGS!txo|IF+)Efmq0{d4*0&wfFE zhBBL5*J?Qnl*l}bQXtU(hdhH zFNWT&!Yg4pZ(%6{M@r%26%eH`6IvNico}S%TKEq7rWKxs#p^G;9>HT^;Q;u#U3d=ff-+h25}SX5kF<3Km|B*@X)6$0o3te~|@$E!;N_j;0O&9L;9?+AQ1y>s#9JcfiRE|L_`i2qE}tg-5_iFT4?RH41-s zDmrMvFClP2_-9N4?8C5l_-;2$*czf$_#TB!`wdJue6K=2yAa9=-^WgLQmIY83oo^a zcgBkmLkhyb_zG1xAGK)V2Pg#BRsQd=x(mX7eLRvG@fB*qSvn_!M)7zp;2;f5)xc6;c8v2m?}Y^3Qy7ZgO3rZ5*c#=XX}RnWmZ#+(ZeT6 zYHZ79F19K8Ih(h>Aw;kK&H8kz*E`HAv_rN;gAG;Xa=rdIGUHTk3{wJ1Z((qJ{ z8#l}|pgw9x;#90xPSvF0I49S5=1XvV$}I69P%%~wtHV;R@`jrXiYKmjFw}D6JQ#ph zyLJZPxyE+@k$Oq1qQ7WrQJzpj(DV%QB}lZa82}cHw61HR;RwI~SogJl&Yj9vg8# z8J=M*MwvY>84EbmI88!)jp1)_C!`Z3H4kGrDog4V*Cu2}ZApyF72exyPGCftyOD07 zFROyJCt?c|vCmPKaX^%-u&mh|;DEy2KTLc1$w2P@VcM@D0E)5fgg9W+HN<#&2Coo* z0zVKFiX{qRYP<*uZi^!7i5ZpXXLHGlneK{}mmFf2y5#Vw&T~{}_Cn&OkCu({ID? z#P)eD%E7^KLx0{7riS)wWk|;4%|H6tOn>r*(gkR*;3qJrFTd^|AH&Td7hi+nyuYUvXDEi8q|5hA3vx;?5A@CyOw^F%sz zdo~&(N3Q`NPh^vBd-4Il{DFj9bbDA8;8!Z%Y}0ekZ_y&U{`PVbZ`Xyh5UqwAj&9b) z=2~FO#XEHIF?oA+#k@-we_aZkqATuq=;Ab}H=<>sT z%#{d_k${W$=;930XSn?z)WuAWpXv60SQq>nU}TWnz84oR2#1luZu?`p_zH0-lI`-t z{mu(Tz(ZY(`<;;p5|Oa}tkeeXcdjZ2&eeIdFYkBKNT074OVz%ri^Vg6qb`0!7bj9b zMJ~Vny0`-#ki-Xc@jm4r>9!x##V2sEBz{j9S75zGM(Jm*;CQ$&dO8(2=F;QRWedW6 zq(*;9%7;srMewR5#-&R>^-=56r06x*3?}LW86YDC1?NIW2*bqbLqm6Q3#-)QHHe$Dk zoU5y#iA$RA(lgJ~Jsyt#jFF4?T(!s=eUY5+^M-hY`d_PmD977ph%*p`BNw{!dDXxQ z3PPj7i{M6eX+xSZ8~Zod7t)5Z$c5N@3eYgRFLUiuY)onL!5DMx%~;22xvI@?51j^- zr%=E)CIRKE!&OM;t!Yu!mYunJ?J8t;3We?QDWH@O$&83&7h;!6EA2EmUV%N4Tt@Rw z05^^HnH)W)`jyyEjRPv%B;}0RMTj|R<*KdHPB{^%LZK>q8;p`RmSM_>RLdZc=7!l? z8Ftbpr~onDPC?L3JL?+BbFOAyfx;#Dkvjk){;5z6B0j6U<`P63^9~e$*pK2xgh^1a zDj0+9eQ8ZEp={rdb&|GRO+>SAfxoAnt3*c_d;w1EFUU(p1hj`^!4>2y$+b+po2(T? z6f&jc1qCF7_8~z4rId9rO_r~qxe{RTR>Y)&Rh-S>46O8m)r^~3@D!-3qu|uhNa^jr zGr2r1u{&iuK&K}LSe*xShT09ViC`@ioViPy-e-RgyK2E%FM@)x)4vp`k;g^uRqw%l z3YuP(ZP|7{_RWIjoHlOz?fH)(X~S$tlF_+1POlT2xz=UAYA40)=Yr z>)^Qstq=iRX4?m61GUY|Cz@-ofO!krA1xrNvrk0KC|Ju7Vni0(PY(sU=tW90dW85^YWk!=N2zu|B1d}s3Cpg60nHA=)!=Qhu9H)$%WbC18kzveKNm+ zqlybB0{+ENiYyTP+b+?U4W-EzG4hAC{&4f3CG&#t45xLF>x{+Ir^IMs?OF* zaSf&uecez`{i?({So6`p8YPmrR(t|wMgL~--V&M+KgFVp?ss9G_=sY3yKt!(g!mNg zF_y``_2S7Qz+P9XMzPxhJYejQs#+l~hqFfGMpTM%p7;s$AN{+b%-<~D!0sP?+u(hr z5os1*z^S4K4W=I4^+fA*;CGBYSoKI3b+HeQ8$Dz!!upjv+X+y7^j(8S!gaPTZmk4< z&p02(LgKHB&pFHYjh{>+#?E#wC-M*D9*MEDZGdk?4;vRqdPMSHkl#nr8c6K*?AxZW z<56AA7>kB4j9+3>*qsgWAsi=q)Wx{dzpDcHOCtzh#r|xFN$`}Y?xE3nFE6HJONtsE zbuWu8VF@Q4^jA;hF@|8SORvcV9BfWQep;}Rj&A#*%7QD8VBQSGa>Z>L z0w-i3J^&9YxN5vaKKln;E1OS}$Z!9iYvt+&i2`;3+qSHeC}dZ1rEa}hB3=e8!ayl+ zVQCC|7W&?+M++=kO#Bx6ZZs-y1G!KvY%|e9OF67hlyHi}<=q{Ef!I?ESY)lkj1Ub( z)j+^v7iNg*HGm^5<<8mSFBma8()ts8p3A6^)+w>la12Ah7ma?vQfrWeMPdbEgbjz*F68eypQEv3OSHq9?fg4;tbS{4#o?rH)~E ztW!A(c%F5->;iHD2?pBmvh&AA#Sc%0;bWz?CA~(W?gKG@Yv@QL{wWaK$Jd+&Msa zE-Hq|%#6!NHF1{eg(9zcDQbf@e9%{z@+8WctMKMiq3>A~xqi6^7Ym}Rb>IB{)j+TTyrlLH*=c%rU2Ex zBN5(aXw-_Qd@4bV%z$0RWv?75>Q#@T&2v*#HEwp%ssu;$K zA3^-$nW`epiaS$LF-uhpMFl28Z@`N~kj-myB6#M3-@$U^xr=i)zJ)RDz1Zw?uH?gT zI@nh1D><8#eN1};tekU|LO%Ph1wdQBa3{JEvgUk$0RjmpdT1%oHboh-?|?7nT=(D_ zwq?r^IpQ3pwXtsA^szvh|Y&pHPc|a%4l*oh& zOf_(o0MyR~xEi4+c2@1A?$|HhFI|} z^agp;QhckLw`Tvt3tR0-B+36k@GriNUdI#BP&&;I1DFo7K8!-n!E@>`Z1MSYCHs2t zFK$jjC(enpEnYQHBGYa{geYE}aB{Et3v>wC;D`go2PotI1C(+;VEr%D;Bf`~Am?)I zp__cg7o34+`wGPC;#L+pf`Og7xQ%OrHy4@btX-}Zw>P6v-dykzNby?L+L@u5R3IB= zP|j5^;e8Ldcq$kiOVNVkF?WCQx;?0~A4N`EeDNPqO{1Ep#IehyIWB3H0b8x|R~%WlChP6dk+n=8RSHXRQ_(t9NtLic>2 zfI=#0lw>G`5LS-m6DkQ2t8Q7xbsKbCx4~{V`;J<$%tjx`=(nFmR4N&wPyiF748fac zVkwk_9msEUkdk2u#!qAAmWUm)GhWVWxJWC>RmiIi{~#4gEA`Gmx594Z)LNkz0ZK2- zK%QX~@=rkFvBlGfNP*Jw?|>+Cb*onDzBvWZrj?HAKsBT8N@%BatUBcRw9q#A8kEIO zBlt2)N$L34P?qg0zX|>WmZa5)8>12{&d1UgLacK?DqEAOa#*TaQ(^|e38J=$7zTg{?Zxw*v#zhm{{p7B^jQPK$z0mY*6Rojp!A87hd2S zwQL${GnX~AXrmg{du6Cyg6&~cQxRH%H`ri0Iol-AJfG)Nf>D&(_Yh9AYU6bjfEVY817VkgGd_XYtC{-x|! zWN(8~V%eX`wi5NGB7sx}?w(2J9hFp$*YpDf_ov}q#IjS)9}O|y$GR_Dng~+6u&tM! zsyxbPpMc<8cG@mEl;3^>!MV&m^9Ste#Xx7O;2g4N!B@)8y7PNV#8U?Xo&BUlVY?0S zsjU7@i5&Ybg!8h74=+`?MLSWtyZplhW#31SJ@hMXHsu>VDl+!VT9sabz5+XbA%P!R~ zCETQI`IwVd75y##Bq_3uRybAkce?8k;-z_jdv%qJnPN&7;G??AzkFg5B69Tix=O(O z;xQBO54xIkKwLi;@G)H_R@vh9Nq~>L&=DW_0iSSTk=TeNEc&dj3>4Gy9|iTg=oSwv za+l*eCA!^nCUk>XCt}ch^ajrl;b&M0;sorw(VIOylJi`4;pu=s@F)iliP3P1=q(;T zN#bL>>DUXRx5{HJyi@R+SUufSMEQtuhm6l|ljg4XC|*wL;nUBhY&J z8igD?3N4qnC{$z@lgkAP#q9U%fLax*vOi_NHnmP`wctBg?%Cy+Jx)=E1<}-@2sL{W z_Mr0174q4C!~v}Q3e_!O{}cXEzFwh_7JLhlwWXrm3pcTEfz~Q2U>i(Wv$GwbN`-X0 z0ee!#m}_O5VgC%yTQOEK!Rzc9K;sg_eFQaCR4Ej&UxIxq#w(Ow=xU5%+$)F@PK-v+O$s8zDm+D~Fa6;l+NYV%l7F;!7c zxAD%0RxwTSoNeEMMO`snp*q{<=ra^rY7az~RWVcbtG8D{ofWeb&qjL*dCtB}%Cg+9 zCz|uNbjKBVJ!b)|P;u2HD)11ezFD!<>|fbHS1aVRLr4xPwkVYaG~X!*ixpd`_Fy#z ztE>3_2juW2xK(URnBdGMK-VfU4Et<~c%5o9?eB1E*K=5=dxx;@Dz+=+*zLoBZct-Y z+3Uc+;>LvXTB)v^6soo7!G$YsPO57>&=1sjv+e!xn~GZ$IsyLwDaOj*7tpk>a-aSL zLbtds4Zbu$cXvNgLq|(>AKm-J$(T!dnhOKsM{M=GFk37v101NUOFg{Vn-6H~YVWQR z8kbhOuAa|Ti=RT3;YPsOqJ--r(+z5Mq7J!ic~Cy+Mkp7%xQ0Ud zW@)}N#E&Rdmd>rmh}3Jodrt%YmHfWS@4P7f`cEJXUIpoD%O5{?3~VBo`4cb54w@~O z`I8FyY`M&zQYc`b3M-WVQK4+L=$}@|QH%ah3KgkE|BOO0wdkMa-`3*3Bp3a23RP>t zE%4K-@|QoNC`&vT;FW5uDX!3mIozweCQc`RIkX%u59_}nzbTm@8Kys{CMT9*ta9N( zQ``=5%X3}m6Wj6u9T)n=^BgTtKOp-C#1h2p@_ZMD#HrZ6%Oft#b`Jp@$4`e!oYyIY zIvJv73ADZUo6sxqRe?8$N((X%Oo_#ND4MWUm&4Rlrr#- z)Gv|{+bMLqU$0oC`CO+QaIv4ke3re5=ANkH3DkH^~|6=_nRN!!aB zPW-q*{*HDJLx0cYxCWvgF2Iv8-43j^Yj62RGdgKP~6A8kCxh1ufqQos}RD`aa}1eXGy zsNXK3BX)7zx%#sb7KkAIa-Iu|TvJiTK9xwL`1{{0az4ta6#r|KnEYqS_So_5glK2d zNs_XJrr9tdZZ(nwoTrj#D%ukcwJF*DWU`&{ z(l5ti9hfkI@|t%6c+II??pH!rd&@7;7fgix_+^&z?&ol)I*-4VjpJ0U#dN;Aq7K#Ky!?i@Oh7 z6PU4;M++ARa}hCpm4UlaWoJ&uUslLeky^9=h+L{N*r>}`jA`u#Nea7;G^3@)D=3uk z0wy}jpnXdpT#QtAw87rms6cdtF{~OhpFRY&BMtXavEWOE(GnM$xecx7;*p2(OYmZb zzXf`UmbouL`L)p}BCm{=%b~m`+2!ArgTIgv9cNS{IE(5fXs$BOM43Ufdm7+)W1WPi zI1R>)PB1o0=o71_08TP~hJBq6d45AdYK`AX7!Yd^fTL550}_VB2XMmZ417t1#M#2Y zGKkJL7D^Zv4T}Kh8LK38#H`_f^Nm_4lFxjm3;;aI*d$wv#2eT?qjknFBrFl%qs$A9 zHzbUS916L_I4U86r~`P4D^->FXAp3y5w0cYY7sO5Pcz0zSnK-#0?bdnWy=!GbP7H~ zXF?aa+@PA&GND%dJY-2)kS#++nojK`YA#I@^SI)dzg(VtjG4a#8k`+HPpVLaVdv=i z@-Z}Ze?Jn*XtTkus&eDr3tdE4xzAn$;-dM0s|_wHp4>7Vz%|A@k~kz9Ayu@+eJ~vs zhpE2{+`a|kN7;a_Zr=hiQvkNPkFAS@57|q!-GwD$@F>8w#w4jBJW;CyywGi}l;1gs zUS!OdtySWoBDAh^2dWk)4+Xr~6{A}Gh^)RNALw$6!Yx)(J#?Cc((Xf9X_&sFG%Pj8 zSKR%aF}gmUB;vP_`VsK}Dv8uD**Xv_27UPABJKo}J?VV^dr$eAwOo35W&p||`ckl_ zhblV~f!$Ksv_y6Jl1%8uia(oFAByki z8=s(jFiA-VSCmpx{z7|CvOQdjb~OnsbH6*1fm)?p`g~u1bj?SF*PMpmDWlON#P5^9 z;b)^F|3(C^j_4HzA3BPsZP;H4iH#tZ}8ARp^908L^D*_a4G;&s?C zdZqi$KtP;52ym0@Aw^;pm-1CI;32UUrHTks>jQzsZ&T zeb=j}i`>%yw;5MMV7?Tw8VNx3I=6MM*gXUAdY5yZFbTICH%a2f;s_2L(Hq=>mWmDZ z>K(4n<9Y&A(VcGJMv;TPCHf#gu z;U~rmEZCI+%lfW>ihp(DQ9XZ*XCU;2Ef?9^+?&&1VW@2C8QYc!Lt_d5o=6 z`hrYuUt`kMl}?d-GBGBgP9G)mY2la*^_;I#UdxVgFEFbh_$wGD|5L2l`smvhU)vDF zqY&nx7004yNUCL6e#f#FsE||-5u=B!sDwT-WDelFR;`47aWS|>-?Qo^42blFfbUx! z5{ASJNRy-gaEY@;fCGJC{Y18g#rcdBhpne2bi|#EBOh6ZBrFhDbF=u^vcQpdOP|q8 zKC$v7ED) z<}quggi8g!J%d+FycbA#26X=r)Sbdd68Y)ap;ttowrD{?(?w;=&^F7v$B^m#q@nS|akfh+na0Nf;9s z5x#2ioh81?#OGVl*WA`Bv6Tb8Ze1Z;tHnK7D$&1Mw@Fwl7I6x1SdU0JU4C&O`lj`! zgtNtyT&8bXe(9Za#TUp^qkpr;N?0c@#nCpp-vLf4JQjx^Rey4+0!6zgNuL)de(9k*S_w zIHHmpda-<^pZ0i!h96-v7vZ~PH5Gs(O?4F;6MTC-TH?Ygam!f1QRZ7P8pG!29Cx&Q zYQ`%ZzD*S^GY`nt*@Az=J6djjAmLo`Xb^CMxm?0J=;bWv#pJQ=a`bca-_RK3!-!g} z%D)}!JQO`oUiB*bo$uk7y`V1nedlPiM@>o-d@dDT<>BKjXfK!VD@0d&5*OyJv|j@H zMcp{SHJ)8q0my%F1%id_MAyoTZgEE~8ZY#4%cEKNK11{(_u?8~qowz*bD>YX&am}e z7y89@VZcjV7!dw+!0)-&+S%GjU-VkfWmpZRACEx8b@Eoa^sQ2qulJ}|DfzA5rDNN9 z)ot?&_+!_q%QH>Bfid=bYC@)b17qx^c~}m-D7+0i9DA8+^V?a7DPucSTfpYj$6l`5 zLN?!g8heFm%eG&Ji;i8d+QRld9IsQgId*<7&<2DIj8I_D9SyXRPrLX4<^fo8?3D_| z?D-%XyGfxcdp`SJrBJQ?D~_;z(#7mI+kV~)bVKtcM04fiy0JH^$8~gv4oo_Q>KT0s zJ;h`4%fnvtCj1WZbp<{DbIjKlwah=FO58-h#rMrnrkz$W*rk~7Nyx9evBA%UCVznu zd!^|lNYv~{Isa@dB`2C{u7fGX`}4si&D@GInQo<5`4ddVX82xop!svz>QfTft^|H1 zLApyE5KqDtqX8F&#Evq+43{$=fN+D$G@p~K!fsZ@VUH7;GO2`%WA-&Aj>6X`+xhpD z{PGvQ8nflhz2*a`4z9;K3yd3>hJ`1;zc9{LFHWn?e_VP78n9^Oc0bPD?(smj7L&(H zWVc`s4wL4%P&rv}TN#&CB|E`1pJHMlW78;qbgW$8q8>6t$GOo<{iTU$mHYP~eA>uB zw8Gqu4y9L8-<2lc?kpWAP#$9rMtw;GzD^z;Z%#&8%l`+Gq(D@+7!rh~mrD7XzC^;yyc>GSe4aUcv1dAWh4{k-y=R}|O^3_54 zJ*w!Rybw$JK{2E6GhV8evH2NF`mFa+D21ae0*~mQy+2q)=vUkB^Io;>2IQAwqc2Fd zjNAq{nist)smd0k;Mmc9-iEc%zfW_X6B%CdVV~388^xh=lT<9+YDoc3*?tt%#v3LlZA71TY zamaXh{vRMHJim$+CHNJ}hQ?4a2W780i8TYWWX(w^o8YURkAmFka<%+F!1RIWt=2D5 zCmzT2qB~?01J6|q54X9{6!SRCAG**d_EOTFvZK0q=L-g-H-S&|VT*t0!)rc^-zsu^ zhLRsT)ckY!i$1K5k9=aPPQ*jxV-_Zc>O?C~mm~xuc2}=EjY+o4`$JwK`B?`dcEBYd zfFflUsaVM|`;$&d5;3>*dq?4yJkoN*m4boOa!IrcHB2!TCpm@xfi!5pTDDI`d2h0v zB{V&OkI;NLHVko(B-@30=A!Dpm$5*d?l~YjyeNqlLK)0Z)mY@5IP`v=WWpR(wewXs zbRCQerDW!-ef-f>o@`?7s(LYbL({xu6BAd}B;QJp7br8)t~4>1 zl&(0{vX;X!Rrd3^s+dSulEYEc=)W*Y$t=1bk?hl-@)AkO0hnMbN*YgYe&BRxvYiJ{ zWs{_K6EFTgA&FSc<7hu3_r>6MlT3I%?R!sGmM};fYSnakVD0OVrjf}e9$x#JGNya~@ zq@JnB5)}ekvh|v8B&h~tv+~PdG#Q$Pp(6D12+7PqS;cwoq>7o;KvKJjI9{BjYUdNl7l;e-)*SOzw5)_mb_*y8KMiRQQveq}g3bZ$rDU73cRVc^>vX1d1xT zb^4a$zM#s>kYhdxsw4Q34Vn1c6xgUss)nt_eS_Um2{Q2}TCo+|14@B%6*BEJV5cfa zA)j53jHxP5A-_Ee;j${9ocVbEDWb?hi8AaXsXzrUN>pHXBA2R)DpaHecfm-$@hJ~+ z@bCFFZM<&>WaQxAsQ?ervw;Z%j*&?t(vt~k*Sbu& z!%grjWY}5hKm$p}oZrBO>jYc1*_z2h`pK?ZO#G44iDi|5b~#u~9P@=@nAz5}EQw4l zd;rGqO&rDhjKSk@T%I^O9bT2!exWvT9GPjpGa%2ziR2W#6XwXS_U|EAzAj%qP^H39 zJ5DUsHn$d@Y2OsgXwt#&d{IELsjBE>GnUE^6U6XOBV4!r=Cs6h^ zVb`6M@g|Dc(C|A={{X-J{DqoN@e$-^8JIML-#d~cP0CTPttkm72_>QWTQHMyUqlzC zUBRQUV$r1GOW5uEA&gQ)ZZz8lESgEh4H5pIWb*;YGF1Evd4w9#Z;`* z$@o*la+tZ|Bo1on(29R5cgM?E!f zH=YRt@&Hd7{JX3*@2P(H6Rr_Z zexP2I3fTi=K!;~Fv0sT@4X3F2NVUc6yAYIXK31<)&b9*!fIiKaJZIZWX7r)CHX}gI zXD`aOI{C_c&FAwZ&&BppxJb93zb<@^f9x!@{r88|bjnZpqi1_$^QIXE<1mSH6)Z|DfYa1cI6r7vsyGrA5F# zoy%H&xigL^UNb<4wSn<{{tv0~R2Sp>{NF)Kje0u{nlnThrxwy^())C0 zI5$z`L=}~1l<}4OWEHh%I0q2xlT}oo;hd7uuZsFJ9LGV`AeTKAXgDhep=z*OrL#&b z8;YuIeTSUHE<^kTp{r(y`!{6p4b<>_;2c*;_y+170(hu?COk=g1NCl1qMES#M+9Cq z#4|L?Fqi%fLu^Hus}U~V52Z{3&UNttLu{gyj=oCr!&e3k^3T)fokRWyyUh#A64K-0${v%#7jLWCcr9bKw#p8g7%hx&Z9(Ia& zghnrN@y-7aZ(kl>MUlPTb#LD#_uh0ua)C<-O-Mor`xY^*NdPfyVG9rvNC+eZFhC?> z5l~UlQ3oA&QBfIX#tjuj6crUw0Tmrw2NlPS8F3l+b;jj;-&55Qe&6$ZzW=^FPv6vg z&Z$$UPOV*CT^({e^#Sf~@b-|~aUyUJgAaz>5PG|!p2oiSLN4#xih6nZ3Ay?7S8sF1 z(D9JFj+LgbsWiaV>@fPNL3PaEk0DH*SYLU?*i-yIgT!#eAp&QvA!nI%E8H95+7Vq0oZXoxEsV%EaIX6-da)5X zW>aRJdnxMKh+G2~xL+#3u8NZ`Zp`LhfDw5TS6=8&N1GkdO&yynO-s4OSjicYujnCp z5miyXxB5i*Ta?R=a6}*VrC_|!&8~1nUxV>t>W3)B5&cZl+@@q>&WJ&Zy|Hv18#{r2 zsyX`NK?Sd~ch^&Cj>o!eSV~}7AVd`h=99=BLC`Tc%*3Qfc{`3610)8A>yyY6h0Nhj z$V?Sst>X%h8sixZ-aYinRzAmYt&IH#qF&d^;-Kv*+|f$q;Qf2*CoOs$5Fy?-b4>qV zgg%2%RAsjcFoa}Tf>;~_&~}ePNNczce6ad}5S4NHB=T4xpNU^hh8jxG1wkv~;QT*L z;ba{`t6GJ2vKupjqcgJeZTeP|VBW=<$!spsZy zeU=tN1X_NAkXhF|2h^yd<(emP<%W|sB9&XfN>4%87cRc?IKndhD!z(AmR@!*2B$qM>KZM`81XsG?yEQhYkPo1)>Su$_0=rH^3Fcx&UZqC&STs&soA2az0vfMTFXxc~Kod0T=S<~rH&NSAfJ3qR;$Eld zvAjAY(9DtS@nj6BOkf_zy(e=8*>Z#64p8pWLd6oYq2zc7&M zyp#g;qDBd)p1FKUqbxmx{TpYnd_Y-@v9su~o_Gqh6n!4nkDX8(#ig7%XvTlR3AHpwDG zkuGaadjy9xKHJ0RTH%d3mQ@npg;?RnG6dUR$>5(c`z&cE)D4{xOfZ-}9%YwWvMsUz z<+vK%TFJe)KoiTcJEnXk_ffChlA!&U+^>0Irv;^7vYpM6chy&;z)E&#lkZ_!EgEg{0{BL!^r&O(x1D?`U1PAtB2y*%i_$NHFkaTA(y0Vdj zb)ChDOHrU9rl&$`2Otun*7Qd(rAmw(K?P|`YFAq$i%lFEyhfH3g2ACoGBom}42?1w zaz4NSHBwF+;F{JTw7HR|(M~+dL|Ox(A#@07q3(m2Y>#Tov%%78tx@gG5{ebxi*9UG zVg%^vkD`yw9Ub`?VaJcwF*=z+R@zYsAV(wH8GtCGQ#1-Yo6wp^r)m^)dZQN@-A1ES z=O=Vbqti5sI|okzO8-uDCY(8FL!;vwWjYV_0BWmI77S*Ej^939CIny5xLnkRa83@- z?{j`cOU&u2yAxeEa`JTDz@f}A+$w;SG~=N-W&*u$R!;wG8LEv95bdhndW4uZHjfP*j34vfhUhiIuq z$OY{P+DuwYQTqu}V_~W{7(WJ9R58JrXdn-9-vdF{PNps_P=63%THsNV5l(j_SbxtM zIv-)#N0>9*>?2IWXO^v;5qkEJ>!|6-PLV$PB0p^jP9-c}gg895AYPAzF$trNZXe-> z*v|Rza)k5Rp~JEAQj@{WTapW5m~jmlq5qoU46WzE@Be z!0#U7ft_0+613Sz#@C`Kkm{SD#3!L~BK%L`M*YzC2lN_aWC=0-iqVi5GwwxJ%AQ#6n0jj*B*mUOHfP1IR!0w z%uF*Ne7 zMgcK2@}5RPX9Thod0(TDI41Ie))E%SL_X9g;)Jpwc}%02vlVtl{;A_R&bj3MOQRHL z646H*r8@k8OysymZLI7|LO8lP(nh(UxRRqZrJ0s1SxPrhxi57^%(lv8%H5F$*v@cm zcM$cqHxLKvo(`BWFzBYEX+=617;+c31}$S@Mx014HiTsH>4;17Xz9Ni?cd z4PNTGW~^ZvqsAGC^DWT>MJ5>N)482!px@noD!66Fakjhl6u?P_8+5v$6 z=_BO^!isv7UNF+tcU7wudA^ehsGEVx{reb1?QWp4qKAQg_bd$Vk)A%&u&nHVbVK`$ zRQnRkyzJGStaxs#;vZOp=CvyBjxi}Rzg2N{6=0o#w%dh1uQxE@{=!t!{Tr1pD;Jy;Siw z)LMC~v8bZ*hNFM+S>bu;$4*aW0_pFf62waDzChS{ACC)6DM5dzBCM|#wJv=s80CF1kQ;rS8d{KEvUwp@_261?Bzy;jC8=6EBk zZED7iBN3(jk6>rqD#{07>X7kgIS?b`Z~gI!PL=UI4^DDkM@`9iK}WTmO(@}vL*JRA zD4YuPqUMDiZa~g>iTf-#Rd|~jeffQ;;I!)|_$A{N?S#0~hc0|oql7aTjVa?bjWV56 zqCl@}gs)#U)L9vCd?Z?OoxhF;@9+8!INxc5dYf@Xqh8K5rts!{lHq>Nz2v=RUU+ln zqaVn4Ti>n~J2#~Qy`vpf?4;7^|15%oxxceb2k^lc3j&s*~y?zzG4K)awiKd zCF4_#Dx7H;lRPxr*-5_|-dyJz2zjW^DWRi3)A1HMZ?IqtYIJ<)zC6_AoQqcGp%!Nd zT6f03b-dM14|v%_>zwOZGlVC{bZm(H4te}Cx}%KG8Iz}Wq|IA?Mk~be%X`old)zCO zb9XV|7g`ukS#F|52I478g7wZoJZ0&Ps_H>JWw|gL@T-5Lu=te4*+?6|@vk6!#^-cp z0eyE-g7Bcv=}jYlWXt5aylx0xQHC;0-mm%G8MMPY_Zds{FTtb?zu{wvo{O&;0kdR| zCHhhpV@M@QYFMH_N?Ve=C2gO(zAZ35W}M3Ouw;J^ddG}RIW+{wMr~=?^0N;fyD*Mp%v)&)BPv7uPE>8BdXc9t*k_ zQ=BFyGM+h1@d<5^+_SpwTFzPMLo@bMh#lN(%=&@b;V85t%y-#_Vr+{tyMs1rz&0Fo zII{Ng3!u!Jy5ajo1!5yfLHh>$h6kbZ9H(cUzaW{|`17a0N6s6Q@TKMpJOj9%F@A$? zAhvTcl#IX7JTiu!3`9sTMP}{s7vt*#csP%ojK73>&^@E4n~=`09HlicYOp56;V~hH zZ$wR>(3TOxANujd=Qcyp6NdkWo_Au}-JoJ_Oy1XpAjFd(5suD8us8AlzdYVKBrpM7z;}b6E2_M+3D4-QA$sW zGS-XoL==gR(~08Hj!{74FBH?!kE7oyo1jrDoiO@-NDSCXdocrO(vgwyf$#c&| z*{nM$v=5_2StZx#;iVAk4Sh5A}Hn`T+E4aiw-8bqd*J{L2I^=0|fKyrEx zhg^4UfaM&9cv%l)j#G^GU)Ixe!KBlH<}eSeLE&~?0IR7sJAqDlef)7BUkGq3U~l{h zpJ_$zzuN;oX`uOl*j@v}ZhbMhPZ=1KQ+DG|8<^_$$OZQq1LJP$Aix6#Cfp}a1ANiE zf|u#u%4YGpIi)#EUKNSIVa`&{cQZSH`*&aO3ut|>&MggA{4L*LLH%65Iu}3c)Azgu zE*EIy@A&izZ3UWSH8Pn_Q&T4;_-QJcR!r*PO)G9k)0&i_n-ZDzhnWK#}Hvz2cEn{_ck%S3N|Gp{2OZ0lnm-g527Ser%vV< z4V`B6OH<9Kd2mKJ`mCu_wJAtkMPd8YinKKlycq>Hb(UAOQyHz2UmjzdOuuLr`j%-u zhf4i^j@V*{4&OL(lBn6Uw(%u(I3h!|I<&>zHFxe)w}!(JvR$G{LEGP zm3kH&b3!n%{3_4Pq11BqPSKKZ-bM#hevRg3Ig@gLuG1(VCcI1&UPl9HD!-fQO6ir~ zqe~ABw^(_V?xY>q1%R)Imr2cAeu!<`8jG6=j3=y$DN6{Q8=V zWy%`3s{)>w5tT8HU)>Wr&&T};AkNS6VKnA2na;OzHV*21`Z|~=?;K@$1Dk7O=WiFU zkuMzzlKdH;L(o;*EvfM#wpU6W(C1G-m_UooBo+5di> z)l_+2<)OG!6@uUnriHanOWw4<8bIn!$m*1ifgu)%zpvf{QBJIge_+m(vfPIvu>3<| zp|^4iQPA;YX5zXb;;unGi~rMX=)uh1=49wgPkE7*{Udyu89%NX&V}xon482umOTmR zh25ty*@}N6Uy`Qo#|Hy`DwAAf*1ftv;Ae^-AVmvsOWU3RQ{6Z`6#uso#%XwHzO67} zW$%xo`NqFgJDBWxI6nTB(S+A_IWB%}pe=`R#J^Gcm94OQs1vx~8W^*(>(KwC#(loe zs7XGG>i21zEd5PX+d$iGo`R?W-#b#@uw-)?3MdiJ^L1O#yaU9$`DhUH{v$fTc)m~9 z;#7J0GTz;s%@DUb?VX8lC9C*AU+4nFZ+bmzOe^CEm_xKc95 zdqQ_0jhrh!_G3q!{#fgLaTfQP>5sM6`(8zBkna%RjxHeHAj-|z&Gezi|553W*{(40@zH{> z=(d#xV;`FzGmZEvnE~NsUZ4JWt%vc^g2&m4JiO887GlhA#aH0Dd?x6QQKDMYWL=WDIu_Y}$71;YY z7`CL{$6Dgy-9G*G(X~GP_0c^(_rIK{T_81GzH5`p^1IyE9+j21&u*6j;46LX2!Qc% zU3A3po4oSzTQ<7`N}JKt<}|6Bhf{Dvgb5n@N|NH^pd8_W2xs%-)x+XFB_YdrQ2HNKfH|}1W z3|L^_ATZ(nm+qNh;%2%dhXYPDakJdYIAEC(&UL$DUJ;*cxcP2w2f(QY_HrLU>xq}! zkBa7g?r=JKrhQmof!i_wu+siOAWwZLKqyp%oJZ9p1Y`2UG1q%kJ{{D8 zW>CZsdoIEqL7fvkZIWOWJ$$K>Q=BYJ*LSJ_nFuue-4khd-8`-j# z$}%cDx92c7j4w0qy~f?HMSxB6Y?LqJSF&0zxAjq_S-L-NHZb4a%l@jxz<%x@*=AN4 zSm-vf_N+3n*!`Tn*=hqz-N$@@YYd$1w!!cnUuR&2yPP%PYy;=IpHuU>1}@ZJ0{@HT zjy>VOIqKbE_eN%MM5^0{BiCI9u0}cVQ|xgHvHn9Sdu1kvk$dfpbPp#u@%vg|{4K;d z5x?JfHtZhbsIuMo1K;Fho_3hmf>YgHF5phlV;(O7iog!o*IG=hrE9RD>U>#Lpq)S_b zW)Q5`BWgUYZqafpxZv1a@)FKoG?`$7P9f9jhVCi2kQJD>K9}SHEz;@bA{$B27q6@o zQ}09=24jX)FmKT^8vm$J_}%9?zwr#pA%^)qXM~Rkm-qAWm(i9%`Gnl|s1XQ%k8n5% z?hQ^(MrLskI(|DSK7PnYNVhg-&N{^o&QL9&`l zyZ}5G$lHoJOE7P5S3cPoRE#w84r72x%DV*yM)2r}%_6u}y$F5MX$Jo)VYaUiOAz%A zGmo-mrV+f;%>KgeW+WcGOWyzB9BemI4&H5qdD1y8gsHpK$27G)TXNnva4T*~J50yK zuOhAD5|r;&*i@1J7qlTHnO48F&Z>xOq|3LWtyjKWIIZBRT9Ay%2OcWgQw48Hb|Suq z;*MMKJ4(P5T9E!Zdgjzw-L7S#@1v#6%I_|!ENATupziv{03Sl@2h>Av@5LHi6AI6+ z?75xMmcsnXUiax}R`@D7xUx4DrVm3q99{X$LzhBo9|qXUXHVHEIdWbt1=@eQAlo?u zB~y7o^RVG60CZ3z>|DgerSdtAaCmnT(DNF_ozL=tUeGAvOhxsnJfu;k^X)*O7d6Uq zUZ#yNX_V{S-v{V#8s$3=z7zn8&nzVdQJgeF=)1`E>_(yBP@3L z21wN<>b}bfN4uAypRD?$>_X<=>#yP7s>{@cQW6u~SDDaN>LSrx;STfzUaj=-FxR~% z4tRswDBOi^GTLa>P3EZGM)&Gez?;=3;kLM!po&y&QLl^U)$SE(fVU~WF6zr!?fw^) zy=tr67V)D&SE974{$fL6L_(l*< z;iR*ZQi}FbHRMl%;?9|!frjdOo{;y$s)lKlDLXW)hU-?HC9S%u=x&LZ zE3LY!SWD)oHKE3i+%BwMX{h<5pOSDtt0iMj;VD4p*(hihg1G$x?Y_8n`v$KN`08ENh1%_z+U*x2xxlv4Lt@* zd`~+W#2*v#i}L#_nfz)}{0HQg<39+xxan;1qPLUmSSyR3*DQL+s|mk>pU$qKpz85= zA)#IUgm$1l6{hM*?OfX_tAvxDYKI<#vm&Ye`*iJ(IUO(vRz0ovhNU|7?6{uw>U$AJ zs;d2`O1y+K1zkhc!AXKLos?lf&z)4?UpT40o6$(S`lS0Y>>bh@ar zo!Q0*D4prJDP!hF%<;;YiR$8K)->zHGXAiY&z7vS$zt>3`$5(5*|bmKpQt1Utn4MH zVVYO9T(tnWpRzWrk{%jeqx&`b`l{95oX(2R8zSzZXwa^O33zBKPAvr`{#SI5sJT}m zoPHIiHL3QguOsZdm4tDlkei;^-R_wPGXo%GAkC)5&Eyl3ck? zF4uvGWlz^AAInv!#IT=<<0S>=VhOtVOncVDpy*swa#tJ8xjh+CYsi4zva{E&)jNAr zb&~URl5w5ne4PlVmvl+D!&4C5Uho0p=S@XDv+{m{A64GNg;1EsGdl2bp0jbYaKyeR zcr8*->VXLNG04=nq7%2bYh*ipIqBqb0C-{NLwfX~m`KK)ZYWTDw@y9P*+(spJ}y?r z^LJ9qV~i)`b0YteehBW-1PsrKe7^T?KduS*U|AynjXoeep$Yh4St5ThrkeJXnt%_M zCGwNdFW7rEA%lbm;vhVw2^~nd&IMtgCL}!3l#j?La zn3v$r$R_KHopc@U$Z)k%(;$-lF`99zU8H(}<4(?oT(Nq2typbkAM0;f#r7E0<$5sN zp_<#Ld-H4e;xT}wW+~lvv$_F}H62~p?Z_H1P8}0R#@vs41CBQ^IqT2_zzJqTmjaJu zT{;SsiH73PN8J8yPcr)PaR5v>?5QdRW^xsI2a}to9=(w;*Zm43pj~d}yZLSnYu5}D zx1T${3UH2r1#ZuQfYk;Tx_Ny8Yt<1XfHR-1PMuD%tb;!LaZ&EBL|0}%VTAGd1h$eV z)gu>C*mk!~2i$Ac>f>@RYd@v9g%B0gZA&NYQwf2YSQEDFXViW%Im@kP$MmdGjANFm z>3|v-WYm1QnX#WU`Rgb5Aola>ki;$MT;J5svR_c_67VFcGr#g^zo>LeSm@4*K-J$A zcMHoq%_Bp=ht(^HjM==;ok;JzVldWj53_N;s*VUBYqzhm-+j$s>=o+5*8he&uK9j9 z!qPipUN64W@8(keO(|S|&fR{OU+}WuGWZ^U*1K82M@`vw#v981tiN{x=^aCIg>;DJ z{SQOxB&0wpNbed_rjTA`+j!5AItuAw+*H}`8&Zal*0D%GFr*G7xfkMY9V0n=G`t<^ zcNZ`d|1$45xTk-a;pRFEt5`+IC&^>-G<_4&u)_ zV!Nl60RJRIsz2wb?S6#0lKr#d^Fus;d;z7Q(OIJJ12QGuwb=7U;JJ z+)mSgm01vfFyIbmCGZ*k?m*Ta+GG1rDD36&ZhatYr;TvHkWgqK-A&&I4GDz?QVEBs zkRhSaKw>XohYbmZ2GR<;JIRnxXnO+gk?tTxefCYv(cXYNXDo2cSoll;-59%}_@Egw z+U|uTaV#0S101rAj?Ctm$|`C)L7Wps53+;!)uXyroQYtpCMo+iG|#Y|>>q>_<@uNG zn2%do?tRQ_iutM(WS64PD73Tu^C-(D0K1Eyw5!;mW<>&&^$6>D%(ITiWWA-^t6KSVg65l>qX$}9bcm<$MTE1{(Kb` z4f|a&l!ev167W3(ZTC&){Cxw%vaVo%V2TpYUO(uC8fSmxUqekYl|1g%3AcYwME%&W zw+MuF1^UEPpwz5^>>oZg{=sKmQ?0&7Irsa{e-U&A?Tz@2s!jNf@duP!@NdwH<@2l- z`!2ieRwO8&7rn>U^ACL4fhD}nMh%v_vo;0rUR&>T2)hrA2E5NeOfh_b_qVRRi|r4z zKDJoRw)LQaneJXzhh35=MpHeWJS1%gwF9FKT9>ph?3Z%)O@!=jv%=p`d+ZUDPJ#P< z5x9>UZlU{37T{yX;tH4NINDDeRkPiJlL4PGaIU+V1^29hb?)9y zfCmg*=yKz&ebAWP=yGM%e$HkE;IosXtUk}%F|nDSmt!5vj-eauXKxQME7~JF0&EPd zaL-WR0|CAS%@)tCr1tKB-a--9u6{J2=P_aJ+{aAZm^f%ppo=7y>Tc+WsE-?F+?~iW zeA2*#+f44>KsOP_M;%T9+-JC1IvY<1^sZSxV<<-jvp+;@>4*q=3LD>mF$A3>Dfs3N zGM2vXRCK6wX0HcD-ZGjqXNe`*lDCZJRBNQ1gBV@s)M(^$?i&SEtC8Q?hr*aMPb2I$ z8-sy2IH%#&R+S4iOTV}@XOTum(0(x{Q&c@V`tXUS6SQY*b9s(xtB^NByh z%Dv{8R-e9LD^c7!wRZjzt5=}9 zf&{r8s-C55lI4s?XHi|rju^F0wp~?MX%u#NUP<+AzR}H_&{0!?=I9jWI?tjiS6BZm zDbzWqz?;=I+RlZ}G2CTV&(*v}=hSSV+L2Npnw;$@pz3)VwWO_r(er(OVFIhuu*JE$ zE)4*OqxjR9pZaV;yMxZAPKdUEnFTZK{FSyeX!vv3$u9$3$hLw_8cEKZ@MrZR-pdO- zzX#xA4KGe|vN8eB(C~^Rr+Xj3My+a7lJhfjvP8qpNzOpj!s?|OZb@=p%K}`c6WW?2 zZTeL`Am}YGCkI;;cH3GOGSV!92Kw;1gd5M zuHa)T?E6S^o}d{kO^zbYbI5r0DtZk$iZ~ylSF2vF;f9FgVA-?!EDbM?I3x1_*J!vg z;+z)!9bOTUJND|entM&e;hA04>sE{AO%Z20Rh_Nj4H4%t^oZ5xXyMHf$7N+XSHmrl z{EHE)UQg%9)NgAfe-maR)#qsnW`0{E4&NQCKL42L|4YP~fLqw=3kFEB-Wfsn!AhS# z6#ad?dfX1wCfQzBJzg)w;7!Y1$WNd`u03$?XZ1wgIAUpaOKPp^GF|C#w%RIDGUfYL zC1#7OPMf|a-PBneW7~F)H&TIPew9O%Zhu3QQay%Mx5vq_04rs^V22icS zwY@PnS)(Z8FQ%fSP!wImH?OSW9mn92?q$k20^AYxO?9NyAk6&ZUx=%3!+%1T5ZPoT zFKLy$K}!ywkB&65)v)huW&g#n`=G`~o;2(Ot?a#q{V+_5ylvS3YGofa?16p3K5p27 zJ3K2tHtc6HMUQ-E*txCj?=`z{FUq3Lbe+ZV;0|tC1Wbny`D0hISaGePO*1fLbXETI zD6$Aak_WFufRte^cq=;GjqWd69e`xM#6r`6UyJ)-WD0(vlz$6T$4uf2c_MBNJxHbF zmH!Q+biAi@{O?L9{;sr4loob44G*v;$?}W;8^j#KjqKegF^Dqx3I9TT_*ocE!Xi*m zeGam}!=0=cfDAyYGya9xLWW*H3lo96lscUf9Awm8Y)OOBt*g7(G_2v=yB<$Y(mq-a zxe?rs3ko+il+a5EYuknnLt7fBB_E;2dDwgx7&j7XkbGbqX+?bQ9+<#<4dXuGz(lf( z(y~F7clux-8&%-~WB_X&-NE%AMZ_UHQds7(0_z!|)h4YW*J9N!7lL2D?#oEa)s{)$$a;@@Q?Xcb?N z9zTdG8C(zXB$*+lW?> zl&{O{ImofR^4W~7;nOm($i74AGCvO92(ANx!Z6(RIsS#XCREtc0nK-%_F2cfk%F}6 zm2A&L==bPK-R@sVLU_HFYoQ!_>F9dtDnxEQ<%%Ts`HYRCYO$ghbVqt4C)kj^depE* zR`ep4`>2s0qLD>!rl}Xgm-c@GvLNHX6`I9VP*?;dvL^mt>20myr=jN9^L@IuJOR;? zYb%8!B|LmjAIq9MSZNzSCYv^bLL*CPB*K!Lp-sief2Q*L?moI!|7)$u{UWn#o!qZ-pH(8s{U$d~Iyviv!VmZt;=nt!Ljs`&SO^KA&szn$Zpd9nA{92|uD>^A-Rnu~m7^Q1;WIJuv3L5ljn^S^ ziL9dR^fL@2xv)~4KLGvCMxRpOGF9n#Hu~7}lw`m_a9FWUTV$!rbqGVS362_*i#DpR z^>H)Vs4<;TlL7e6c>JCI`Dj2_Cr-jTT)wk$q7L4K=1yJk&Y437UUTO6(Sg6{hyD|I zoLG_Nrxhr9{IqKafl*o+7460aW!qYnjS^)IAdeSiqePjSQaXQ0oux+0n!p-xOL-^^ za8HCU!=;lNBS~!mwkD)wG*>r>&zMRs^7aD$bG|%L?7D$weF{<;oN^PrlLVQvr3T~! zOk$%@tdW+QKAH0hY>u*GxYTVqh%v>3Q(py7!41xgTXgc5DNF_^%|}ZT4Vo9Vt)&oj(uEWcS6gyX7)o*tZveWfHLNKP)l+3+m7Pp zZ~-QJlZBw^*f$60$F;=ES6b>8X>K6YE(dpthg)4ei>{``&syqrNd0gA_QZ_86>d8` ze^+uO9L;3$r|u8T_yo8s1gbbPlQA1t@HI92a^M*k;AbefQ#{U`>p`i$4L_4WuD%z6 zc?j^YW;*YA8gS$ z8i8rlXd5Y`aV7<*aWMnbcmo2)#$3qG1yC#0y`IK>l%tJD5D*)CL25mujK)tXK#eMB zH1G1+%w&F0Gp+@`i45KZka3)huhfiM z;3vT-uRuVdSI4@~Vg%=`zz_ebI19{&S;KItqQLZXfpyk7;rBSf-_-PnfbEuVlWr}) z7a=vp6d${~aY8)Eq41w=`kB%`D&0;0r|FiJ*HfJ&wyfIl&sodDl_SC<63BU@8Ee6rD$NNA}hNd0eZ zz!NhG)*~IS4T#D8prU|kE)D!|Dm)RR;(`-YST(n?I4|@omia+ke+IYnLtb6KP-YBI zfyTQ22S29)Jmh5@Z`UsN^L~v7Brf0%33Z8|b8a=Wt`J2%cU!uUc*pPsM9{3V(fz7F z`4y9iqe%rLmUT&MQh$=9@<7wtt~A=1@KuuVXz<2i{-M!Ypt{MeDP8GjN;iRs$<6js zr1X(&y<|eea6JHy?_o@CcqgNdb2G;)AT@9=qB_ofN<5!?qKq`h`FxKbT_}@imsN`Ium*qvRZ#Sn>88u?o7`kdB;e`UhuAnAmEWx@@B zI^kcL@EX7|lCY(ivL4-(jBcC2t7Ounp?N)%R?18J)Mfjl+7FjHJ@620lP+i)m{vWh1-M=T zd4bg0(g5p{nrYSYzIp?Ao9OC_!1oX-zYR2N#`X9;lkux4vk5YH;!?8$C-5&M->Uhp z4;V3}n5nr*7}7zW{wVw-)0~)0a~=UrXUvg;{yT9UJd~m+YCC|EtyDPxyf5%v-ps2u zvUz7B@!Oc4s5F`NoKJi{yY+Oz*AmODC@y#>aK&2us4`{4q=k`jm_#EX6~IsgmvP}> zFYG2MLRHW_VKg&vhGd9- zeFj$vVg(*Uot8>+25asTkQz#QQS?4&`6D5ZXw>i)K-~ZuyMwy}a1kGxC|TdfNn(q| zjk2D97|eNGy;zNuWNN;&{3<|e#zpx35L_%s{E;_#H|l#hH5jJoo6Q@gd*cn}X6ejM zV-I?>^q|(vPm2-fejSIo$cm%gLfu_YdDZ`ZKigw&DryZ*(^A{zaeF=B+*6ULdcaT7 z%Ynzu$5|h0r~iK7H_7KpHfAzh0Uz83xEeodm)P(};-5-^9}@My65o%zY4xyR9;`KY z9UeNU-TqzBhj-zvxi3e69}&Eam~~t|DtIrk3b+)n_W%k6*aaY=tY zF`qT4Cj{S3%tsLhzs~s5BR}cqqamv;_;*!-zt?|^<`BP|0Dekv6>-B%;C-TRE%94r zz)uU_L3~RV@H28}e3g2c%1aCK*b6aqY4K0pmZAFQgwg$bNVHG0!*8}u0|_!$YN{LSKeTrrw^DVzLe`z+e^J!mbI5N;DVtI56DzTV?r zLvADQsCR<2V01ayx7ZiKp8@{{Dz4vx7!TrlwUvL{iTql&cJeQ#$8NX(L(OdR4??rF z`h!ej869~9V(;NnTkTqQK?P{QTNrJJUHl}Z+k^HMr0aHrSe*lug1JX^Zv@H^fT4%M zsD!A#zujZ={&p={^;}|$!R%GSMbGh^&70wS$!z4k>z2KU){K|W)N3|pW$%Jhd*(gp zrVz_QpRPWzkI{+)prvFW@E8I;8Mq&TQ4HLUKm`NWBhbje9})N?1Lq=e3j&rnWDj&E zsPjWRigd*xJ1E9(@L7t@;>zf1h*4Di!(K?SI?#?#tO9{g8JK`Ts3QW!2y|wk0D%Gq z@)0OyAQOQG22v4NgMc-Qg|ZNeo2dL<`%j(?mr;y1Y@wLc?$HqGM^oRityvtYQ_+gD zaH)^&1B}Pfd?({^K;JLwS-W{kSOvwtv;$~OQp3LicQ$MI6pt&ldn#+Un%2bnZ5*^0 zF-w_hIM9o+S!2SO8j5ip5wL3MpwA#Cx51&ng%qQMMo^3nn!*4bRENN9I!K(ej$}IL zN(Shh2N|Gq{*Hj2jvPkEeH52U1SEr>QG^-%jUpIRdvD?Idimu8wVCrfLAtjdfjIhX z!IcKu;C;x6Ogwta(>o^g3p5S$aGTxRhr=t3I;$SV8^^1E5Uf^MLidrk@M}j{@t7 zN`H|*0&LAZ8>y)@ojOzgkrz1Ex2B#Zsq+xLv3#o&!uKH}A8%^yana5mSx?P{Gf*^u3Ma zqmrM%pfAxH8472@Z{L;pqcxt`%!7(arefp1V1+`gk8 zSEJzuxj*HBd>e78E7fzbdWwfnzCWeJ6zrWvziX}6c3+l3nf0&Qnx@#?#;hPN^*nGBf{j~ z+>e-8pL z>iArB<>@5-82>h9KMQj`e6qQeD9}<9AtmPiLTy}+Xp?Qs^`wlsJwO+8n-DN1wGc{L zsOT=$%;Y?La&nYdt)=#O$!(xECb!8;&XY39?eLO&T_?xoz(Y`Sl!_iu&VIz70NTft zD`D3`MO?BxY^2O`U|J3YxE$Dx0WJsDB7k3N{28*F{LuJ_n(Jx2mU7g14+64eX`yCr zhm_Iy1O=$^RR*XrIk(j%xsdILOFgPCg2pKxKG`LdD9}=WW4c@sDuEJl$#evy!gx}~ zB}*y5#hj~ja;&~{p`?zA_NjkU5v%WC$(HK00h}%5KBsyg0GHM25o%|3x)_WraGC0K zh}v15-qYGyowk9!oAIAl(-41(hfmH7CH82k%}j-vN$rXN%QqJR$&4puGBcb4%*=8G zFoQS<1&44w3JtpdI;8jz?;^4#Gvpp;GB2tBFd1nZ;7Vo=gK-3x$;^JxB{N4wyA1aU z%xx-gsaMs^gJ5$si{&A}(X2BA9L)wWz|m|R103#a7~qJuiUE#j8yVn;wgmxe7N;?@ zp?DpYzp3t_a!z9&q!_0$2N>Wq=3NFjjro=VPGe%-5a2YX3j>_SoPvO^oSeEHM72}@ zQom3qtNU1rv2xBvKq@B>&U)|n%DIdJtehJdVC8%Q0i*FX$o@!;AE`;t8I504jv52` zM&nUPCG6Jfo&a4m_GW+@8xSx(Kq>|ho+_w5Q!Aixiic0GA(Y6{Qco~l){vX1jWy(c z1f+&|Ql^F+qyTFO-_1A4)j>%U6@9IaF*y&nCMRo-l;DGZNS(Cic*3yYiI}wbywe*N zteSIYB5ug9u7Hj(=7G83?!pMECmJCc>PLg7N5~`@+GhgGv#2A8)DPZMDgOVl=ugg< zxcuGWuWNYRqpkJGdLzs#)I? zF)RIwu^KVPJ`d``7rbm#N;W`c&6NqwWU#H7qfQ0Ck9mfPgpXmWbSXIRyyzv~N6fw(w6V?z5#~eZ zkAcl(OtKL|2IQ$^e_55wBgF0R06`mp^fSptK7Q}4V#h=%YWD46_|5(ZH~7{ud}bxW z%Y0iHPC@q665l3-XYuj=R#>-((~sf4v4_y8W`Z_j0)GAl?NdDNoVlP>pMjrXFXT_( z&uzd|^$J|7%GYoRv3R%FhwNJ33tj`xWY&UNz6(8W8M$&VxCPuh8Mo4RyT@HBaXBb$ z2WKJUR{Opqm+k&MaHW-AgMbWkdm(igml>4qpa9$b9tPM--$KB&d(N-dQ{!CU=_muy z_#@@m?xVep#-AY-gJ+CJ7j)4$kO69(f`D;cF64&cQgy!bUp&!q%OEqw z{PZFwbN$(vCR-DB@fvPp=S;Iz5T*h<$C&lKwgXL1MYHdrRL6* z2Q1I|XkH1JwIwfMDvflu+febU@5aBO%1j0A1~BXR$f|k{(2GFT3lMmpfin>pg=UW` z#mPn(_Xu%Z>L0$nh(5)`t$n-f7@$N#OC=pfA{Lu>@9oeX$WU?) z0w%d)D49S-ulxE!(G(A#oE#;}wbW`axx1;2Bi9oMNOGQ(N$&4na-T?Ym8>d_Q1Tv~ z^PX?^Cg2&D;pbQI>#P8LaXU~q+?H0~hrnqJ>_*@c1Z3aJ7R260GhTk1wtBGD*2#Q2 zNP+Dll=CtYpl9xY0x|Uf0%EEsWK8{v0vu%94y0!!u`i*6d&bq9rO-3QgC{3O0V|6_ zS9pn?0u_?jbOa= z!B$ITyAB0Li;yJ#1`}c4zd%5&@C1w%{sLn~Hw5IbCOsW#bnq#*rY~^~1?QPp&|UC@K0q2KT- zdH{KX^SwO5=?0p#+8-5L?GQrgzJ8KB{7T>ja>xE3xnoz;rBUWWTR&VX;F}JGQ#{;S z1o|N_Bnq_DNfWLUwoFk8MNA=Fg5+8!TrHcoX}e2t4|gv(hmq8byFq*rpn4wypE7U= zf!>1<@gW3|?axQTuzP%p(T?D%1TW(?uOqxiI>I%e={d$dKF%?22iEz%SBmi|V5`P$ z3r$;nidw$K^*N~Jt(vxqCI_<`9rLdevkR~_^Ek#6)hj3+JB^h^yRwq^CgbqB~RKTJi$P9p)8vZ>`cXkBHk z+!w}FeaRC5pqGRGzR*{+7Z} zWl4p?je6b?G{~L4fneYh*eUq8`pqJ2LYXRiOOf8)$ng}AVaJdHOdlG@i0I1X>6j@$ z&i6Z%TKQ=*imHAMasu!O#@f1nYa3SfM#oV#bS1@nXW&NA6KiKJxYdE!p1^Jq+Y7PPAJJ!akT0CVBdHi&RU-KF zT&n2@zSNP(-vQ~ssn&wu@K4PSW|HJz4iNeelr2Cvf^Cq&fkMt9`C%k2u}i(!QES1E z;~`cZtQ4{K6e~nf#FlwtFmn^`J5){ZJQ0JG6{hT50>?^g{O3riU;SioQzesF6zY%c!=`_u?}jQ@Or9*f}db+Zwv{R)ct zLWdWlf3gFMu(30AJz9s#piW;nFkwFbg`R^gNh|sf!p$3FB&`@Y01wwG6S^1TKCQB7?p;8gx&tV>7XUgg`TjTKA)mXSU2MgLNt2z3CM;a zLqKK>R}d2IGB@P$+&b@(_-<2RAAHH0nkq{sHtv z<2A587XK24CC4jagcBbHdP+Qi{G`UGA>1ZD8{xEg8YI)>Uw{&iS0Tl=@eAf*y*vIr zyxiVudo@bkj+|dh6C05vju2a@PwGik^vtB6qW7=&_fXiF-7%qkn~5WSd6e=!Hl#az7*C z4N~pRw*gH3N{%3%+{gppgVe5Rev=j1Nh4Sj+V2upO!c>M3o{ND;zNEMC%{ak&joB} zU^sCAqLGdw$@k}_7MCEJDYN!A#KV!vs+y{nQPmXX)wm9&u=hvY^~pxIL_N9L*oLAL zdV^W(WfF=dGU2btsUnHjY7-4KW0=xaxiG;x6)92NyNknC5^qsesX7jb(^Txlv#103 zh#sYJa=4w*h}T^sQ`P6f-(n}~sJvX!7dR-yPE4u;o}s!T&v+x$PCUfaW*YpZo#;kK zSE^qn{a?I6WYq{CD=t1yU<_R+k=A{NsE z-@K46wdXxTQxCk@$DYHVb44t12Xns6cd^J{gHQLe zKCR&qk>GENC4Qs6wFYmFC46XYk#z=di6vIiv*#H7TVshy)OW6rhWc~vj3sVn#aQn< zPw@6w;wIX2o{@hrhCFd!WBZX13rG6+;;RR4~RjRiJI9C{zb@4~hQN#6w6n*3AgV6G0S9EZ@LH;$BpQSa$<66PJ+N!@#V>h0I}319L6+Dyr_K z3SnaM1N235X2&G>g$*aU(WUN!U!xM2(*~dEo;In(az+jqyjdki69<)6zC|Vej8b<(N^9S$56!qsDeebEn4)Q&GOeKyH_cZ+Duotzf6@R7@ZJGZ*>OxG8(Fv-=O-#R^ zk-x^5Sj_wsslSVTn|z5sqT#gS&A!A)+E;AkxA+qIjPK#CzQhpfFHvtv@!kncdp*3( zm-w9JFxEW$|$xAITkT1>nL2GGFlUGW>QvG0qS1L zX_|l|ld`h5QTG^4z_Ex~SuOBx%ITVbV-d5Ekz-+IhgnG8JR2iP^291;=Tj(8E?XgK zWBCECDtXe4f^4gc`UO^ym&rV3GIAzM6p9#G^C^7-pPtG5S_`cOE19{oQ{#^z9Q_uh zoZ6Oie)Q>9GCkBUzCNuAf4qyg0>#0*XIs%m|SDPJWQxbjlg@Z?r9PkGh02_sH zN5y!OA8;oj9IyvKy7LZXQ+mN; ztQ0FWcS9S?PY04IqiJW$Uk3a#aP}|+ehXR24}XroueH^J!YB+TLCH+|)5`(1bWto6Mmvd>BP_h-^1NO~B^on*%lt3}vE? zw8>c^1fCkDlVq2jDW%R3WUs@&8RUTN15uknwp7kcF(cP*)2{@i zu6#MRO@H>IU7K-uMVkSOH5I{uZy;zT|AfK}w<#n&x@taj4<2Sry&omfW(W&R&#Jfw zF-Wb+uOkzQHY2E@-IChXR-0lIr`^&OORP2}?}LFjIzuB*%Frm2p=bwGn>Ny}*+0xg z*|s^2cJfG`fPIu{aW`;4DoXNlIDc|l2X5Pr=EJ#Z9T}uUUxGi`f15t(LPMCe+K$o90wQOh!&JKK=TTsf!ROzgjbhPDkh6Fj zjZ&i*AtUiLjpEVA;q!QUrszyWKS9aG;~Hf~Z-L?Qwi;z2*PPU*gkc-}&<-(@Ll6i% zIh@`_C!(@AUAvlGvO{t5w4-g^6;(k>oH^7=z7|f%a{BLK#M@wxGk~KAbH!o98F&;7 zj&vM0oC1Zhlr_06%Gnu|5EPGYfQy||`v^)z{|b#xVX>f0wA^1{2&a~r^22#*>i`34 zz-H1~irP<*qRrkg^8ti9DkhjI8puQ35D2<&VCupG)kV0Yq6HqM0O91fk%fNF&`S}P z;l>%RhZ{8SWp$P_LeH>sqn|MYMS6(OZ?^=K*5WG=ha*u+1AGggQ%BoQ&}Taza(){B z2y;;@J_(Lc@rfvM&MqDUBbY6D+|M9OB*mdfzu+)9lJes1y=V0FgpaE10~?U-i8bAL{O~#hbI-by6-|g?$G87k>bbBf-iYe z{A!>W)x+xk0y5m8U0YBB{`r*p7E;~cB(;4{p%%7MKO!|zBGlwo>UX4em?_i`{GJB? zd{8r%2$kohq*_ zep{&T`8*9rNX`06sJmLJ|01%JoxiZ#t=6YlQj_6sS<8R9Zk2f9G4>yHG0cLXp}A}cn9@vum2%C@=>L*wbt zn@5ub{LfPAM?^TOiJa6fyv8sF5tRCWH3qNR^A!|G|KHXAq`KatH%lkPI|%cRo%Ir0 z1)Ypv^w66=I; z?}qxN^~)E{?~B8dmNhlEvP9L%sPBrUwT+7!me$w(PkQsbRtnU6DqCqS%WLP?_pM)9 zzqF;+3YVY5B7G_07%8mK#pfA{5~KGjvilE1I-a^GRe)(;4jDxNKGlkSowYnClF1}$AySHGmT`3$XW$%>Zx)jGI*6~0E)+e=Z?<~ObQ zU3UJmB~6X>EsK^dH4)~oXsXkBLuwcUS2UV5>gLxXr&?;k{~_*O;OxAry8mb9Or~k6 z5Fu#5R0dilw3$mTEmiAF(@x|s&;Pxg&pfmC?b+A0 z*IsMwwfCc*wA$1s-K7o*t^>6gy^jy{mPSMPK16X(Q5_yDFLc(crI6cfwLDWyyyeiH zqr!c+6WcwWk|u!vvolp8 zlTs2;D~$@l+%wyl&s@UF!d&Q%3H_d`x5eU_YglkfSYu}W00X&$9iN7^D4<_Q|rG2I9bV*}D zB__sWEvbE&Z*MG*kC%B7sqUeeRuX|Y}Q|FHgBKsV{v6h3|Jwyt%DI~CHZTw1&J&%C|n>S=2&eEf#- zw!$=5hH)!mnC-tOME_QJPX_0C_Nu?_e87v%o(8Qb~_zdpaM zr>AqBmq;B7UugL#aewe8mGh@9O80wj+Sc9I-P_&Sc1Gc^uisYq*{*Iv|A_p~D17|- zuI@rdm%@4o{6uS4nb0S$--hQmEX8qB;Ca|QA5robcNO+|@=p@jTKGp&TQ|I;HP(ME zHUEq2$J3hMbAxLB#Y{E2=Y}rakDL3;?c3Ux7QQ*B@EgzSa(Cf?yuWbPT^g69?|l^7 z#}(SXUH@%JtiwBb_4fTY^4`CkdDld5XJNg%;EUGPA2_q&{-C-4+`@6MndqIM5nr7P zjd)K!2;FUk!qbdROW}@2Sa;`If8p`?!m&mqFMP#b_|-hDXW+<0UvFVUXx?;JjJ8}9$K4t>j+AMNWs);IC16TOAAx(fTd*7o-HcK56< zyl?)aU4=8d3JYBqF}N2NUbM7>I%t;s;Z)n1g~tu!ezSF3kEU14g#K;a-nX5M|HF{@ zR}7*5u0@FXD{mU_?p^v{3cviO8+$vuN%9LXQ1HLhyL#}v{ROJ1Jgb*(EIimgUU=EI z!bI1a3k%D-3T2AEwrf33N+_(+zYFwld-p_VH{DivL04g}OaCXk3g>|A*LD@o+SdDP zR;#0`m3pm3DS!B*5AK-wwWa&ly{7v&y4Uuu?d+Z?oc&QtSlH85xL}){t$iQ6dCdjC zx|ZB~3uoTg_m`#a?z;=$eA9SmXMqkqtMKlFs_py0$+HT7v%jlwQCFdM7a@)LbYqnMSb1<^zvV|s+RA+zH2R>FF*(68K=fauN6-G^^$E5Ofc|cJ-vnJ zpgFg-ZY%uD^c=vV{rn{Iz6NM>7ym>+0^q!?RPTVv>$9>4K{WD9)JG*<1boTXZ z>FeGx*?T1kzi#OGwl~pL(R1sY4DtRo#B5u8K2fjkdJP%=obo<5E&lv91dk~g^it1S z@h|D>o|NYe+YV1ouAY3bxA!?xd~E(k!v19Gc<+(E)wT=?W7COS?(Q^_VgHf|eWb7N zSmFLRjTb)MvaOpQeBgkZ_h(DSh2|#@wqD%Qt*mU7qKW5sujwrJbu+^Cy9z(hRoK}D zfe-Nye*OG)8oQUQeT^?OUF{D}bVC^a@l6`Mn9JdAsOY1hfGq|0*ixV+v3rMBlw)sF zOTOCDC0hH(G1c$IRBdOp7d{1=)R=KU(A7)Q54Ub3<;P>nkHnPiYkRGv<1yw$9@E`B zad@(i!rpoPjd6uKTutJ>ApY-7PdF>)&Ej z+6uo(u!j@$*nzHzn~fVW8dxH?FCW~d<`k9-V=vHqAGJn&@}N!EMHcyb-0%l{~S}i)l-N-wRIMLsrAO3M|p6fm!$gF=A>TdLL6C+e?S<#A8)pG;DZHz# ztJK|dQ_t9B_fhCn;e}n@Yq~po-$E`e|E7PP{e4XQGYSt~XWjOPZQJmC!szSA+k_N< zbX}K?${)6=cCBE5K;bDRG1r|Q;nOU{e&#w)Y;X8$O59TT?Y6G=8x_#LJtY0>Jfpi# zlhLQXT}Hpt)^!tO@~78rvvz)%x-Nl}xGQC@-UY>LFZ{F7xp%j0D{LKyC+%I+$C&i? z^sMflEPUwTjmvu{Af8?D0euq_6O$8t<-#{%3>daE)dtam2jM#lAGz+XwMPqo+O`d< z*Q;55__}~uUuPZqgX_jS3xCu$PWY`c{Fye5uwz_XyJ%6{&cd_TbsaXeyDhTGPiI|) zYj3nARtqh>xUlk;82v2#U|Zo!tvAwp_Zabh+=%==*Kbq08)LfvNj69L;Lg{s8!!B4 zVO!y)+q&U*$KlL+d;bFl1C9<-Ru~xX?uI@c7R7lYV*Z_RZdfhV@MZf0bwQa9{V-rw(otWtD5%#U=6>~Wbn@{hywxVi^BFDXF zxAaVO_I1K)IGfYGnk@A@Om=G~duiU+uN5JF=aL%QtRsmZ*8C)3?>_pmPecA+D$pNi{R41S7W*)~uPK zgrJ!rD(H%E<+>Q$i7p18OZ7NvK`o-xQLBQxp(2sTRU~caC6&DOOCYX@9v?6tG~^=x)*U%eD^J_Hy3Vd zJF?_(JKN^|(`ANU*XF!qTeNYq%HD5oqpk-`!($tDb)Sbf`YV>DbHumDx+Lw0@g3+~ zdaNDIb?NY`+O2xaEWYC%EwL>(w!is|Lre3%&_!xvjr#VzkeAO3?>|J`-m}!l=e?ul z=Ud-acx&4&OWx9c^BFfSJ#uE>3w8M4ejPOa5H1^wBdu>P9BPcyG2-^bxEnn#_SH!o z>g&E2dS7+m)=xL747Djg>ixFXw-#<`d&`oW+iyDK$kH5Vbe4R9w41`aF;5-q-jalO z;MPxvwpYf!aC|wuB=kjWuMTxDfLEJdxJu>TQg}<-%}Z`-KXS&6OW%Cvp|f(F*Rfc& zJ+@zGU}y2CxY&VTKb?(TW_em$8hIXWjKRSUG|Hq+-;a6g2-=;C;s~kW!z;a=vkp8OF!)Is10a}LGWM?+9+)^qe(+~2b3 zydKJ2Z?tBYTC_56$?~_)#;fT{%>;gg=Zvh1?F`qX^OpVe$|@e!Pf(;2_tG@}V#283 z7+}(!F;+xRvDOiC?6LSEB~?yIW#paZQ9**o-JKVt_&azg=pMkm?z|6hzdK`@b-YSw zWy50WH#(oN6Fdn5JdF2I4-(KDNrsBO#4_nQDmZD;0|K+= z+%2Ff-;(W)6@HSJG-Hz>RqO;01qr&r@?(w(%lI|Y82oM=w0qTTtf*IKf?+PdKVJG`Oj zHr^;?^&@A>p)B#-e&#A1SH+lELQGBpO6+CrR?%@J<2hye%E;q)JWb4BQ{Xs{CZM3$O57{b_$Ta@foDQ=LYtlw8hSnf`N6+DG({|!gwPytD`Rlf3XV@{rVR4yfGrZ3-T8m^8{^1&C|qMUWByV@!! zHaR6Wioco%3L`MV(?lT^uRyK*fV<7P>q)>ea!L?vmY{{oSf@JMXK|q!;fDL9JPXw8pSAvhbCX*bVpO@8={W2Bq&mbecS4*eQ9&h@=x@ zP@3m*TH9y6vFl*o@Vpkf^Znb$s+Vrz(dY?Eh)FS3@yB==Jpn~0wTX?7Fs5FT&9=3l z+Yy8H)+0PBL{O4YT8QGG;h_)#voLE=;-^Ebrh}rNx0JgD+Q`V}fE@l>KH%{+knQBs zMz(v>N-20zU6soUub)9lXVf+4ZWR9to@Bvn1YH?3Zv^dBVr7!x>MFdeJr9A`nltAG zmH1K~^_HOIz_bR6zk(;JK_e)yK_h6V5-XFW1_OA9JP(1QIrADQ@g$FGASh`Qcg}4o zUf%>sYS0MEYtRVVsl>`8L7h6@11RRs6j?)Zoz&owV)= zf}XM1UC#nex>MkJ9+-q1j>@4-lN#Makn%Kyk>hvFQ$M*>4o{q8m%QhBr3~su_q2kF zUv2ph2q-!!s)wLUJyu|q#paDa4{x^x4G8$VdF*%2`8Kk94-d=_l*WI$lKul8Mt1&F zrb9gHU_lA{xI5DL2MMQx1r(ih@YMt<*myoUK5m}+Gv+wY66XYHG9-qhyCkNidY9;( zM|cv7djjvjThM?&n`LxWtkb;&DFZmkOW;e7#?0EuO#YZ56k%z;JgEfFr!jV9yV|lI z5EwA$>8iUvmOypa$6Bb4%CxDJ(*~;8SMa2q<`(=rc&PKL_H!rmYBq<@=HaG2f!utr)N^%0Y;sr{%rw73OIdbX- z_k->fxW}FM0@}{D1m7;J^&}}|@4Wv8IWD%>h6I$0h0CG4;>{z6E`m2tY>|0l{!dZW z7g5C}NGa{-E|(KE6IC1%P`g5m+Tk@G5?F549I{*KIhd4;|1(WFu27B_^Dz6=X?1rB zG%{bI%ooU&L;_yUZh^Z!R6X;MJD&hN>(1B+<*&>cS@on6Gi;9olo+SdKWEMXfy`>W zTcFLHg97V4RF~+lH{94Adn}z`f=(LF|I<+a^DjQW6Y1=pyIZWxgrEr z5TgqRb#^S%(#2BE6ALp>?C|eaTub(b(-*c73%i7aQ>6OdGkpE&GHl6SA8U>?)*EN6 zHO{n%^Ioh{uUbk6dbeKH7~-7#>q7*O@PJJM2d&eG8kr9@G9QYWs}>a=b?q#0fd|@f z3*Z;r8B;!mcPZ!C$X!6WL-;nuJmro_pC#!EOM0b1NZOYq?TblQ)18-Em*(_RW0Vph z%_au%z8mCFXPQTjKq2nCA$Eqv#H`bNHt}kahjj{B&wnw#ke&H0qjr5HU}yzY6i$Ij z3Q7k2c7lAKzCn}o-+5ZIg`Aa8rb`Ws7)=|&xmBKwmg4E;1ZrC*>zk< zc2pBg#|%lNF4Mr_Y|I~>gR!4zxhAlbp)pJ^$H{YoOrG?Nmcx_kQz*3HIlyY84?iQI zi}@MLI{rs&jZ>#m(J92nr_!9h!f~7j-A;^7)I54wy;sPVK6*6bzIh`0nI~31 zCg+ga>Lq!4_r(|7cbYdIJ(RwIFL?vsY2Nrg%V^DBo0lMW%wO)) z0=mKrrGVHF|LOA}2Q7Y3AjChO$Lk{>F9N+Sv10G!DP-5JI4XxH{TU@a&ST-RCW<@3 z^8#kyrXQ_muR8Z+;iv+h^uQbP!1%^fL})_2AiFlaalHL#oM8lpHwcVxtRl7M-C2~e z#mZPXD!=9yVK>CEnEp}Xo>`QBaa=pi;Fp&X-(d`IVFLOu25M@hVULqJvqeDVAaeA? z=!ZgBGFXkEftX5PDe*TCk~bGfb`MW7GZmziX&Jl`1Jda0$x8N~%GY0-s{3@QL zrxc`Ps4TQ;sy!C8^J>7m&AImuz?~kNCY-dOL4gWSJ3EK9~dhdT&&_E+Luh}!iC^*Skg}1%bD(Ng=Aj?~Wtt$R@>FKTo<2{dzm!KkBq*x|+#Rt}im&jHfq5P@9RuoGHg@%P7}{+(*)fen?4oKLZ%BxAIth)xuxc73($03wnvX zbzXPC-n~k|v$;w@S%n;*^8^BWEc2@bR4o!5qe5G(LRSgs8w2DUi>l{E?cSSbnlFa8 z5^INtVWV*BP;tIB^CX^sPXku*{_A-16cs!=qnih;qDHUd$ph}gqZ6okz;bGL0Z$$< ziRW+{5G(!!MQaSi)@dBnu9U@#@hJTF*dBgNln2C|o+g)Pc;FQUn%eZ;E12f;o$8~w zfG_bCeF5iOo>X_0gtgs5vp&c}eA}Zyp%&!(mNVPAVJ!U4<9%hDHa&)&($XFhujiqq z0^jFg#Uho<;v)5_93f;{jTm-HHR>d^FX&{00!=6q3sIWI89oxi*kjWdjlwU6CP@7# z3ICpl33*%2awogw8qUT$yBqK9itp%C zJdOMphbDDZj_2|i@rdbSiT`)%dR}N$I(RYcl)>vEv3=_Y9KzW&on!TtMvYH1yc)lg zxx8PG|3x%a(-FY{OY(Q+L(k#w!mN5H1QZ^`XT5dtC-R(T$1O;WMnzE;ge}E^MH+O^}*zY@A z6{mL+_E6rlJsX2EaZR&S{5qZ_%ViB3W&Qcyv@-SHio;K%BffrfMxkRFj zX1&e^WvNU3b6HdI3--!@z{-`D=Xn5q5{K+>0qE;TIQ3DZhuj&Puh(y|*RK>%?#U{B z8$oySv}Uz7L606vU)C3pP}Tm^Q8`qk#DBrMWi=ph(44yjRGXwy_NHp5s)ZUphBMV6 z+(ujOqz zgJM5yu~!P{<(hZP69k<{&{=#0Bx+M9@vq|DG;A;as~3eS|Jg-hS@<0%-vKLXC}sy4j=A8B zFDJxV@0{RCaU%^=oa%})QD8OCl5D=^buT|EXODX`yz6nQ)DSDDcji@%Qm=|NRjztJ zZLKm;?bEQ>j5I8^Ck=~5q+zkFrR1rq3$0_VKs8%hN{`_h2B@jQ?QJcs869my*f)Pl5$G3=BE^pUX0lTZW& zEq=d3m=N{5Vpg4mjsd%3rzLYBW|NNC_dBwxMvqlxKwyv8Dhoe-kU5Z?tD2>{H;7t z@)H0>CpdE?j~!AX#j?t_9nHe;HUjSC32#5@&JbxtJmekUPV&B=#2@E5Bb&Q-e`>_F zC}K7*O~pUQqXkM($FtI|9EH_#BJs;x3v5Mt-{RNio{^f$6 zJYPWLN5L3HeH-j`JUPjUS?ZPBcvMS49T3A!LH<+xojla?sSus44o?!KV66_%0yEyG z)7k)MyHj8pj~QUfvEIXD{&(<}@~6osm&$R}JQ!fgq1q(vm$#2cl@-)!HQdOR{!@H~ zhsp}fnDa^jrCgNJq{j+)!dz?^B1rGsIvq1AWY^r;+Q=&JWaaz>kLo1&oV#-kgyNs# zNrw5!5M=o)PVXeWs>Xb;83gTAzK+ z!*D%?i!8n-z-!+C)=1h$&*?KuF9Oy`_Hy}wKPE`kO2xVznH`%NE)I{4RqNYbH-js%o`bB`*ZE2ugdqzqfi_43# zlvcXV*X6-;<*{{ZN&De6a3Tc$Q5sm886PL%r_wMkJ|pOHg532txI(kPhSOX74P1@V z+Ze@>nVCxVLpUg%_g{&NB5|$870P)n&d>{&$r;?+afgoBqhRg-JjMw8k z9}Gdd5;FTVp3&;u^yp;BV)}}LE#_nG7s2<2Ba=$L(%Z}m=Z-;is;6v9P6eqccldodI!8N=+ zxmR};nBhQmc)r-U6d}8g6bh=&2eiGJ0CU>0Wc)n3VpQv^r5Hm;K`o-ArIB(Dqe+7 zUn#73eP(iY!p4qkIfpZSUeWIN%>FaFth-9pY(4b2$}q-TGP8XIgu5TIn;UMrKp)R* z-29nIxm+Ec^S<4MMntzD7VW;zOkb)rm(8(S_Ido*=tlkZNN;0~j$eLdbQWjmmtngB zGP~=?sQPeyGW#bcqDVn)wltc3p3r^P6TkH1LXvv5Ji>jY*{4!paiTgiH=BKV6)2{A zGsw1<^|4mzhK%gISL5)jMY9hn5Vzgrk-g;n;G45sX^W-l{n_;j;{yZ55T>jq^p-w4 z@Iw~}(YcP)?jJ2yXJ%LjENs4*UrSoFX>uFEi-P{4Dac;#V1YGi%5}5ZW;}EFvYS0L z`$mZ6GLwDTs!l3l_es*#A~{BZHa3SsF9>Li=}q{!VUmkaix3aGKik*MO(g2a?CU+a z#*23EX?AE$@EC>oV|;WYw~g*&269De*1pa{t{E>^L>24VPcI4pO}2y}z2MmUC+it~ zTLC^RS0KAj;1;!nmt6Z5FaV3HrIsNzU2rBp4sA9e|bwblUSO zuxC!h$``$T+m$}SAG@PDd%%J#Tt})jKodp&ryxiSv-w*fTHZppn{hAZRQyL0c3@$u}g+;`PXbu81zCb@x#S8E5R_!eHw zXb|7;H+++1`w6^u-w+E(y*NIdZJCGxe2+x||3r#FuPkA92PyW2cOc`_6WJq;kl|`| z_yA|C4ZnvgjMC5HhL>a66?4Q|P#!OjX8()OkSlc@f#1{z0!W8IQEV&^uXtk~7)k$3 zBgok`ee~F0%Ep z8!t~JlqUPpDUY#B%*RD%lGlDOM3$z&MH!%H`c{#RFR16PWbGXqu&SZvTH2!fa@=sBeCB|O@&^L zkEO3TH$67v+}KqLIZ)d#E+>1dJmm@DYdyOi50a+cRc#Fa(HJl}JUv#iYTjo-k^-oY zC3+wx3V~$w2ti~sJSx=5esDkNqHKfz0{r;)4_C7O+{s%nT(EE>(}N8+F&ht9%q&B% zDN@0!d$L8tnHDv|keq*CiAtk3`1S0B(iqQYMB^WFuPs9_zLsICl&8w|?5A*s+p~*7 zxXFeZVcBOJ?xIVeBg3^)HgsL%HSw?(_}>XU^}g-w-v~Bt%omCqu3&(;Ha)8z1eIor z#%E=3{waC(!`_|UMSqoNMo0L#F-t2cL>TI>PsiKH7fG!ajpC5YvDG?%L; zP!*_lWh3p`@8Y%k1^mdKQGkDEz$+Lcs@ba#S?=6R9y9+rhGeb=5(GSZ-C_VW72zTaNEF|Dg zop`l?`}Si!{(&F{&MrgGe(tUGj}5zx^Dp9^ohrgN*EF^6Yx06v4-g<}o-|sAw%>{u zw@<5^%LyWb${~h)|_sNIL>$ANIu}@Yc@4VtR z#>jf`E76t24!<+c#4^=q-JPpS5^Z@`9w-HkttTbON-cZjZ80Xhi$o&PlQYP)4MLgy zc^V#xYc}@oBy~R~uPQ&(yWNn<$v=BZ5zZ6z4~>%H8gyQokFW zbJ-)FAk$B`mo$`&tk#fqY5SP5a-kohQ%wK&0YUs9vY4=_2W` zyz{R(L+F3X8QfCLx;jc9FwE6U`g%=+M(a!GiPBg+Ndo3Hn-%x419p56AhCWQ5t2FeLqQxo=ePFv;rSVsbLlBqs z6>594Nu{B0Gh3)s8v1CkJlWIj?vTW;F9$2o*z@H?q$-VLL?-<02Xn9SxBA4c$BMuG zMD8>GRv+|j@VA{yV^Zi6Zm)OKl>kEU;{ItFU7($$%)|c%P<&3_$ zl`3cStvcr`P(R}au@|x1uX;&dXkfSX;Wy`+6QX?i@;os1hrS>j()kjj&m4IGlZBmp z9uSWo7!ZEi^3YFHNI#{CzfB|_o)bLrr;EOx7|*>tqD6P}+`|)py7lQno)bKe{~rk7OZQ#P zqbrkiG13^%Bv1U^x`e$vo;!Gs@x#NSG$TL;g1Jga!(Zxikbnn5_Jn^S< zzxVRQqp&gjHp1>s!gZit>EchPXzM&mqqqegy%T>iUf~Cm@I%bjBRqHT9OH>U9RNMf zbAsoQBz!&7Q)lKcba)QlH%j%H^MH~!QCqn_*>{2?!wCbp=AyMf0ndZ(dUTi% zx)n{3xT1eo$HtEJT^Dw(&B{f1bX(+60!Sf%5*@{FX@bS?sDbNun5r`1{*^#r(nnMGr594*H*CcZn`KD9Wzq8o8 zd1wFTzT)7}hK;>h-_BjdUHzMPZ{0Yw;j+HX=>JVYtKEYA+7qnI%u72?=A|k*+vI2Qmv6md*UrtGGJVBRGL-rXl_Wy+HIv!Mz%ZD1 zU`TrUYN=9^-eF1^nX-YtNOodtC(KA0$ddmf>3}G z3h(0h*y+{lYDpsVjBJ&@O1ilL&~j!JWn+0}cog;2WJzD@DoOygK3S|(8M~$&b{?|P zVnrJ3tX8~cbY>QO3p`xhi}%ef;lzfGLtA%mE^g@G(QjJihR&F-r(1;(b)f}#ER^QE zk9CPmG)&Db1|9PJFePMY=21-hMnsdIYn;ysBF~|g(C(D_Jm_mm3qlNyu!>pmZJ%jV zmDI9H*K_zR^jxE%1%mHV)=XL7K$~6t8+HwC+1x+0b)yi@B&ZDSo{+O%Vk>iBiH*N98!A%$PY=^G z*q7`t3q?xgJyI-dzut=vJ)i8JHERp`0HvdCs==$XnN<<3VQWPLSwknqH|C_gGWC*? zFXqHmJGTyPzKr=@9NN5nfKJdp40G9xE8^Y`HJqNQRZ68MazYv(4fjlyk8t(`-@T%L;{oOOSqc@W87% zbj=`0s%WaAxI}5>%T6Fm`eLbuQS^kKDtoLC4I}{so{-|%l+AHZ5sElwq$*K9&P|Je z*tR{2JL^}Iz-?qk#(d?OM1hyphBdFWNK~_;tyNXDe7=LIEkevX*dCzolAU>EeD+Lu zAt-fF&q_ZFy){uA45$9=*MdE&SWNV+FHyz!K_Xl{3@RnDV3~2JH_s zv$S99>U@n+oJY0F+Erq~gfK~K!3u9?JNBK~rajcrso@0;jqMOnWiVI$Uz=g~2YNPL z-yYM#76lH75VIty>wnx`nTVRO`kDgwAI= zOXY$(d3c_lvDM0uZye^sw%M_98(zp7x@--X@~4L5#sOWLgt6kpEQH~}RE;``HA^>gEq)Y5u0By*^x+%3hAn~GWFS8< zN+Fxk>S!&4Y)wKQ*_sH54KkoMPBuQw+D1DmPE&n%g{dN{8JItrk!ii`FYf5?+uFZ5 zbJD+c$H0z0xYV!$D9^BHXd#7_wS^zL$fyVlgsbo+>|ac<2=jU8=^C5Z;)>v9OQoq< zi3?iIXpt=-zNKaR`u6Tz22+jcgcCri>Q$@8CI*Vk@-&OBO}6oJ74k4;41zP=VDf3y zi#D_DBeklTw({Jtu%?AZtO5)>Yyv|(tu7fWR_kmOnM zQCsqTq!A_9e4pPvT$yva7`FV~(#Y5Z#GcU-{AWt57t}?f)|kT-=bX!GXlj);t!7J; z`OWk&ek{^?S2~K&nE8=dEZZl6ur0C=5Q!MCS;2{V-$q{(U>XdDUu2%}v1xS%raqW6 zj2LCIty_)SWZ7)k#QQMk)uy4a< z#hsfs_HEd@-8m6`{W}_ZigQGSW7uWjVaQpA0xld)KDv^s{}o#8@1|aE^a`6jit_pHVpRmZ5|3^ymME-c$@Ofn6MV2JX6aS zidARYkrj;RQ#IyCsF!xq_vh0n8yUoSW>SV0qDr=9C??blhphXZV&p9hh-)&7l7|U` z0m*dWfKM@Q!VGC{#Kt){G-U@(bHzTZ9K}W_Z|vHVsm&Maz%IHOI3biF2?rt^xv;X6 z8|%(Vj7p0Y<}t(8ka{-SPTk1m5JTthTQlIFBlyKPDq;EyO{X6S_~-iA%Jo(r?fy z4322lmjkgqzI-)r_#00`Yal)TiEnZFmC`s=e|Q4hpYfXEXaC&P)+m@W|7DtMZrh7EDzY=n7N7jT3!godd;?i)~c_MQg|jbToZ) zpg4#5Bjmqy8na2(3(3_cF-oSLo0iqEBM%a*Ea%3wgEy{4UJPzvifpY!2jdghO#E!> z4ey_b43c_U9qUUG(vcbB83CYb%*Bz>F_ZxrqDK{s^w~DeVnOFI+*-dGQ$!91#n9Hq z*0p(%j4>G(8BV%QV`8V*P%-rHKtY9KZVT!K@YKnJjE1z%#0mx;C#o@EY$nU_d38y7 z!$pKNQi2{@OVO5I%ydOG+>dBd!B(RPADfMAA6^&`Q>&3T8x_yY3|xFR$M@#4)jjd;(9j}Z^x@9eVnseoney6k?Wa@i$W(DH`DX9?G zs5^Aa@zdhy=)B#kT?MU+=^>RGUPqhTzA9?2Ap+DjEunC8=zXxm7{|a>MAUi%3=CXj z39ExVeG3T96gtw)ldkWy-KBUGFrGscyS4XGmNd|73i6uzi&9GmAiimf&sZ;vE?$5}HS zcllo|xKLMOFZoNJmI@SJVFvM~CJCk@^?~u)nA0yf>q0MRHaeH2)c|IvVj0D?7v@#e zuT;vmY|RCQND#CTp7R)J)52HzAaYp|j2{@Q8JL;QO#;v98K#j6A3!Wz1vB;K{ zuAyfnXV`r3PGPii^?!XvU1?NIlS|r7Z3Ji?#<-ppAXo{H*wP@%qv}GPC~|ZPe!;Y% z$(DTJ!9Z(UWD;DcfGo3&g($9TJH!K_dvpx;rJqhU@^;F1PP?(w=>!A#R42*;qe|M` z7rtqf(73tI&%|soQ&4^*U#McV_0l8-^`Vwl$;OSz_DGF3K1o@l@i6tIaN1W2N^nP9 z!Q%R5l@3$g$boom(|yEaKEVP5dyKF#Qz;ME)?Bo1&9}G7rvtQf+JcA;4)SujD1yWc znM7@0ha-uISFP=r{8Aoe!^BO~BH>8PCkM7}8hZTz5+GQq&b3yv?8-#f&WD=6*94^W$0LoTQ>A>>SNiNCSR~Du=yIK z#fEE|e>Q^=d!&XiJ%Z~6B()fA7p2ugEuJ=#3WT@eS~fH1*8Dm08%a*}5V6q%SJ3K_ zsSOOUowLz&sDKbIN5IWeO=)WuMv<7o_uQNi^pK&Zq(euooO%W^C2AOb^B|~)bKA&k zD{hw}_Qr&~sWS4E;U%qNxiq+bH*Y+eW6; znWpp^r#CsI#YvO(kRn3?Cfjs1GPpA8QbLdv`#=^V(pG)R_};(m%oNiQLitTc6P7KQ zu3@eGsLRkG8og;g93X)VEy4U&Ndj5%G95=X%m;y?3tG2qLL&MaQ5>Ij%BKjYZjLFo zdsgP9dG^>O^dlRZT=B;8IHzGCecEr+B5PcoSy~Q4o_mZnAJGtN5?9g6a-;?Q6B2<= z|5>3lW~7t_4#EX$r+Q|hCe4qdmJ?ZjXKa2Go3z4gjSb@%S%ygBe4Q|+*0z4OY`tPj zW~+bo8t0lhEfCd2nWz-JTx18tM#E@tvV}pCrn-16EHskMmB8hC=a-~icZmi1fI=oY z-C7<*l`>pGMjN5wzS+3edZS^6YpCG|uCg*)t78(XjKlD?&Gt{kA!-YztP_;A$uc~c zwn0ST=wII;);|Cm0|S#V)i7Mj$E!~erw*5{)%S7 z)PdqPVga?vYvqO^O5_IEd{_@LG(u3PF<}j}6*b78ZrF>AWR!&oV21Aqran-%)#Qv7 zM+w0WY`oPx6VtR8+{{gmY!2r@qM}I}<)E@KtuWlvu6|@h%n6G9mk&ny*-o6AD&via zA=-&D)`j)RSh70HG{}vCK8j^E$HfL?t#guNyZ3`89k~!4r2as1wf1?np(_w25d_!^ zVNlb#G05EX99!v9v#`G-{SOpVte$qWb*LHB!?}h1&ID`S^}0fntn1jakE^(AcSb=0 zj@0I27%EKD`e@%0vTO>oAX|xrV$`8htc*@qrB8I4>9uq+p@FPozmb_l=lk!jLNaBM z&3aJ`_)kA5ED=f;2deA{3^bjo7HNG}-ku_lSbpDz3G2FTZ;Rt=aJR|klQSH%WyC~t zI$kkyGojwi#~P;gL4HgJ7&g27#61XLwkzz#ElM-vV`oT%d!Own!?`-0VcUQC}eEYne^WTojuhlDR@( zX?lV+n)RD}n-6(|uh>SRl`&hGT(=7qb^{lic?rFPylZbH=jM!l*@1qoRK^90a@!~x z32*c~#DIM)TYa=0sf`EH%LJiug4)!TCY?T0Ba%3}-YpJw*S1ZCP(Dd30|5?Ma$m;R!bf z85)-eJI^f3IdBncvU4?G2UhvboB&PkTd<&(areharM}PljY@{F>rmzWb_=<|2wzAK7G?7av0s?_JHKCIj z>7pcyxT%Z`APmsHu4uGz>_M0spOXRsUSB9HDU7vbL9CdO1e>P}M5*p!%q63{sMS$} zn^KqEM5S`Z9cw2}?xA^sWsE`?<<=&r!5ncGhUe5_q&U*pf|OAN`xm1%SER~T$hY|! z0S3hl{YIuX4$ltT7K_>`3Zx~R!FB_K`9KYY&bzk{ZrsrCCQ2Avu$3jHtxW>fe^Dsr zDjRWRfVybHch}(I=|uL8hUXh|+BCA8T!S!KHX-(^4ZWL-LtA!k-mr;^x<=CM7K|+0 zI+pKdgbAI`4%_!jHmVpXN|5cJBqSIL7FyZP6j4iHNP-j-ciN^o?k#;9I!!PxoXRo+ zWM?32rE6R>qIqg#?blPtkO8$)Xgin^1W}27kjimLH5OiC^5B$U@<#gSrZyTz&qX^! zVM{jB6u8^;qTn#qqyN@Iw}W$C!>Q$xv9Cjo5>jVOpfEv$7uiYcIksJG=892gCrkVm z9T2r$hKa=*lw_Z_bLRuew=ICiYnY93KyvGj%y$ysIA8BpSTOQ|u;_K$-GXT`bDMs4l!x}@D{(O}V>x~HwNgYi9?`Te zb&rPY^`%u0ZhUDT&LjfxcU<`~KmEgM|HxtK1JGxNH0HHcJwb+!H zsZV%?F@SYT!gw54Tr8u9QLV%zbUmYU*|2FhA%a@wZPE2AfDB@<#n!rMmrIwqQpK2E zTc>PySe&@(sf}HzgDs>bZI=Z3H|IMNCO0>i8MktM(L$gwyFZEQ==6Pef8VvXs5IU4 z1i^*Hn46Bmx9Ay~DQ^R)t6s7$HEv$EMbjpIAorTpjcAh;yGG#Sgb;ZZE8&cv5DIqH zPv%G4JFOSmm@7{+a%I=9s!_7-5Jl0hF&33(`N04?dXbY!>G1d3&tmHoyA3WoamIgN zZGL!G#zc(DK2^PhVCt4}LBus0N#-ng7^p)pS=m5RS{!jV6>P0S zuK8E{%BMX-I!z_?z+AS@aNqdp4FrE-2V71jSF7WxX84>gA z+xk*kIKsn9+ktAEgLG2pzzn%XmM5c8Tt;dZVP-1~LleVfGE7#qXjlP9VThZ`Y+-x6 zagR-MDz93qi^ex@#9=&L?E_JpI^e1fI)ohooutn#8+}C!lnqov;ey~L47Xis+mkiR zcN+{HF4nRnO{i<{jEi=nk)KjE-5&ZUQ8uV7`jyx!jj@>-jj^%9DN1dQ>QDy?=3Fv# zS(*NnC9U?m+*D0mO9i#nRITdBEK^d<;_T9<^4MPgbyQAb|@CK0~Zdk!&Qi?*~t{0B$=3#h~u?4 z3@pmV)J=4qpO>CD;bp=9QIJc!MY=OUT2kMmF%rxIrws_>!A%-yTu8yx$`5Z-FC8gZ zd`y%HLp%L)t(r(>#i=#>n1S0gjd5Iuw20&)%k~We15BkNzc8d?D`1QBwbs`N*9r$J zDlFEOKhl0^F+?9N;*LEqntzyPU9u2XML1&F9!jV}PapI_@C35D3{pAj4k$LA<9JIa z&&eobdVI>2qP_%+j=7|VUci=J8!r~`QPWPEm6`Usq`PUTsv&~26WUFOsZF3}I4{&IBK|-5AJ?WC*R9W+9F_wHt}E^{5*IG2N-a334ZtO&rEUhJ!gJ4JQ4X zB#e_AA_Vru*oDzax=5C7BDscR!hx_UV(kH8TzxH?8(wt+VMN%SYNg3?41t?uiAdN& zZwX9cXF1Cb@qnx{#1Y#pQaAaIc+eo3l1@W!atH*VF+0#rqM3Hv(|O2C$+mE!K%+M9 zr|r-vSK6VHVcdf%!*Y=j#g1EvtE>F@zKDC{P|>b_*?h5;7HkoWLk;$^MRDh>DA=N4 zXotv8x9g@uvAR-+aP~`+DA=T!(~UPv(}}6g$Y2Ha;nt|i?Safe=1pyp6L|5hHc#1! zkP6uc)wP7M)BzWnZP0)8yO5)C#C$)eQL}(cskO(wM z0L`&`OqqVOnwGO=333w2Ok0~@c^VKkP|g10z>dMetvWS`idJSiW+-XzR7-H?UHpW->PjOd~C5TCCgKg$fEE#6) z#96c;Y^V_1iH}2`D>8yvCM&2>rSS@;by72F_lY{rfNU-)P0rPgVS;;AwY}}oyD$UP z6D*vwXluhge4nRvn1~o@#4HGjdUh)@?joD;FU5Dsox<4&0 zZe1gSwJxYgHAPcaHqVsaAWw88WicL5u~ZmWq^XOH>nhXhn0koX%`olk%&%Mb`R*8f8_No31FNyc}J#SZh+Fv%C?(YUm`Oc`leZtGy{ z=IM_8vZlJtux4S=#OUfhGMlyaY+fQ@ad^M19(=3Kr;}EML>0p-;IkPl z^&MNLtItBafg~(Q>dUY});Qe}u{T_+mtQsIf}mvZQQyE2Qn*DniXbdDSQlYO{Du?N zZCd*G8D(*7qfUQs)5d%HebGBSKko2Di+izMd}5!&(-8$&px>-EJMyg zZ1%A+9xbR$%D!sYX)iy7)UafAVgmWm&SQRUrKYxMwrC8zmXr`WPXl)>oyxdT6BcAU zII*igJvw34YH0lYT&kAfKuYWynXxJxEG}e8-zE+nrjEieN%s9TmsaQ*Kdj?pb^5yx z8Gj@^+cgcEsr*WSEx|T9Y7~R4E7gtdCf8^7aiRf|?XFQQdDl-_qvosogl^nOvR2@FdW^O2!YP=TIV$N1gkE6B- zTO6eEO&q`K*N~U)Vb$@jWHsSvvy*2&s`-u~qjMfiDSs|m7j28jBm9J4@SIv$H z17u@{#fh<7CfL*W!XnAe$~7YMu*z*`g$pc`E+*(n(Z;gP%3~;1&7{V7IF;xpqk~c@m!^XP z#;ReQXQ;jolG`3k6i-0Y{L(g)2g9b3hF1G2bB=HEc)cz8u4DCC?DeumQ`Zgf5@(X_ z;Ga0isr{IiX<@Z3*hJ)3dqoP}=xtE4uj)>N-Uxmv>hhhNHwRt>UwVInrjBodLmKki z)EnoQb9-DnUcxYHmssS#WLp!$&v53|O^zU@PAUBywD0~&*OuSYAMB(Y*QG`&&-fhx z$kcG0E~GJzvb{AnTLOw-T-bbTvms^NwyK@-$pPxx*lR{PP2I0RHGVwA*>i*<%yGb5hJ*^3Z4@8;L>`tF=0 zQqu$mJ0XazC@Ry`cLRd;FuFO&iL@Htxi-t~aF1<dW$PVTdm<_b^Pewewb{cPeU zr|4YQRO22)I+n$OOL|aw-!*u;VP`EiAv#vm z;O%;n+jU;c&Oi4<$7@a!izYDII>TqW?fW(siu`8OiAfM$rs@hlN3tL4U)nb!DU9c`5E&dzY-{ez}AwAh|(x=k_w{bZ0X9GJL1!y}pEBVC+K#~bJ57{oG zE}y|_K)0hxQ=V80nldM6vfy#uKpt6A9D|Ke(dW3&Z)yKS1Ig{ z0Q#NgOQS8hoSiM>C(ImmSATE+j;s1@l=J>Z?v2ZBX1jz{Z7us^VR#yE^JmSWTc8X9 zBi+!i>7v6_bmC~WTd>NiqOr|Gt@Art7@$bB!VSY?PTpnw#abs7c2IIy&qEf`i+}|h z0iXT!w@tUOYk*gZ-=xihy9PGz%-AyW(-DZqIzPhf)LW8G@_ZXKS6b_VO8}8RX8fH*ygXbD7O*5Q5zo;Us%8aVJlEv8J$rNAM#= zV#0ju)96Mt*4KNs(6fHVo6ho$dJr^2KNb!f_#o>#bJI#Q-*i4W%9^<<0oAd6Z^`)@ z`pmCCKwizpxR#6EG(TV9LcG}dd>J#+DPEV|SDiP57^?-Qq$)3dNCA+|>c!+bl}?r9BM!fLzecEtm6oFMM87j=xl zm^4j$6U)ua+~sYivNYC`A_t8LR(<8a4!kyPQ7ct{$ToM#`APrWDC1aJ;@buXx$q?b*(zAA^05|m1WO?; zRv{OHBnic;PO^(M%(B%qwmRGiAK(+r*-)(s`Mwg&rO*;y!FMf#I6WeXtHEfCiG-H8 z?nbhlC>Q9275F$C?rMm()!0n6V>eL{bY!>1NEg8&QJJdHI$Da7sB}d&V(hM8D8wSE z<;oSw+T9(iv9BF=`8ej_drLv|iuHCb4&WXEi>!P-{8!d{a zuxF}rF4ZZwDT3-V6Z$R(wjF*iKR44zpUnJn@}{1KU?9A^1qFI5c8q*GpQA7ke#r>z z$uL%K%w#8GpzUrl=_@Y=Gtf3I(#CHacdw0kTjnvGgz4Y?0-*mHzJAofOk7YyS~ z*cRRJ@AJhCuMxJdE22I5#t0%Rs?RPQ<)gYXu zuG%tnlo|LjZ`~j!Ff!4U-;kqm)&;zG0X08hwb4`xro0uMA9vCtse_I6U3SY{Pzf~2 zp~+`hW$R&I{cFC*0<4zaKpdvo$oPpO@%LuIA(2uxa7`!g>_UgsJT+)P)G6YNnv8J# z9u0~SrZ(RK8;ppIOpE9?m*VI9Ok)zXsBYcfxRT8$^C=sZ`Q5aQonYU|Y1oTF4{QXR zY(f$}S2)s|s!)8QHSszuxf-~*v!{E%8a6ID+i2AHJ6vm~mTTrU7AkjLrBCXaIvxIJ zSRWn^lge`^^7TZzL zt$fX!%k-zSou~Z>p54is@BP|{+REuVq{bb4>o07^fQ>s0v7NRVaZz7!SjjZ?vSktH z$KILLAyh%S9O9}z{04Y8D}=!ey3>2_hj-gx?1m+pi+llj4}X*;c9rtNG#Fln29 zem5mJ?u)c9H`%WT?t8{q=AYwXorq|WiK-k<~5VJbNlHI}s5Xw%J2 zWNjU-ED>u-9U0GH#S$*@qn~_PZd5U{xXyOiZ14?E!`)!Ht@Q<5 zpdgTjMC*`T8MJmS%n!|VL2d22Cg1ud--S)Si<*3|ZSq}=uRe*AIiS2X!f-BVI2y`i z^#ILkFcik8!UQ2knPLcD1ZIj1BX8|XZ?h!q=xO@Wlo+Ys>;!4jMD+KmZ%vc0sWaBC zLo|uUgu{&*>8njWu&${G)~N^bUS0PS_zb^YAhAW>WYYY&rZlbeL|k-@x;n?7o1 z>g$`TzP_pI>#^uFN#T^s=NF@1v(&`wP-iD%8e_A2`zaREPQz@Eg9J7&-O@2A?iiiq z((YtF*fJEzX1q&*97ONTth#Zq!f28$M|qf^an;hqbWZM;C42|cWSn)60+tdhiHlx(a=S_Xsf5~Llg`-W%l`MmS$8ZC*{7l z)q^TMJpt<4fYb)Vwn3N(p?h41&jcr>&HMy0_rr zsy*|#@F(n-t&`Lwif8>D3B?w1?(wtL1JzTY2)m>{-GL1`~w3LXqa@WRKah* z^LS}WQMsHVnmUW&CMZoe0~*Jy&41&QeTG@#ynz@d);F{EjCvY- zq2oYKk)zgFxvKU}AGpCUgM9A!ZICyO9Lt!mHF>3C9fPLED&=g84kjQ7>i|00C5Ap` zux9TyVO6tws%dYS_Zu6(cygZ1M&ATbLYwZ-i3SA`c}zx!edfLeQFiYc`oPYeU1%HZ zz9i}<9bUqyK?mf>w)yD2G)uPr=3DSI;&jHx)=z4sPt~TQR^o^J<}Q@4CRhhkn#I@t zhT6xG4|6GQ#`#W-71X@yr2XX|GdXqPMrR>zy$K1^JKXY{<;l!!SyM~aCN|J$hqtnE z;X$Z*(o$`vKqZ0#C*M(8wEReTJIdV{{OZp^RB52nfyLy<|KpgKe%C6pAP z4YnyCJyVlX*+pMX&yKE7)NIkwA>z6_6G1-?JzW)}v9 z!pPH8kZUQ8_d{vc8zBK3fr)o^ZbWp75>ziwLYSE1rZDi8P5q{z7~(I{(5y?ACSuFH z8LXk5EE6mq)^GWotEFF%`;KmX-A-TZj9-OZk2`*HPA|rpXJfJvD`b<0m(1syPq)JdAUlb_v6<`W4Tqr(sDPwyfs@!n96+t zPb~N6ai`@T`!?m??dkGzl}_a@;n6RadklA4?od*$zNi_?{TS}F+U@;=Jyc- z()`BAZ;~*zL+y$A{W0z|zkwg;^OrG`5C_OU9o%c>;kWVvK1~@r9l!F>^VI-jzdqZ^ zr%;o0G3zgpF0J1q)Ng?>)sL^_=Jop@xRr0r?;r{GDj@t~et(ZY&2Q6>G{%juapw6g z;az=^HCE~IHK)f@;be**&y(&*C{rModk*Q6>SRjyQ+hG{Vw}Ev9o>q0?N8Fye~GCY zaTky%ZO0Jp7`WE^MYKZYD*M+h%5Q=f?^VZzUo7jV7Ug&MFScg-QmFd*9G;lpjz#$` zzqBP=9UB?a0kYmj`8`N}19YbH6U~eHUA-v3OE^SL^ z-z#}yelv^mJL6zWcBN-w|6_jp7UlQQXBv2LZj#^OMfvR^zi%X;YK{5buqeOBlKhx@ zdHvqAD8DOjZ?QJSD#rZYy(qt@$ghJ$YVWIgVtapUQGRbGzdey?kS^x;{zdt?OiQZ&MQe5&1d?f&{Th$@ZyAqp zD$TF$?^?546GV&oJwm#b5W(jKzv64r%7^$QEeTeBfX@I6692Ry@of~Y_zuB8;nUcH zALkRbf`7^C`?79{<%0k$pi^c{i^!2<;UCBZ)= zNIPc*Y1eVVC+I8~5kY+#TlH8EJm>TD2e6e-M(fkq3f~*TuMXjr5PnGTcWJ-i3F<5O z>#RM3@8?s<0iF!->@x`e5aR{s&VS`|*1%RiP=9HFn*!VtU|)a_0`>lL zg1rB{An)t5-@=z3K^EygL6C3=sPW$;coyvtq#y5B{D04~vk6=IL7o5y1bP4N0Phzh zpGSlLIbbU|dosZ10~8aZ@U{S#26%RW9YE!~H^7P@`Q9n`K|Yfm!XFFaPlfR30$f3z z_5LbB-rE%Xx6)?{zf+L#}JuNAPa? zGlchm1M;tgfM|SI3H}lNDfoBH55eEfvfD%WJpmpU1dsN<7)ZV9g4F8~!H2;=LGpW2 z@DIQf!T$!Hyaf1u@FBo~04svjuP*o@#zl~Nod9Ya9}4i{03QkP(EuL{@bLhj2=GZk z+W1uPKP~uGJ_#?lnR*Fc4xR~K!FUUj{&_*l6*DD#Y7^W7T@|G7&kk@|fXfAc8vGaJ zy_F&SyqDsBnt3325A6nO9#rK2WBOMRdUJ;$^y3~u(mxpD9}n@*h4>DbF{Qsmkn}@> zv#BBS`rV3-aDmg5-BH_&Zp`Eq_7s-y%r*y@IN5h`%Sm zhXhG?_X>}HP>}igyde3W{W6EE1WDH?NIqAG@I%0J2)`BB`Wot|@J}%Af~0#?kbE8! z{3zq_a?<}P^B<^m7YmYZlOXB(6#vmIJ0$<7;Z0%sR{mL*O#(HJ2jz#(JtFv<k<44PXvD-JP`bI=#`+_4b-?W1+Bf$ z2>upyLhxgZPY6FLNWVNUNV!=Hkp5{45NEdXGcJp%oDTfwP|kTk<-bZ$@9{gIckFks z*IRy)Son$nI|9^uith>V;s7rVa7%y#0qzO#>HsGLoDFaxz(WDv65wqC-Vxxj1gewn zmcPwqXVvGv5Pv+t69GOP;G+RDr1sw9!T)4{PY0;}R=&>$|H%N=zbZ#M8|$9{iO$Y% z)qj5UpMK{T9Lj$Q&ekFDOK=$c7koW@g5ay6Yl1%xJrV?W)IY6Pf`5Vo&Um-(01xFK zW8Mq)I$pJQK)2=J#<&YIo=XE<9^eYWv%|Pw#5xfC7YnWn^&-Ac{vPOgh`0J}2=)6( z=)1x@L;Y4khvcU`^=Ipcd7u7hz0dV!tv?9eRX8*dr@@y7_)5W-W!aAjvc`3V@XY~U z6`=JC@0WvrI>74!JQU#D1AJG2M+3Y&z&{A^69Gb!tv;U*@W}vwT=l2CH34o3a94nD z2(T33Y=GAVcyoa74DikXe>*_QZ^~ctnc$}b{9=Gl1^CYa{zrg_TbBOC0se4+uL`g; zK*=%6cVmG40lq%Ku>fZRyf(m_0=zB2_Xha>06!Aorvf}1+*UcS2(UB2p9*kmfL8~2 zFu=D3ct?Qm5AeSQ_}Kuz65!VY{Eq;ag5WCm#{ygz;D!Kq1o*Q7Rsy^!z}o_RZ-5^N z@NWbB*8rv1`~T{?6F3{IKYrj>Dv}}zEkBVZBq2nLCHkd8Duq;IjKO3uX2uqUQc02) zS=uBe?Mg{0DkNq|NsBKUV7ip_dL%z=UMJ^@7(6ziQ`mY zb)Lx1yp;Wz&)aw}A7}izEB5<3-{U9T#yyNbf5qj`=cnAugTl`}vArtm@MN~*TJZ; z?7}NJnB#dT=W#VRay$QEx$qpD-aaW>e{?3CAH9qUJ70+Q$=5Q2eay}RHO>W>erozv`aeI&9 z$!x>(*pmZT$k}|HFLD(>=GWZGzgf9rGJZ`qVQY5gAdcaUoWXf~k#BM>Kj(Jt;{M?U zLfrmJtih9*&7mC2DV)#exrDEA72oAr{>;BvKD<8==W#YK!wcHDoeg*{yR$!saRTq)94_E8uHg=* z!VA?nPDR#WW42{i_GTW(aVlr?X)fb`!uuU@oD+B|&*i1Ol2>sOXYoyRt`UF#N})9B%Z_x0lP19=s1;tbB?^IXBT z{E9!bRE?zHiaeH$cm_MM7q8?f-o%-l&&7O`8@P?Xvr^4u9>=jM&*X*d!+c)L+c}5N z@HKwU@Ax~*9G8rH1Z%Mg+ps75b2zVOeBUu1p9lF2UuAs%F}8osANeQC*Gk%tW&^fj zM|NjF4&wyg!8u&OSNT4_;7*pRos54NYqAO3@d9RYD97_QKEMV1h4obAHF)*|~l)ubv#hLSDJ!9Yk3>*yyxh@*KEr}H5`%UAgxKjnA)on=l+=5qvVu?gF-GcRKTJkU*^!s9FY`H`xA1Px=OV7; z2i(jb8GjEiUdPHcO{~Vc3?HIOx1Y(byn^A&AJgquaU$>HTt35Pe3zTJoqJg37-vN7AR3omCbM{^Qq@)0iL8~lKu zavOK^fadlOYw{$X!SmRY16aswIhFVEalXh^{Fqz#3sWtU`BY$ap2+s>$_x(X)tt<` z`6$2R9+o*J8LtZKuo>I)LS{0LV>yNQ@^QYz)!e|X+|8p}CG$9*EqE5YF^l;e&#Anh zPx57MJT>Y6TkhfkrzQ2uti`6hmQ#2S-{KeC!9!0^`m4^yJcFIsi&t_KCvrL;=5t)m z5BVi`GId5Weg#(NiR{70xtOcCj^FS%?%z7;_i!G^CTz>|c?Ab?3~%Nvp3^qz_hR

$oRypK~4B?Rg}Gv+P;PJgTxTo3jHmn9I?e#F>1Ai@1^>aSMN8 z{2jXZdf_nE;7M%F&b*A*atiO}Vy@#i+{MyoC*xIOO*Up5c42=Oa2zM|c`oM%+{_=j zm*qM-?ySpZJd<5{1#jRC-p9xIB7b4(oMfB|tj-g8I?v;!%;87;fR`J^qhn&r8Ou%DQaM4!nqcIF#dfEAQhIT*43dIe+AzEZ-@a$I)!S zR_w^`?8jl8z&kjH3%HE$@iYFwy*#mVGLP2m%3O}(L{8_!T*5cHB>lX9QDXIOiL3Y_ zKjZH_;NoPt!&#Fj@eH2Fp6t)zyp~gWA0OvSe1jkHEAC{qOOp9CXFGOh9}eaiPT~wc z%s2QUcX7Y&$v72RohPyt&*mlU!#rNY$(+SU_&k^M18(Mz+{5xkyv@Bu!>m-!Yqa4UE7z)O>P9KqUb z!H&F?xx9u`c|V`xQhv^#_%|!`O2$2wC$SCBX9n{*gOBkQzRxZEmHS_oj8mDl*^C|7 zjeS|j3A~eYxsc1bmRtBM_rKiutj%WZz;3*mGdPdWa|PG(EB?$mg|$u zXBjv0C;pEIWhKj1WgVW(c08Y#b3AY1-JH)wT)_|dC4b~zmg}3$qZ-d(_%7V^el6g5 z-pYIV7#H&me#Ec1lYjG??4=z!( zhCGeuvM0mef=VB!5xjxZIF}3gD%bFH{>VRBesI$7(QLp|c{VR$_{y#HJPLUo@8E1c z#aH+aH}O0E!Gne*{T|7>Y{;f;$=2+^^Vow|urIG<9*1)bujNGE%Dedh=kZA{<_dnu zFSv{QPI4AIS&gPR`!qr^QZ}=-q7bNqk#KvsHF1(!K&nBnO z_tBihnS6wc_y*VUTkd9=!lb{dJf5ep3oqqBj^Op2#fQ0&ukkNd9F~lCG>>OdIVTFIfPg9X3pelZso6xA6QHOyu)MIfGt_Tv7FCkT*t4tljW~Y`ag>G*n%B+ zA$xN$$8b9Lvg|cUzm<6$8?!Y#u|J3LPR`*1F5?>R5lkuwZc%H(u*`574f;VzH=W!9=;5vTG-K=+AGJZ3*WoKT- zfxL=0aR%q{d9L7Ee#M_zYC!Dm(HL_GLcDaSHF@qkMsz`91$&+1rwFFJT`J;WfO4_wX^EbG!AK&0)NQ z_wz9><{SK&UvdZkV);9gagJg=wqOTd#B2`bSl+_BIiIg^HP`TCZsJ$`iGT9oJCpex z$>Z6a?b(gl9L^g#gY)?!H*hO=^YCfOxX1D|_GEt!=k>gk5As>Q&Wd*>{r-n1@>HI~ z9_-KIyq?oJpD*wYe$21=D@#vL#;?TV*qCkDg_kpzH*p5%@hkqq(le5A4reW%%=Wy9 zSuEfUoXN+zlppYG?qS)P$+*>6k1g4eJve|PIgvB?2w&hTuIEs4TNHsWbKmpwUvqxm>r;%aW-R_^A3_n9x-u`4q;m{)Ta=ko==!H@Yhe`V?WlkqCC zCL6O2FJ>PO`Mm&`rc?tV6pW}H8@8*0i;tH%EcZY% zk0V)!C$k;T=jF`h4Sa=Lxr_VHv42^Ejd(iGWe?uU`}hQx@GWlSHtu1W2a|EDunwEC zJuhS?^Ej4McrPF4OI*zj+{)cNaBeb>BUqa)*pb~ih@*HTr|}uS!ne7VtsY9o>&84z z#!|5aX2UP0lvj`+{(XM z=aHn}j_k(*&ft?=#`pOtcX9vuNq>j2KAW>MdorIla|R#eQ(VnodBCH|I2CyePh?BB zXHO2~Fy6u0e1=Q;K0oDl?q=!7l6ll;bGBn=_GC8mIfHZgG?#D{KjJt1ljR;y#;?L! zY|BjMawI45UM}JWe#75b>WMH;sqj7JJSKWX_#AxnsPH{t^65NNy-PH#cOi4M57vI8 zJe~9Sg!UJrVf`gsru{>1<`4Wi8s<~_$z;7Uti&p;$A&zYUDz`kwy%FQ^jDxhf}^$H z%KQ0HG%UX$8s_~R7i)iqpYp3{SpKJISpFC8)}DGQX+Jm`=5sU~@Km;mhJOAV4gH+Y zikpEL@@kIf9h}Y=`3m2RhJH56pGA*MrM9d8qQ0ADpH7xPBpT**7>`x2$0pG* z|5n=1U_0#>Gn>PBJtsxO`qSk5qG7x_(J;Sf)R(9)Q(vRLfnRF>M*B|nKUjJ}=r3&l zq0!KPB_5}K0-LF~WP9~ayqLYU_l<^m7OG#(8?;Z-K27~T&f_!DFrVkSQvE%ySKq{M z)pziB?*B~EPgz!GH8x-)UciglI~w-SPQciCtdr&=`hQ&YW;dK2|i)my8dtA4SZt38i5a1!V6VJ?n_`L2-P*`D&O#`qngaXTBaDKBPE_KhBqN)3}oaR%?R=Wb}yeeW!B0Xqb0HHrC#O=S0JL zz2(6yh=zVgYQIi>k~}RM`kl#pwLi`0qM_fV^1J*{eXG1P8v6My8pbQVC|U2&XsB0W zm1x+m`fL;p{kN3QW+(M5IX4>m$%}^m$7-LXK83eOL;nx)(P-#@q5L{msedYe6Ak@u z=N|2;7n1t^EE^5|$M1rUHef5ZiH7mcj)wluh z%d_RjUq`(@o2$2$ z&tw<%q0ytl_tdJ7P_Spay$9I@&$4x`>79=hs)#T8|2&MyW|JthvfzG^YW|mdt9sjxx7XG zE*g%*4tck{S1$c>(q1+iw!4B{Sw32>As;U{luwph%5CHh@_BMsxd$`U`$ofgG)Vm_ z`IcxnU+#*A`Oi{+SbkJ~UVc$tCBMy0(a_J={89a9{-s{#m1Mc{(J)>`)?z(2Wb_hq5_HS)E*U42G0?1u-U;W#`Qtr)KR(J-GE_^S4IwXav-6bOI*%( z_%T1{wrCjdhiK^kPxS+rg&gKxF&f${v$pz)Y{53{$P0KWvp6Uk`Wwpe>XUe<`iy9p z&qMNjE{=wIy~elI*Ko7?cKJt^do>yN&}itldNlNNJez25uKg_aF6_>14(14sXqf%tgqfoK2`p2v{ZPWU>EIu z*gqQj%a^a^jq10{GvwLP(BE7>qJ4q(CGy+c#4n;@y|1}F8pi!idzsghTp=2kJDgRc z;W*XMeu8`&&toqRWL`A%KUy9q-z-m+XYl@L821rA&KJ0Z@A3ow#^1UB@?^e8L_>c^ zvKd>l13U6kUctf9u-zj#PJIGzRiD8J)#q`M`Z9Sr-&0@DuhhTgFWk+8RwUbT2>%le z^Qy~})K6w>^|N`Q`X%hcejLd$oE#1PPvd>+bNGb%^L$l(1wT^%jNht%$6e}wv+T-b zyu+j6cvX#t>%;NtjoC{38QMFlU%*S59S!~Da2QANX5PyCqhWg=;R5yNxJ>;`u2o;p zt?EC^yLjLmNxv1MVLpemy87{Ks@{TU^1tlC%a|Jt^Bu-()UV|&>UZ&8^#}N9G(0Y! z)4o*wb$+P6N#4xw)PLpQ>ZMoNzG#@&F|5NzJcVs}4lm?o(XgL-Gf#aKujS3WllSsr zJ{=AHER2TpXu0}3{8;-&?O&_^$lcuU&7_|LqoJQF(Xf5TvYz&a+D}n$%X8Q*8s^i3 zeK~+v@fuEvhH<8Iw)$K?rTzk6SAT;aavitv2bN!*%%>ucj)w8-N5gs1M7=p%Y46O- z*-!hG(XfBU$rCu8ck}sZ=>HY@HLi??@i%ficSOVTd!k|g?Pcn%WckWGG8&evEjME; z^$zkmat~&y=g7mNVVqICTKjFhD;mamKwiLQe3u_a!*Uy=p})`NZ{+XfpXJ^1UvlZU zll99*!}^D_DjP<_{%RsOXM6Q7@`dc9o-5}?K zFZrGNPy9o@^qOS3L!+VpO03S~*o-aNF&g^6fS0OY!5sB`UadYp8n*j(_383#c|M=v zOVKc|rCiN-xtUw|OEk=DFAsP>S^pqbj)wOCu%3EDp2E}EnHR8kG_0S)eD&cRuRe*> z)MrM+c0Z#2jQaC@l`FW8pYWS#822acQQyllA0+J+c~mr<=f_3E{;SId+E3QrTJFNj z*+=`JXu0t7Q8e^3oMW|5iiUaJsXl{q)t`_T@MZOl(J;R+)xY6(?SJu*50n1m-z<&e z92X7iHH(J%v}6Z%aWpKS8Qm|H%4UxCeC=1uH)x;4yVUQEhJGH3mQJPS z^9k+GXkX1Q`5X89C|SQQTk%3>Fqflv1MlDie3DDJn(MeFdPpj@P5v!fF?>(x$H_dZ zL_+$I$a(VB@{RJHe1Hr2D&OOm+`&ItZoPT14x6$qJF^#aIGhur;l12j zqlbl`OVwxbKF*1T^Z8*u8a+JxzJ>Nx+{iDul|S)Umf8^35Bu>D9>tnGo#(I%d-6(- z;27S>+xZX|b2-=WGaj%pna>fd$5VJFJF_SIb2z7QHlN_LT+F3h!MC`cpK&|)u<9qt zJZrH&PhxYP#&$fLop}*^GK1M1$e|p;t9c!7;;o#EuXWYW? zxSM~n^rmG09K?!@e-k*KZw=Uz|7AAE@fP00$M_c4b1Qf8fKQWgDzg@wvK=qrP>$zq ze1Hr1D&OZ9+{sd(CF35(nry;$ypNCbCBDT^_#OYpgFjFDKbj}-G@i#^%;#86;ao1@ zGOl6y&5jeBvn|i#CG5jIUc#!Ny^FsFFU|z+Eyo(R< z87||y+{EqN!vnue=5qvV^JJdM-pu1TPUUPq&1GD}&D_D%SIM{)S%Zz)mR;GKc^t>7 zoXw}XjBB`=I~e~)Y<%2SWDPcETXtn{=5ZXSayFN74S(S8Ec3Pf&01{2PP~)@Ifl3J zJ}%)Ze#{2nB;&N;S-gN59K_L_%6s@IU*J33$-h|s+hn{3?8W{Z#_RYiYiv!{YsgdC zk)!z**YRuq&Gy@pelFlpUd@|1lk@l-U+4S$f&b${+mrsQvJOvXJD$(WIgq0`gD-L= zKj3EW|6MX(1s=`%JcVcRB4%<3ujb91&ByrySMqD_xvp!GZ8gAkqR{kMb zuLc{kDO>Vl_GbaF=e>N6tN0OrXZatK@#^qQc8MMw{ywo>C{K}R$#dnWT)m+Q&R=pkIOH}ugUMq>*X!- zUvjw}$$TqE!+dMV4dfPbTe*{biQGrdl}F0A%lFBT$j|XLe#9@igQa&S^Er&wc|!Ej z@H+p%V5#uFXrE!R4?^ikeJe5k?Yez$_CpVK@%3bAd@&Gwk9w$$b?~!NA zFUU*e@Z(5&yzufZJ-=V&J#ytR=k)xd;a@YkrJVkI*6R(Y?S+CPjR=2R^j=MxQW@fPP5V%l&iNn3$c z7#=$5dVQYAW-L12&X&((H}+tE4&+t5hPUuG&gNV`!3BJQMd#;R@_P(F{-@_1e%wj> z9mC}zopmg~8h>BmjD|Es)*f3vjnw;T`Ue^`?Z*oe*9ibapJPI5Q)-~i@wG{^D= zPU1}7%ZE6hPc!{E4cqdPyp-?q1Af7;`90H*ToT){WFfuHglZs#xD&9Vn1`=dM$XH{0` zacsio?7)uf&R)EdgE@kuIe`;7llO8iAK_DcmalOo*K-rU<4-K*b;kibl$Cfik7Z*v z<7sTe|MFb+RUXabSeMP&itTt7 zJFzRfvlshv07q~%ujfs?oA+}*pWsry&Ug4ezv8$2iNCOPS=-M;S&6lHJR7koTk#Bb zVpn!&FJ8&P9Kq3?#3`J{nS7K_@@2lt_xTaG^GE*4QU@j5eHf2m9oA=Sp2-V%F|(P& zJQngg-pDDuoe%IKKEVZil`Hr**YGF)!UM}C+f|O0ScP@jfKAw(9oUgw*^RxJ!2!(W zXpZGXPUhXbpU?1lzQWh|0YB!~+{QiJ%hCrspIL=Ru_o)V8C$X~JFpvjus;X#Dqh3u zc@t;w9zMuFmIc?7_>J#r_=5t2mz5 zb26uLChz6re42~-GFNgnH}F$_&29Xhe{%mrlKoPaRe3azV_i09E4F0^Uc~Oaf_*rY z!+1S!;!NJlhd7^$`7)Pt71!|-ZsAt$K_&WA59>MxNk?nXEJM#ketj1$lhxOTn&DoY6*qImbQeMF!EZ}I4<&C_VxAQLE z$2ok03%HES`8L;ZJvZ?ye#@Wu3;*C>JRrQ6nLaOBk(F7C$FmWevK7x@Cw66b_F^CQ z;~);@I8NYXPUUpo%}4nppW|Y_$`$;G8@QQU_&s+pb%gVahqEe=Wi2*jW47WM{4dXC zFJ`bm2XZvWav~@54o>HNoWlitj!U?VYq*x1xS8MbJO0dF{F9}^8{P3dD$k0n%A#{jp@f>#M#q7!6?8|{1!r{D%<9R(Nb1J9vZqDJue3H-bRj%MWe4iWmDZl16?&NR$ zlclP99P$uWW;GtmT0EJjur<%*1-zJ7unz}v2*+^(r|@>(!`Xa>&vO}<^Id+xE!@hV zxr_0C%%!jAtiq#s9P6?XoAONlmtEP7SFjHYIg(>}9q;4}-p>cQkS}l*-{yy0$ItjB zck(yxW$MUeKUCo1Jc`v>hxOT*&3GEyunR9_FJ`bGujFWs=LtNCEutM$srK^O?7_>J%RG+YXx_|Qc^~I+0iWXvzRC66#P9eM%N(6- z$HA-=4f8%$uEl0-$&T#Ai`bq0IgnTJ8s5U&IGc0%EEjPlSMz;-#LxI8f8lPHJto=C z@;sWyvMw92HP7S)yqJACfJ35Zgzp29$MH5!<2{_sg?xca`8wC}6MoMf{F|l!lWbol zR$+A>$EIw-vv>}B@G@qxKL<0P<9R(Nb1LuQY|i6je37qk1>fX)ZsOP6#y#B2{i`SY zp)9NM7@okB*n+3B9nWGn_Fx9Hn9t$7o;UF}PUAzI&!@SNE4iAV@N<5{?fjj8a{ps( zKaXN{)@1{p%GNxK=dcGaV;1{!IIrS(Ue77Koe%IKKF+7Pl&|vxe#}q#1-J5h{=(h- zi~H3`_RB#$gq2y1$Fde1uo2H-J9cCz_F@M6@k);1Xins0&g8v(luz;{F6G-?!%z7I zckvJIS2NiU2eJx};_*CzZP|h6@qAv!-WF8?X_Zvlai#bJ?A}n8!j+;6%>gJzT)&xP;625jSuff8gINT`Sq1O02@; zc>m&3Zh8 z?bwl>*prttpTl_rC-DwW=fixI&vFr0ay2(`Gq>`4{>nWpUpLvliaeIJ*pw}JMznq^ zb*|in8O-7cj^<=ePM z;AmdQ8#$eK^HDy@MSO{?`7S@^MsDYi{F9{`IImfm|6xrwW;33_cI?V-%w#rmna2?v z%}JcXyEu!F@<~3&#azbae2ee#V{YU&{=i?khhvRx$MG= z*^|B5mxDNzBRPhXIh8Yb4RykK@Tag{^re zFW|+zjJ-L81-ySx_$JqL6TjyU?%`gRZ{)hbsyvzv*oe*9iXGXB7qL70 z@k-`%IB(!2-o|O1%SZSWpXF;@$#?iZ*K-rU;K#ti$?j%w}xQ zv)P@!IFLg)me=tPPUlm6mM?KB-{4#PgrDz$|v~>U*kG{!tMN#e{sL2$@U$@Ls*&Bcsx&FQ?}q)Jcm7bIR|kl zZ{jVylQTGvkMUV9;v0O6>$!viy7?4D>;f+a{?!FChz53 zKEg$OiLY@bKjH@d$e&rJd9u9+^Ke$>@jQX2vNg}$r?NHA=6Sr7SFj(ingoTWZ5S~`__jL&ir4@`yjN~w6cN?VlAuKe#@F}9cTdC@Tc@b>Tj z^K*Y?Emywy@?pL3zm?MK*I;-%DxJgAU)u0+OWTsCvm-mPE4#5b`*Hwtna4to;{;CR zWX|9{oXxp>gpczDF5xmR=Nhi%dT!!Ye$O5Jm8r1r((ezjEX%VRk6{hgX35VPwp2fz zZP|fEpQr66_uyq5z+C3BkmERk6FHePcn@cDE}!N?zQ841#kaYJYq^Zx(%yI8QF*NRHt| zPUckJ$=RICNBB5j;1Vw5a<1W8uIDCh<@emdUzrNmp7i<4vMl=iWBPN=VZRi8uDOQx z+HA~bY{}Evk)7C;-PnVdaR7@x7o8^;awNxa94BxhCvyhx;cU+3(_F|GxP+_tHrH@1 zH**WO@_X*#UZy{v9na_ell@+n@zcO`z^O+?-*I7}$GHb9l z>#-qQ@^rS1hR06&^Pa(uF^6N@iQ#GC|9dN)3J0{G)=Tv0Ld> zc$2c&t#qnku@w6cZ+aEGl}#?K@`Q!zLN8MzI{f z=OO0C#rDVPWy8wpTe5uoOlwh&`#R=|#g^}O&_C^Qe!Yw3CSkdl`-Xa)PwSAEhkRLh zs20ud*L@G$WW0*8lk_b)U*hl57v+v&{nL*~rMiV<5ZCV>@}BT8EZYBBA&;pMzE3%< z5ZecZyd&g$2a3(LivejOG1i|0@L zU9jYqEWf2#j;|wQt`-)E{r@lI_`6|wa@lb1=Z4>vsu(O9e`JlMxA3hG>BrlcVmXet zwOEe(FYeFeRw`8`^fS3;_+Ii*DC)1nasRZ(fF#CZ)L-F?ia35alTv9mH3~MSImRc+qbVdJilCI{dlF@FXXs>?R^U* zd0z}yv-rAqSt!KU^QFS|KQ8~ztzs&^4vx3@Oj9a6pA>`~pHSC+7G%INqv;f2C5DQVT+%V*}#d3#`yM>$^{{7$Ee`G3t??=2P+jnH@ijd>| zap7O7@XOKh_3VUjKi*<4ERo}UVFXs6CG9}~{;eM^~FYb@{y&zk|{rd7# zAs-fwO;LV1si<@kLehlGDc%P$W1TNcZ2g!@^=@<-wRl<@B$+aJF-Bz^};c)KmV|Nnh{ zRVnd!s8k{!p3d?3CAUhcU7@d{TRiR+!gFWQE#_lNQgn;$f0W1v?|UthY;W}vxoL^qzC^ybMDAT84=$18_lp$W;(TV7$d8xE&z8t9 zmdJ0E$Qw%JttIkbCGuhWURx#Ge`JYVvqWxDBA-NpStn*@4QiB? zs-2k%cQOhKM`aY|49ObQKf5qhyYIeQC>7?W(}+G9IRzP+!!vV|9M{MikeOeQkux}> z&#->|vh(+?H6lN!FgqiE$dEzlQhs*9utC}GX7&wB=MGF26b{MD=$l!XnNgUZ*{@$t zR=T}lSV3O);AH%ym!#{0jDGpq|LP(Rs9G>!$cT)r%)EkBa&O46!G-ywGV-%?;{e(J zu4WDCn_aMPro#s3XZO!3C^Y%LIR#lm1`p28DoihtRhXZfk&{34pD?JPe>&vl59wn% zBQpv!3kK$f{T6p*!H|B1IfIk?BQgi-w`fzscK>T{7g#Iq%s%_%C+@xQH-ITmK-7iNs;vu`fx z<{ zMon5ZZF$N+oev3zsc0V*`-Z}5{_n8eokIEc?UOX(X>_3dcz6_49O3LmZ`WmG6oGR%pRHQn>{=uv#>BfV?_Jp z9BH3E8TOTPij^V_^2E zumetM+_c#J7W*E4VGF}UFxk?A{H)MdLD-CD&5Jf7ZhW(o|CM4#`*uvTqTQ0-P2smE zinX1*Z&$=#PHy?Hwp0F>Egir?0#`(>5hsnWnmua z^D-+pJ9F@`yrQuNWe>{A85@CS!9w->rXHb}5JaQ$sCEZtQ-%P@l zKHY6Nba9NVa3+MOtbRF0`e#=r>*a+*Jt(g*qacizK5&_R`-UTv6tm*RB$d9zWP||* zrpHd7Y3WO2v8~O@&CD58Y+GYfc)}^nACj99pIXAnkvy0DGf+HggYr^&Vb>N8j3;@# zl7%k9r8aJ2JTQGShxN_Kj~A^YkySxz?D4J=`qoMdxC0tsw37Xk#bK)A`pa8tZg6G*s7fS3fq zN;N{jh@hyT)S|?eT8h?U#nxJFsl`jZB2q<*nhUFlTB-GdSAOqj=IkceeyX3}_mA&C zUtX_d=RNbxGtWHFGtWFT=WMuU;`B+1qOjOMh2^py#F*QqQj=aR2y$7N4QGMEtx?A2 zboXa0k(sxmJiFV6vfnOyQPwQfm)sgvSZbHb+P$io+NGK8UX!(Ss|UQOYw1*;YxlZ5 z-mVr;yVp%PoaG{A_ecVNP8!%O73i7?tdz*z5AOpXWnC>_HM}5>4~&=E1~sWt)5%JXHK`@T-T*V zYC1kYb0%FsmDw4i?+e;%#ys9#5&BCv!D$t%FX^uLX9Hw{{=3ASBkgDDz^vOARjMa-nRTtv7UqiU=D*FAvGclFb-UNk zSo%4aw03D#8@hDJLHzx;oXL=_8uRsdY+YAZbzvTlFjLy#R58Z&tnWVMYmKTx$KGyu zT>4C-wF^EWWR3B3f_DSvMf0ey+8Ql3w?;jY?Lx<>cg1u=Wxt1XGpn1*r#<8ov%8t+ z=IFlE^-)*#_GndTYt$9m7)`}kF}v=BEU5*pUE~8hi(8|uz^!vzqs-h8ojMHj3vGz9 zs`b%rsNYuG8g;XcCs_4*__&;#!Pv=IxiuTS#r(G4>vEJ5q-8y_j zCu8C6FW}?VY-?0&koMDBuuiJmyW7|f_{BzH2M_G+Z)xkI^+0W~)5%lH?eX?C(2K9( zx-JJhuk-YoGmpqICY&{fw=eW)+jRzPOyyJKq?|GTRH~#5N>W-k$(s%z>b+iL`f9J; z7A2cGsyBAT>iUMTHh=J!?ux1>ur{}!wKjYE^|#x|my=nCm-P3a#uDozw6V)9>1D6~ zgR$KIWz8V|iuHUm)=|v&8GH<~orry&rdS3&Y4GDU)xxgbX2Y$~B@L6|ryDyo^R{;q zuwGng+oKv{lt0ocZ0PJexBFAr?=*OkPsDhTp4YS@Ucs(0K0546JlxC)a80 zPc%+_uQ*Qf9f!_h^n{Oo3zJ=*{#KpSLu<4(-p_@8RM*1??HG&XYsBXgjJbqO?(#rK zwWgdqwXH>4cF7UMA#XSK(R2-Zu7;cn=IZin(@EY~JQwZg(~i1)(8T6#+VgTV>1VO| zQr~au2m1xf$4>-5bMf;T`EsPavlzZiaeWDE>MpO|8ZE;*fc~GU2hM_A$U#o3D2Gu` zd*C3{G1zM$VXSqk18?L3vYdvp5_$#tnbS>i-p!Av=r7psz1_4HX${akVxO#TLv%_A{)T!J`Fy_9j^}@ESs;a9G`sKnN zOYB&eOZKkX0{?}dqc4M<+_uiX5$hU?z&{6mXpN9Q7~--2(2TA|^UT|qANcTX)&ZY3 zw?sAA&N$xQsixeBv2Tg0=3&fdOLSlOjZO{iZWFwL+lrKK4?Z(Pa(_C20OvonrOQL> z=3KeL-aI|vnQO{8K>1LiN-`XYX2T~i zeqwLh6Rus+O!6_bE1?NpPS801x$Ab0x=JK*W%z06_2WS~gdfJ{cO&K~lmqwXw-fyO zqOUKqMSMCuN00|?i9+y`4ve9-ABj3b4(yk6#C&@9twrCM+zhnN>V+MSNNWe_;e|72 zo}n?JEBOC~)c19=MIv-aeyT&)q>p|WhjgfgUXIcjA1YGc)J}B7pY;A!f{aO6PbVFo zqtTdMHIx}>W0=N9e(5FN#}t-Gdq5%CFtP#r_}M(~vw3Qv+v4ME`)+WM&SSJRb{pt! zLykgp?gOwb{KK)ez0=X&-sy**ILyr*4$oou<>9Eqqd-@)x*x|pT9~JM)0s2i#ZES` zU%yRxuiD=JfV#E)ZW!dGA3m2)xjg3m0roq;c_;h^IUu{x`zy%K*ah9rmi83*BhDl& zeUC!A+7Z>Et3>p1lAMq!hF5}zGlcyV`fynyf(vGVzmvZ8RF%EfL-Q^5pLziT8cL;jG zUbF%_@UuI`dRK8SQ_ObQW?=VzcBnHO>u5h@yIEB_^1&n9IuiAo2j0oH4o3HfUhDK> zeFxAt|G=HmTO5uK4|HpK?u@R{T189@Sjdf^XpOp%E2*K!y@8U}G%xb%Y>e%~nd<56 z*64Hi@t}Q2$*$-QYgg2l)*3yHoSW=_5T8fzGh=LP7v;@IQ9g#BX3!o&zlOA3(TLLe zE^7b}tgWvqTcaJt?HF607tXQs%ITo11aIN%kWUT0j-0!-Yl)c>T|WZ)EneU0C|uv& z5?bHA7W^IN>-bT-9HH@D%xvm%m_O~HeessipWn$YIf(v_uBH&;F!@L5^)##GU>fm0 zQM^m6nQV-4h+}_pbn7|6 zj>8q}vVHnu7HJM{5`x5IobsvdYPdh4`c zhtN5#P4o8X8rU2Ab~?><^HZ?V!Ofjc&^rFSxjVO^B|6>H5?$-v6%8F|iLwLj-SwD9 zIm!*F4}@+PaSm(Rp_t=UZ&tg)LLJ?;W=r&9&>>WxB%Z`u&EDKe{2ZC zGsg=$AM8bAti>3P(BWt^+T*sy7}QqVYkY;Vy|G-?55BpOp&I#!%3g{tF$2+BV9 zwIo2_8t!3~mTsqcEZTy*8lnxc^^kdXce!VM^bF!eHp4mw|J;W4(dlTT@fy%p9|86R zq7PpVxe&7ykF-My>`)7xF|(ulVtmrry>&@=338eU+GrjW&rJ9g<>|CXv@5nQtF}b5 zNMF`A#ASKDc<}2p@7*@0z57wDUl;u9@#2HgX^0zc_)!9EYJy(mOpsAG+dF>&dJUg0 z@SSe+CEJ;-P3YDMI;qRsMNBhIdG<9iXLk8@9Xi^z$aT>S_);6YEvocBH{g6ku~`ER z$$rmQI15$Z8P(Jtx&ZX=10ChobViPyL8#C5pijUj#SzNSDPJd9sEs~h$CIhZVQ7C# z!e=pZxl=bic0z@&pZfYtdighW)<1jARl}dO_VyI4NAKxx&ZHkld>8=+m*D3H{QLqx zZ{f!R^9A_Xi68p+r2Q$8{N0KVTyQXtT^Ye=ESIOMPtivCychXvK%w(jRrdh$a}Skg zbt4~1^xI|RE{WQK)ULykj(1e#m73}8($aAMaA0#M?ME-89&4?W_5;=YbEg|+%(K(M z+7+GpS}npC81}U=Y>Ht|QhpaeZkvGd6%%JqTL#?A;Cw(b%n^5Se!EQhB=JAe*xoa=J2Kai%M7lI{P8a3p$e~>aeI79{D*KU#(;A_&i`j89BJD=@ zi=AyxO{Ux)XTj@w?yIOAJ70yAXf@BJg?XyDhUQ`Cst3up4KrbQkig*qWtJH?Ygj_ha>xgU8CO`dhld{Sn;-xRebiw$5#hI(zBj zPW1b>jBPeO&71D`#JwKMZRq=5^WTYlmGpQA)?iGYD`<>w$Exeu7uj2` z)!(wi`-RdDC-6yj=uP|I?iAZ_f97Vl#qGIU@Yxt`7koD2o^(T$@}IRn>=np;+~#f3 zSpMV2xdLbEL`y${eHeVA+oI+0i6xoX7Y?kChOi$@?^usL6#D}78!&fbPng|}b?H!8 zL`}syrv0Fnt&h^4fVFtit>cUgUc|@j%?C6wJ~XZea?oBu<=*?qw`~=>GsPJJXMgM| zSl^_7ic5$Idxb5lF}AkxL<{Uncd_IPWLwg^*0Lem0=ts_d)pSzJx=z<|4qlKTUxtl z99MfA?!D)9uE+lHpPoO^7~i$VDK?y%Y~SfBh{CFgB_;0*V$T{V{>1LVMO?xjLUE7E zau2a}fcg26(<<06s9xyhzud{AfBarK7Rx9O{%^;n@%;Khv9HDWTx0W@f;%5^FEDRg zbS%XOTlUc?$KoU136ZRQa7JSIiCGKA|nTR)RZ2>y|lA+$%_`sJDTrs3H~AJ3L9H*$dlEq0c5_zo^39h>H8T7RlFx_%=7ZE2<EK|Hs>Iopl(`4Mt5;v@P({x)q}^yUefqVEeC*CNkviDo<2MRU9H9LI;g zh>bp+X_a1mX%*3-&+gfQ7D&win~fi2m)x zEm3+7+kmx7{wV4r#CyGH^Mr0jPH?k`-Bi|4rWj3S7s}J^GBdXdfAFxId*U&k36jl8 z2DhiR>n&Th2CRY8@PDP9d=+<-)sPo=f7t)xzTS*-%pWhOdh9W3q+Jo^Z{<-Qno|Sf zPfL6Ej>)+ltsc6&nI-Pg6tuO5+HhyFElT%jYw+BQo?|(x+cTY})OkyF+jquj+7l6( zamP5POKG?+HMt=nwF@!-e~j%|zekYk(!46sSJ*bv-aQUHq<@^9uh1IzdoT~gbb5w# z^W@BqR@mu(c8!gG-#0|$-kF<5bC2DrwRcV>d13!t z+(*&ciP2?4fOH5$W7cDD@|DtDj&=EcF+HJ>z*glX+V^mQ;8Q-(OLq~sccAiIb1+S_tQ5;&| zqu9~=+3)|~XJWK>(0-ATb?_b9FJfc6Ae)QMtM;>AiZb-7-U&98y%cRu!6mQFMYpd~+``FwHu%zJ^$H{!WP&$B72-%s|zC-Eg( zDpTz1El(_;iJhIOp9enkbL8vf116KP@=!$P5$piT+!{@)?r;=9*N?*2mSAssxN2AQ z;p$y@M%04)QrtmS;ob`6dtkS@_$2$y$EO3I`%4cXhPHSA7N2f>ZbN-C`|XKjc0YdP z=VRpz&qHoI(Gc2wfkNq2qatMIV^b=8@fgjS5Ke8)I`-oh7J$y-5sKXtE?33_-a_zo- ztd+1VUnw%VR2)J+Go|bz1^I`G1x1|L#?Ay1uWj_|m zzJ2$#%*W&ix563jMZc%Xz7`Y8BDyLU`XxNjQjG<{BSw9Z{PhbTXC^L*o7xB^jU?^y~z)>)Z<|!;xapq zhbc6#uf*rxmU=uyLd;}qO{(A9a?1YPoXOaI7-vcr)!)~0RDAAf0jZ#qpL<$r7B0VZ zVRK{srAr&Jwf*})-I?Gbn$Tu8af9+pQ{nDDIF$D*Jv(U*=Q2ga#SvFGHX`Unp5Xg&NORkYZ{vC8k<5=k4v#NuC@l_`d^c%~YuWcFE&l$bh2Mj;EL7A`6dL(G zWEImI0d0K`uHz<5Y$z-({5}Fm($M$OfK3|y9s-OQDGWR5dyp2Fg&RWQ@8ts%%PJd+ zzLyV#i1d4UR@sOUk^WE0s;z6NTT$CIhG97`uUWiw;h6BS(qTp6VIvC`FIZ4q8!il) z4UKhm%Nv?0z+Ad&Mg7W}T65g&8CQ%jnN`cmi^f__rqwhGKW2f6^?qs7ss+oJHeb4` zae=w0W@&w0t+{$>^AfYMu4z?$vw2pZ^Xry2)|#<+hd|a?x2UeMZpFg7ro>*XFRW`^ zY1Y@RSPVAbN!+w-X+y)(6^qTqHH`~u7T5J=G-G9Bo!N|7XRcgPXRca-0M?6Pz8UX3 zY}l~g{pK!N+62NY5d6%Ah?Fav&DxbH)z>$Hlex4RAFEdkGp9D2Af)CR8IOreaZE!q zSN?|~o9mjINm>fy3u`FQH$!7`tlphtv7h35ZB28HxpW1h`=T1C%B;bxXwas*h8od7 z^WTJDQCC;nWY(?0Hd243S!BZM4J*OoEIqGS38}$r5iD+Ev$VwkO%71O*yXF5>(;RH z(%6KWo39)8Stny)Tiip0IKiHq9$1V0Ua{OM9W&b@i3dHCwQJLQO->f~ECKo0ozFX%s`s zBz}4)2|q(#MgJ)8iv4@wKh!<(AL=MK{H}iozKh^{w9_yS*5K+TqL`0^Z84Az#{W?} z)#Vk%t8BV;nxmJjlI|x7c%Lc$Pu9JVsN!H7`zObJA<^|8>Qer#?%^!f5bMe8aUHJh zlt|nE5CLV&t{>AFD|3h8wztugQg*bE8KL=~n^Zt$Q4+FogmzLfYs!GGMZ`BD6 zeXCCN`c@se(YN~|`~J5&WZd8VFSbm+oAUord>;*vap>qmhMPQd9?Sap&+~?C3+AQo z-TPcd<*CYl{Jr1bl@!G?yh#pYppl}?R^~Z9FqN9jl9JFb8y{oQhESm>Q@sj&OV4Ce zy~EMyB$}zHNytGBV^|mtV^q>;QP;=riGx)l>Rqw=q%>u)o7lK@(W$RjNlKzdsx$h= zIh5h7np`4CJZWsOn+8as0%NJ5viT8}*Q+>;9v(g~c$9-It$#1h{rU=4{d)$$L5%8% z!vK;=PA*+A(_;b+>`%PoFd$%D+(B_-ouubBb6s-Hu*I~Y+0&Yo)HlhUL?dU~G(u%r z@rej_K`+!xf*>5zoCLtivb5NI1zAom+5)&3862+{y3Do51M8mg@`UZcWC+G`^(bwq ztt-JXzejM!3VOt5Y?y56f*g2QVNb`NA;UBzV@2^PU_QkFF0xUHCT%1b zmd0fgaD;$y-Ioo+v`HOgDpO2xq#kz!Tv-6by>E06u_P@o?nOGrZq<8OjkQ^c$y9(i z&MMMFELn}S2NI;?6Kzt)CL|$@Rt~eVWQ`jWdtgC5$!09Tg3Fca#1f%nBZbt@3sn;Q0r80v708pw3oI4FYBdV@LU#~I%D-T3Nc?k2;=rl zcts*0X=WwW(`=+78mOMJ%ZJ$plK#>N{uB-2Q#5*0?U z62R`!d&lV?A5ZkcJ|e;eG$nQu(MoYkw5In2MQR-w+y4S`|HB?413TG@_YSEUaXvzZ z*!}^R>j|!zJv&!cEVKt>+gf(-4bbYD0%JMfw)kMOcy4b4lON>ukdeKI^uP+?>FiHO zktv`jWe1e)Do^7+^gWNL5x>erCI}+Up(RX)OKU?>KOR3i{ZbgJZ@LJngmx}q!d(1v zD6a4KYOINpVjiecat9I90=;iLWiE32+k#f}hd_HRW?-Vr& zw+}{5KA5=&+>e?*nvSy|bG?26YSL+Z*Hv>+9P})ayL7N;t{{H7`5U4p;gjjeURISc z_fQ%&aaCa{a}OitiA_ae<_;0p#8p%*BzB2SrNzu$MC=k*QL&i#xJDui>+7O!u3Nyc zZ+{JnNK!~0ZsNdPowJeqNU1e_Km;{^7>=5BYIR+Oc^O=Y`$-jw8KU;Sktk-)1`pTR zN)&^l_;CQmY(WqlhN4A9r$%~p70*D$5W#09@xm>}8u z9TgYB7m~w|Q}H&WE6Jm4skn?rimasKS_8#%en`bfF}vhVLrIh-D&8Q9AHiD5dv2!M zi|3)ZSI9aMN=bfDOy&_xKY70>-i_%e|DH7MdMkwDqjx~SzFP7hpTehcC1#!cCn~Bi zcrt0p)m4bnfqkeGPWlcC!bw#o^!Hf|CqSWJ19%jv+&)ldisIUgIe9iY0Q!1T(#|Ih zCtz+V{YZ3-Vz_%D%}D8mTt>fM$j$niDFf)qhH*1|Hzl2lV32x6O+8B)NK;aSnz0(w zP6a)5?O}h59xGdMYQ!?lO!3`=&wl+d zPXCuCfQLy6?|%hcEG6#|DwY{276w4Yyg!Gva#K>D21s4Bf~9!hL))NkB_`T@py4;hzpOCFy5~$#x{FLwxHhV zjG$r^6)`^3#-n{JfZ&nEynd5NEAEYxMq;Fa2XVi#**oK zF^oOzos)nx#R$Q`-nmqyiLR~$nl}gt6IG1kScu;9iUi!JNHM5Uh>3MXO+PGP4!G2EP+3DQ3F$jS=3-4wFy8NMGcy%4GWn%M3QA2 zzd^iIhmtUAFqdgm{bi5b>Ho-Q?1ZX@--Hi{#i$m=R{AAw^eK+{cnyrGme7>dpv(9J z%%+xp4)27-#{1B_Is$nSkSBFv!z!kh*)khh#AT!{w2@2FjG8I91dMc8M;$HOrW+fR zfXb5umn!4qnLuNtEY-$VY%S_ovbq|qHI5)WtHM1T!FJWS7{*W|H66Y`X(TRx5i8esK)ZV*v0}Wc1n|#Vo-mQdFG6teJ+3`REP^gh(aHB0 zVQkEkKXW1AK^uDbMWX?q)TD-d{8r4y_ks=m{1H5Sjl%%%Q`QTb{4=a7--|Y@Y~Dt# zhqN)RG;VH2QyufYqy;w+3S~4lGv8rtJS4{a6uu1mlCM*vz1$IeTH*h~(^}u#f|Voq zoWfs)Tl?P8Hu|akkiuUBq3>huI27v$9#Qx|utI&GXs53vd`!t$zMT0!)6Q!qcuL`q z!C-OxvBJkek-jg)v>d_H3Rgw~e`({d6#koYd*K$9Ps2lF-&b~ftI8iiO!9qWi`S-_ z+u=ICGXiT$h9kIHH50IB`Q!rA6fUZMK~ktT>3vS zgd@0B<&&^~`1;s*o5~-9yZO>|GQ1fzK>Amm{2k*f8^NrAH6*_`D z9sEb+;xXLr;Lno$Wjbw?j^J(wubTio(#H3pJrj7e-G9G>KLVeOe{bhJ4T-U){$uY+1Kg2fT2%d28Z%7{#Z2Z219}5Fd)Ne!dhwnQ0%)!7@ z^v8w1+cbX7G~jderv=`u@q_0BpR3b~#e6iry`mRx*Z2U^|7?Ac(C==Izd%dnJX`)f z8rO<}FVJ_1rF5T`u?XhANPknXe@^4Kj7Rei^qYmahctd!Ht?nTDPi6t8gIz~uF;PR z`lA~E5GkE+fqqipV;Yar(x}yUh~YalUP|s2!zVPpWgc*y-F`~rjby$>`fRb1PiuS! z@mpex+otn3$=#OfBjD9oE;>Jh)Yx~K&aNZ8Rp$!1=Q15i2i~Uh2Wa`!>rTAbHAyg`3a@CQCM3HUnwF+u;R&L5`byIKE>zz1~xM{=)U*zzCL zxr5BLSAS8oKdtkoe1ZQa@N+tUh2;O0-YM`QonM9HpzqiE%m~SMMCZFnUk~UXi1wp8 ze{TfvgSI}8>HJaH-M3%=muTkL>w46TF`wIQek4GA&~)sxoUDmm_HHZAiXAZA{tg@igSdof6i8<1G0 z;c8cGuEuuQJ1vLUQ9|wALhhNCcM}o5H4IHd?ni&hj21Mow4qc_bQ%ptOH9aszgsZN zi48n$7)5D0fSpb=YmKB^vyi8HS1+&apBmWZPBxI@! z1TC>64o;2w23fxWu2O`cegl?BnBf`;7wwn18Zi6j9L!_h3Z*aW@1rGSe0Ux-omP(` z#AL25=K`8H0fHj?={SXTRgB^Q$ohvK0CdfVEBm*QXSrGtWCsM^MXfhu7A!Ep90t{h zWN$zwB9>6XCYWqMkQO{?au+;sKsJ$4vNsz3F~B0VkS1NbF@phvMxxQFRp9pkae}-A zCAauREX9q0o7jQqO&YpjCPWz!-U2e?M#O~yMKnj!zhGZ1*@I>-&Uph$Ye6RtuzOGt zj(|r7e}-LmHD6Mzq)}$bon0@pKgDL`1GaLH?Csov!uv$ z7A1jP$Y#T$XA>;v%t=Jx zNXYqV5k$%P5OeL5a~*7$nDZ9;Cgm(Jpp%>i1dqNs3Gj0xX929AoO5R;j&3vGekvjZM%xN>`s^&a)0Xi`6>o8+>;FpvH7|+Av zfxUK^FkFaMfqNy=jKi34;6905hNBGV*VKueRA`glg%{eyJL83jA=!c7e1j^Sj~ZCu zK@x)2Rn}8*q3nQL8Hr?uzk-@TnnII7BYz+Q*w2P8&LL-DprFJ_M>^wPV z8s{pc3mhOc{-Ytl=PBfgj^O*6IQ0b1w=vR;XNIBuLdDsS+CN5C)dzT~SoO%#blwcl z4XjjP4zyz%twz=z*rN0k^w>tfz-kEGX!FB1ItcC&xXH%YMlXh90^5|6f*#xEl_&&m zv)i$4E+fo#p7t^vpJW!eAE+o+4Jv@}WzImIO5*WlCWcz1UIqh@)vlWexLExmAU5PXP=vYif9(N)~4U@#+(9}Mb?ub za|MQ}0m#A0Ed#?vnWp3$3>Xq!Xft+ddQTLR;9B@5+EF^nj49nuZ-r7CafG;Co!^cl(` z4)CxH%gopU2juqtp&1vS2W0ObnsE#Pke5;?!~ug`gO4Q7pew{Z@B=<7Paq$rMi(L8 zB^II{pID531}#}W$zHMIl7ml{mmDtHd8+J;eBu#wb7y2Mqi&a0GL~WfOz@S`Wn{{= zDy7TFk}Qz}eNY9hn0@JRZu}fk+U&an#)BG}>jPND>`M%jlsoY|wte1=viD>7h&yut zrH00D3z3Y8n}75(476kpBo`oic~8QeuB^gOh>%i~tS}XckT&(KqJ#mG(5VrxB!#e> zNJt;}aEiN-^edsjiVlt56??c$mgdwfjGc`xqL(pWS{y;ag~O{q6RHxL|=PgMOPI?sx9b1s-T)-0x)01r8`L z2yNhgXA#0-Fhil6eR02Y0!j>KDS1M*M-_g~Bw)+N$8e!T`pLEVbtwE7@PIfzuJBJt z{-JjJ3Frq77RT=^d=1uHaF}xG5*iN|Mu!uDLpD7wU6vLAS13n>e7JNu4_+0=xO6c{ z9}$}#mo9^mg2eG|m1iRX431OoQHVb-Vg86yR2<)@@^i@>E0qqxAD1!_1j*oJ<$Zy1 zDYIY}@HBhA5377P)>RPOq2TwZ%9F`QYsJ2dO9z!-kKH1;Sdl>!mo)3iGcQvd4jTVC zH3RRtvfxT(u9)v3ToRG~S1BKf@s6l`B!Y183VS|BRjeQ{H0qrTH>ye+P>F`na_tZ{rX=xTjB;&S$4MEo&26Mi0LqleW4wiUk(4D5S3Z%qCRwu0 zpSohza%6TA1&nbCpcD_u)SzhuuuCNsw5l{-w&5QGG@R}PaMNg1)94}DFW>k%7FJSW zn~*bP=-B#_!m_Q{`1%~6B8ke39WY8#DTOIDST2G`y#v+4g2cy{&*ikr-fuT8L)>h~MX_E~Npk)+!k=|W9F*bQ z{He)+FR5}!7hek&)?piZ_yoib>t!4I`BT_Lts^48fur&{qXGY>N=0V#r=Vi%6;*07 zm%k4ESg)%6R1zwmzk*|}byUq1FvKr_BU`VjM-^%<=B=2H^|~sb`jzqdSo7B3)qFu5 z;m<)?)>|swTS60jFBYBEVZ$o^B8kyy!};8Y_+)jd3q{{*zB?DN+m@=9Kdb{DS9c0k zE#a5IS*@sQ2{A6?KY{+Ow^eEWdVUzYzx9qv_myg}p3|Q_uuiCydeE-NmsA43tM13D zN4lu+XW+QjNp%j^uh`kLpm^&&m5hYzY((N>;P=&KFcuPjg?~V^{6PKr7{b`uDrqAB zQ12BOJ6juk!#bs2F6a@-Hxa*&gf);jEB-sjQOBhv5&(()8DeTTFe+Q0ZePv_Z z>2D|k{#x}ye(cXGPlu;iii3Byu7$N)( zQj^OuUbG{G@5O?$5*_3Sjvzw#N9O}4JFXLgBZNN=jaeQWBZR+?*kq+T$X^}7gA{^k zT{<;dz~1I0jFqEHhjsBRn&Mz_cZXoW+arLv`Wnm#(SS$#0_NE;g=gYiVGYrxJNx;sFrqb7 ze-=JZ%g902$=8!`3`4-@^=`ldy`O-&ddl2lbQX4Me zcSGCO2yypGOW_-0HCmq_#Ax8nLjcFvx@zVLq>ZsU`I{PC%YRSqQeoe#wkW)HCh#~L zx8af0K;ZHAH9ywTpQ*i4zecz>GQ`;$@I?FG7wc#dwkT_oJ`aP7b#!z*@MN1G)=@j@ zcZ&WR4kyS+6kh5DKF8*NLggLsOKX}gk70PMlR_bJhJKOY_p!=P(K`ZtShTpml+Hmn~cLgU@fxoqYn7od`Kvs z2)+tW6I<(G`(EySRJh4tZYqKFBYgOl$vu^*<@KEx?kmZt1TxxdoZ2^W0$LY61a6xu z1GSO?trXFYUKJ=ODYRN*HS57$XaE06oSSr4* z!v;s}WoKLiR~kG{hHJO+2MjfMJgg7)p43%%x;S`(+;4oTiwRZA?Z$6RD*)w0$t7US zhnfaYlFQLFjwAgWJXvloxyJ9X{02{vC}eC#WF0(JqB3I|jeZV=MXVp=Ef{g|v^NBr zf+--nyK@82V+tZo$)!9-%$v@*xtxw>6t`#!xf$J18>KMbcd&c7bF(z0EwWoM*6k$? zgxMdUfx2Ceg`b=AFM;UY5n@2+FSq#h4wdf5c(777%HAmUmh8OIR4>@(mB-lD!I$#J z$PHgJ=n-q)SmHrB%{>TIc@_8N5%L&683z=3S0KF2P|NbheIkJ0*xwgTm_m-cg+IY z@;MmLL^nd#^qXcOkkCXs<^ye&ls;oOd@=o&->;-LzsT^@e;U4=P_~gZ8Et!|@`?>V z!fpD!3&iN<#(qT1^!wrQpo|!s;11~zNS>8Orw`~sdVol&+yf;*`=LCb>BfL0pob)7 z74xnfi}jN`BLU6ET1+)}W~NXxGiGE0ojXY&4K6TV#Z>}OFBhQI2t83}*-q5G+NYw~ zO*uG-2BXPKhSY}m7NczJg>r_ZJ%?5(lX=M*LV0(PH;9{-yr0NY9FbZ+@&ac9-dCSO^j9bA!uRZ~t$YeCzyyblb(v0zl5P2(N zPVUrxgATqgA|g(Fh%)X!Kq=+})?cCqk1OB@>6c&+ZFA*aelePjHHg=FjZ~x&PM-(V zL~Da?E>ah)TEz02>(MA~E^1QHx=OaTrZ9~ZNR1*WXULcE=)yH`JQ$owVBT?P6R|Jxy+L8;V0K+MOD`8RpbTK<~X6&^>g_3{V?65M}6C5}5>>1TPv|ArF+A@$gij z$Q)ZRUlkS^j%(D-`x%bj?tFt*g7HZu9)u)!3o^LgOdyX$GHB$dNQ4lUi{<0X_Ys!e z($4DE@2qb9?QX`_2w3{j2Qs>iy@*Qr10?cbN+g5##z|NT`2iF18#GA%pcv!lv2yeI zPSF`JXVt7``56*9+2GF-p|k?$M0CsfBXVkNItWlojt_Z;nsXHXfX5ckBO-YU!aoF2 z>WW5IV81y9(8LN#T2M_ zx}aQYUo&2V00m=-49g>xo*5TZ(3unu3XI*@zzQPoinajLC}AQXoDbKpG=tA$82T82 zxZy6Cn1#*ExEvEJm@Fm3GZF|>FohcAxp*UbdEbKsY&ompsWC62d)wh&d*5K*a277wL!P&(+jUs;p_IeI z8q7F>$QSZTk$;tHsAQ&OrRCg zl`l44JRfMKyfdjbuE6F~*gz4A-m1F+_h^Ne%eEzk6XCb8@me?q(sLt>)T*#ayP8n5 zaTRI{o24e!7+WR)t&(W1F%%)Ja5d>n-0QA}RSU27pd(%6vMkJrm05qppCm=LaW0(7 z`jcWi1pn&{zypd*#x!1;2KZ-1=3g!zLPWM6S7ZX_<_9&vzbJCj9)A6Fz=MiRto;0U zV*sD9A>Oug13qcPT)war@OecVD8#bv0`(eevx6!!7U4R@+UEEHbc0yOi=cOFyW=kS z8CC+HfqmE7;h-Zqoy(dp0{pQ~Ot_U2!JhqcQ=uRh_1jn9K;TkVcdL~De9Lc~9H$egyC z{}t-Cej(1kYH*2o#9`elj^lK;`Vi+9>sJoC7J&5-3rYFjezS0k6TYkk5yPl~w}h9) z*4v?Tfa+uGZA2>2a)~^~F{nMfLL$HMAhaG{DUoRuK+E9H?1Y;bTcNe0BG?8KW(Hlz6%|XQ7?)yCDk`~Iw5i4}IB!v@WTF{71!zQUxEGtibz=^#xs~u(Kw058-uZ;ipERIO2dV)Q8YpFoMPO8MO{=WQI$d8Iw_hc(R}0N zSfEL=U$xNybrwyQJZlYlIi_gJHA0p}2EAQdH1!?fj!Tf9&4Lw*t{+1Re2S*NNwP#z zYyjOLk<0ieoTX^9RGEjlE<{)?+CpmgR$#EIqMJS>4*vqTqOCC#%$WytvlK%$%8>{b z-6GpGV;xQHRvMPly$-CqqHPkH#_B;p+vQkg##P{7bX#0`q^{c~iWoyksvR+Py-^1A zV>#Xw<1zS6(H#<<1ONX7V`UxlFxDP+DNiDF^E;B@OMMi3_u~O_v_$*Sy^BxBT*65< z^zf^x)onvRA6^L9SCN-`CVw#t&`{*wUB=(Q4j)cd`~-BYb7rZ0;bpz za0<_&b&+ZZwJKf!Q-;0bK{rA<-%V@Cr)(1DyO`fjQl%-!Aio-{X0E*#0{>QgU*#z$ ziobgngx*DvE)srXaS3c9midz}i4M#V%ls*cT!vWYPfLVt6;=rURU*G!^v_6S%0>UI zM7eU&KPOR0F8b%`Z)?%MBo_S(5|uOWI{0Z>_?3@Hlz9#e@M<~M6s^$T&~QiZ7ZcMA z2fRD{y4-f{MgMoWDkwcNJRBP@kWYq(Hze{K9R=w3W=u>koGkoSOw2v=fI8%+h=}h+ z825y$6cT_}6Xh(CP*cPo4TlcTR$hjck+JbN;b!4Eiac$*_-G1pb45p_nQ$hWPSyly zIS>vgzbAf`sUR7oydWpX>6v$!+Ym2lLfmkM4PAUm7NBWEH-DK%%T$hwz8)S%%noPS z(8tfk_8kt|&~G0CXdE{=RP4M?Ldf$0v2oLKgq%lE&f0;EVoG?h;>7ykw~#O9Dg#lb zdB2kan5Ps9sBs4gHbj{vpoHJh6}Jz=@2lRhslk@HgPUrM`9G&FrT*~AcTu;7~(E6 zU5Tx|V%{+gaD**$8UG3n7anN~SgL0Ug!6)$F@1}klikuuzLI~7wV zX-X=S6eF6T%*=Q#=|^@TSBv!;5pS=jcJYha(X|m33G#aS{5Tcqv4;z&eiU!|RlJEx zXrk2AsqGL1WLwhX+4e_8lF(<|_M(O+e%2swqhf&47Yd-C*xX1?d^ZejS({<0{P1|? zIW+U1QjDCSoD%wCd?oxoT&Z~MWpXXtD?Bmo)&nm9oTQYBR%C1a0Vmtg!|%ukoTAi- zRv+(xzQa>(=;uGBb$pJpPPF2i6Y~M5DL)m^(?fO5%Tu5|jTl-X1!;ogmsNX>w})03?@-&ZeR*#Z7e}`UE?vQ!9^?u8osY z2~AUALfmS^322^DA_R)KL$$@*pNh9rymX7Ps18ghfpThl0G!%*TJE*b)q(I@W!7le zkG{+j{!u*Jei0EPe6_u8;oWr7<25!6@QD;@S`>M;Uo75i4__rl-qP+vtMpDtjmVJg|T;QqNtb%(3en+@|=L)1a#nEB)Z zs2!@>kBT|HRA}YfP|K)kT#QE^>OG%r? z)(Ev6!I_8Wp}9=`0m>9aU!4FrQe7jU#z(-o)+lw8fG&RFIKVOLFR`y<^We9UAQAOX z0(y8O0;oEiX?@!6RWv8 zPE5xYxACb zpVe%`eEu=Qm$gbABQz8e%g(yOZY>tyIj~l%Gev6|zn!MA#vZ7gUoa5xN?VL_e)TZG zABqRMv_;_-E3O`LnwZjljk44*`Hs}E&>X$u?xrw;u1~~?{4jJcB07KyBKb?S_Qi@p zA9`^ScY^Vr={9tih^8jdMAy*d zsxofV6^)xBgIfp+dlBW0aVF%&l0P-cJ|w>TRGOfCI8I3pE-8hi^b4H2;_ZP5+T|p$ z%-!}#Dr%*2$>)3eqiYr_oZ1BZP8g0JKKech9DWKavhG6QYO&U-^w5zXHeko~_R9%) zi}WJER@-kiUN#7DgLte@0jP*V$i`Rz;`kr2n01}~&VYw6=m*$ldkC&FXenPW0v^69 z$Vbpp-emVJ=D$k<+-wt<@#WZsts8|%6vaDeW#43bbtNBkA>dZ^1_(?qMNC5iVBKQ3 zPUrVb1iaPeT*bdYl(x31w+rIAoFxEmw+EWf7m!!)w0*vs{|Z#rF1v3n_fRCe+n&)9 zXmBnR=34@DKzSQL>zjL?DBp}S;{3nVXHh5^O7ZYx^(89rART=oW>WAmg}zVKvhfT( z|AgobF4Vz01vTX*ZfY>-nLzG87LTVh{emO=1WF-+EJtl4Vo9i3j=;Ad#}IH5lA1-_s)kx_KSAS?}xB0(!VU8}I|YML-{a4QaCV51ZJ}PtZUg>OU8)0X~Hy z#VP$60Zsl(iX$KCCk4#r*V1P3FP%8j-O|hCB_HdV0_O8VD9HLmFA^}spT+iOeX7f2 zK`~!Wmj29!WxPlMJgv_Z#O1u5T0hsD1&r_w6bir4e=cApPeC-WzSN%)a0*{M1@J5V zq=3`8MK1NVu0uGybHv}C0r-ucDd1fGI8+m1Io&f;8sIH5!1MZO0bTqN#0l#Ky;?wIsbFrssBaL^ z!{4OUbI681KAINdOZv}6tDnlRlkvs=sfWi-(1Ivu8IKfW7F z#rnH`r+^VYm8Nh^e@wti@x=k_4gC!Pr|=h@Xnj+63-6rHUqPN~y``55Sj9KuXlr%o z(*>N%*9-&fwENEI*HPat{R+`~F+WVU?AF@_tmZeEfXDR%0@lJj7r+<^e}av&uFIkI zVQTc65}!`uW{NVck2DH0S>oFov}F&(PGbda=;q6Hz-(;;hNA1#ZfpXUC0=u&gy=7{ z-RIbF06)Zuz7~Y9WI`lVN>RdF)gc5J1$zM@c9~GSo=`G>HMG)d6fy3j5w=aglKM?Cjyi$1 zU$vIdbn&>Z^fvjpj@+RIlTIM@48M>(#i7xchn?E(`0Z=TfmdXGhWWZIUHdDl_#Nc8 z_`Vs+WGDKvfR&)VFCcy0jT+pv(8Mn=qFzY~5yWabP|hkxx?)<1+8UUWch3ZuBy9`I z#B@7(l{?0i-vZyW`f9%ttu85nVN2ka5+vKi9=;o{XnAbt<5v~}rr4bE0EE0OReM3O z3fNf{4SSZzB$G_IXw04_k=kKOx5nF_rgrg*yc$h3bEozos=ZfYoq0y|O~S$x-(MJE z#J-hEJH&|O6f|Jbi0yuaz1`!1>=aBME0MZ+kK!yP^U8hoAH z8mWy%nPnYElH{=zouUq>FRoas{q7v&|Ab3e4jXFxMOsXnprriqCAhn#>oT^{4J8eV zEFQlT?u7AiCqc!J$Pa#uoX@nLanh@U;(JuqvrdR5{2-5_?{iL4Eyd>DBMUUdF=4neovb`Lq_w(AjJinU%6Y$ z;VR83vmK4U>HzF-Ll@tMHE;QyGWl`yebA3Jz;5;MeYB0I+t9}sW7%5+Z5{aeMhcSw z8wU7;g8>IQt|vzpB4EBWtJ0P~!y1)RbMVTZPc zI&T+nI`o$Ul_k6ccffbWsCW{aA71UD;((Fx{AVF3Jim-8^6|^}$uLnd6=kP3hH5-% zqUKzbHSlH2P!Ky^2Fq%P={?p@^oLN#|A6UPJ4F)(o>i3p-f2UP&!bu1WkVPLElIjd zbd(qG^n$_gtHH;5RDTK|PVIU8mXYIAl-$rEb5EsT+ zS|o_>M-8Qzl9QOiA0Q3dZxHR{Q9clFrxKc;#D{Md92=IoSCHM0ddfxReJ{lVdAg?o z(c!QlqCXc!8LAwMIL8jXpT(I_jw;*fRX23)j|!<|%2#{%qbVG3qTE&XqT~%tGvZB@ zxXLE+Rw@aK_9gLl%4DU6?54JO6J@p1mSRG7`_JO-l;%p-)D+wB=;5rikh?0@E>8J^ zC~hXf7?N}ga?%s!#gd&c)7ig3nTmF)iRnaXi&HLY=?;TZWj7sHB@^LFVmQ(?`p=G2 zQWo8dNc8DVxmHlp0F+=$N;00<{J`m+csm_DrA^}6jlKB$q#&YdI*#@tvR@2-FV2L{ zr#)*v+lh$`sy5MJK}6Nd;zXh(f-e06C)y00+H^rm!_c-Y9(SO2HOff}r4+H6ErO0% z(!Lq1-4(BWhH8cCs00>=@Zl>)c8f^(P@IhZppty1B1)tX&=Omxb}UZSADfk1{34T~ zX%H%W4-OH`RFq{Dp`BDR6B>wXHx|e9;*_+>_M#Nl6^6AHHb+nr7utU%rHD-Sb?A@c z?UZ%7DM^#zPjC`uw)axC=*+!YXa^I%A6E(w5LFI8b6{T6|X~L zqs}iIvauW-yHk$>-T>(eOu3M;8_Y8o6LGy5w`oFtw>}VH{~J@H&j)8a?bh5cW^Tae4Ic zWO!9(^A&9L2x5l0L7vg0iIaCH%;7J0?sZY+2%1;!Vk;6&xtl4mI+bCwrgVS!yh~+uYVF{*G1TM$E3W0A~rPqPEzQP z$++nkYCge-_hp#MGiE?OvPCh{m~{Etnv`%1mlDdq1v4h&FuG9M<^2Ly%pEg$9(B9L zhf#8g8=36~STtkuY6S8y?`ab+)s1~W?E(uuu-~PGG-EhyKlW6C zKrVx>!p8n{ia>5-vj^y-O9k>6qmf^a{nzCJ`HY>&iN}5{k>8-3ys@9$EZPD_KV+F> zKf6yL)A;dxpwp5v+ZY4YjQ#v^(UxnpAn1+#LZW6KT3TK~R ze))zEYpCL1vMprXg`iyV@jWm9&l%K50Bpf_@?44n=%{y5dV(Ui76eakpRb6^TmUoir#sReVjM5r5fE z$t~^!_{|!$DoO&r!>Hu$$GIw2;}kUyA;`vRbW!s-d@WX^iJCt^%N1uNABU)Uo0MYL zs8oYLfQTBV5RoJJD}@ii%CAtwgL?=40my1JR5+Atpm9eKe{g{Ad@D4CZVKq}dj>ra zuh5li7ZS!F9B4Dp?iBAg(bqireeke~1o29m_=}F0A`(=%Y>aPvCguY7QD|L@Z+Cu> z2%M$4dQu4KQSMvJk_LqJzhoH zQw!;x`*;ghu#Z=f{#5hAlwMV&K-D~*fvWyCd(xn4*7rk|->y=qiZ2?7ssYMQ zF^T(Cz6Y@j-wBiE$5&8OX95qjm4vULuI0c1nYJcu1~uVbTkG5DI0 z`)~A$;;sho2)VrOFYadWo{;+y?d@*tI~a0TGe~-P^$EEy{ngVPGITiPPG`{cHbDbi z#}T8C8c@&r{TjmBiSf!`j6=m=OGwN|oFj033vzbjc+1*3tgYf)A=_TV5>h7j2RQ5u zYp2Y(6+V>Jef1Bzv6H#L&qf@z#m}FzPMk(>m1(o zbqptD-8O6`uoMVU#hLjyawZ5m2j`iXG%2sgk)xmF;Cy`?xlG8MD}~Hbk=8mmWouy` z!r)y*pVGqTB(C`!50Uli78Yl1PvN~SRLH4*RXHsJ zOrcn|ATIdv~O3+pd?X*7gZw+P+a zBE%F}oS1_44J`t1v{+1?9?utYnQ|kQK;+tmMoXtmcY=3$l{6 zT?F-ZcssV_>}w@op~EFs$vSOIk@G}rpz|LU-VkS93DAYwmJ-?6FWI2?tw+imizOH9 z8jV2%@oJlPO54G2bdaWU;MOfF%_h)XgELSO4=tjs%rT-8=SFmf7D5JEevFXW*gFf< zsG{YXCwb+HlQyE1o4`s>!_XHlx%3O9W&Krh8Ix?iKQX_RT)x*Qtp{;m9mI!?z{ASL zLz?EIv3sJ^6%S>S;^Q$q6%R9w?d;@`Ud)>D+T;xKO1#GA9m3*LjZ&O@Q-OwS6qg1q z9-&b}t}Tj3Et3*5VZwLNCpS;IK9SR9a2amzT`;%m6`Q=W|wTw?;A3T{)q}_y<)PivQAE_rTl3#m`e;8a|U~74Kme zgKE7LeqpFlEj4*j*Cgz`jVqMmm$ZFhz4qLzQOx=$SXOEL0ptqLDMPaLrA%Ip)n{oNq0a1xWP-``QnX!4>GtS6wBr&CYo&MI1Wjzm z?pX4b-bKBw8{>QsO_ZLAyUIk##o`JvG46^m(*J4I%dwB0_ zLBe^$^R3~1;D4(VzNKmn@B6f-BH6F!0+7?E!$0BSMWj3V-JyG+j#zrdB%o z-0)Gf6ZbMvRv|QmUPf7X${NHZdqis<4whDDjc9B3P^|DX7{*2Ctws9nW|BWa})#9$TW@O&aEc^ zrT;8C6V6ohp^ET4j zMozwt4V=o%ZhZozq#F;$iG&z^vvT@e#f-xdxH)}!yaH>*Lk4pCJqQN78xI-CDSS^* ziZd6r%IW`upt!@$;G6;Bg_KOl2%b}vA&5^0aPsBhfid~RDO#ckwV)k1&H;b56ty2C zH5R6NhZ5`rE2>yvOf-;(y#EA2M<+`c7O209FfH&X4$|rQ5p2Nc46a979wf{eY91s^ z!*`agoMC$Pkn8*cALSJ5vo8wL7UNjLl7+~_a|`0tC>XnQ)X{l2E{N@%Pj~`heme{} zRz5zyWvTp8xe$gKSAr2biq;9*o0(*bq<>$Gh8mUs3J7wr_NW4{p=QJH9^#3ew?YJ4 z_H5}YGzCh17nFE+bWWr{(_BBaoqqdfBjx-Z9WC;~5`-5wm}zL_L(Q|r(8xy`1;o(EL5+e=8%q9D zqmVcz^0C$u7RN+B(J114M9D)M#hf*;EApw%=Qz`{fIibG+38I5xkf3@f8fH%VU1F) z>`Oy9yE&4IZ**W9k{YEc&9q#pQo4c4{YM^hwpON6?)_25f&oyHW(-<|* zK;^E%2o#xMpikF!qJe(*q5|aqPqt7LfjVD~!}*>W?7p96}I}nTI$>r?#BaFx-x5B!kPr&FBqd7HY&(9(fi| z`jbHvGiFI@Gcr@rm}V`289h8UI0ED}JWx3{41bEsX{hJeR(b(%JL`J^MK#a1!W+{8 zW7HLH5A!qRQ&35EMjsv_@6=BKsqeQ&(exysej53#)^AEE^tB^U!A006_$A|Y?S#0~pDuhuql8n5u9dN0qfBRL6zENj z@G-3U^;X7PKZ}-J=lb#By{)f@3!HX{;*0|tb$6z+gm>E1WFEQ^r>s zRXJlZLwRVXb07U`c(a|8A>^TYX8;}jwa&M|*~^A8sLA=L|6i!tnTbB<@m4r#c|hOj ze5;)-c-cd1oTZEm;mN5T8!)(f5T`NcVQ|X$mN|KdN7|fai&`K~W4;$7v&Y@2oU2Lz zzth6F>9QKbs|Rt@r9Gp{aBgp`I2`}=82D{q4v#{#zo#v;B1j(-Z9ECXC?PArRzXgs$Kf>yleJIAh=-n@-20WFMh5?Wb z6+@k64b|C-;}g@gktDoI3b}B145j1r8uWJ*6B~cdY%ra@lknl@b)Es--59^#8yp*; zWc<124l?v~L5B44sH{Ey{Ii+46g3%t0rjA=80jXY^P@*;%Nyrg6XNigki#1h=@VKr zL--RvJ^-CMSRuI`Bk#ntM?ekQw~+U05eRX9z%s0+A=&y(;XR4J=|7@7#wV=FT7^RY zfw_Fb8Fzt959cKVoyqFcWl4~maMp{$3p@8AmL{yFNpxU(96dEYVcj4oNn2iLO<4b) z)`1UBj7OcyLbJeWdr}x5r4DoaXq$^!u&kAguHid-ARS@eq;OfEi}1g58D_ziSV=`a=}D3A07n z4DQ&&Q)#vH>aDVB;{>bqin1O_tKn_&Mo&qeN@o`?Kz-Y;!L(C0l>Y8ii!bPvjieXa z4q-VH>4LUvMj~0ssD|-uM$f(~I0AZ2_M& z(0os9mw{ooyae2*42;R4yYXiXOmTg=;O;gs?tXIu;PVD1+y_PhzHHve%XDvJw|LVW z+MFeCj>O+GM=KY&9kF(ZzwH~cj@EbYxMIE)f7drg5MB@K3g-JheFcm+!{dM-`1F2l z6}seNR5G2Wrc6rkOI5P0nAFZ&R;)$Wnv|it7LIzmvpYtV$#uIZ`0PMDwcXGSUS+pP zLjRn+NF&=h0}h;QZc1Qp1f$L5#d@@fSvgjDM)-Y1Qh5gTq_;v#q)eI24;(tHAUVZ+ zsmF4znFKUNn}WhyMPd7ts!pdt@NzWRl<8j6p2Tc3_#ra($@KNpF}6(YHjaYq08_hr zR_0-xp4!7$i4#FF2-!ovp9{hK8`4pe{MrnRr&jtkP}sX-{%&gEoA4D2xCUiCPZ|%@ z$mfW-%=rd`NX0^paGn`zQnBb=Wb)x0cRm4B(KPFHqFi~Yp<=NvndctRxc&IW_y_Gk z8-g|qOwS&}!Y^V@r#0q{ii;l`WL?Di}0@4sMls;hhM#_xKyu+W6tj< z0bS;qIgDB^e_FKQ7$^)t6<26pmeZL!uhOUhCLE**cXq<*Oci&qTxq?EZMyX=XAs4= z?=c4Po39mj>CCeoj`tOJ>qc4N41tb{9lFL%tReEGD9Q%yok&Yb{1}^bU1jy#Rs~N~ zMrDrUNBD%!<8prni1X`wnCUo8rt>A84gEV-u7P>-3R0FgvALM?`gig=`S`&=*v_U-U zP41UWGiOQR9>Sc3)--dL6b}1qSZ+-lx(l^ptn_d!YuYf461a}&Gxt*{XuBN?n?Cg% zSUas)zR2p+z%_-H{xinI&3*3YIdpPcsLuml6~DyT(C0x@#WZZ$^m&Mj1x_Xr)UeN^ z+U0m44Zi5}m_8&aMLs;z=W*}G#8W-Ndr~)QmeVu<=qar-%L%swdRlk8TxSN0dq$(~ z&K+34_IYl&RH@LZZw0ic&6zB{DD9M!tv)a6k)_$;hfVtI<(pGH`y8HQW%U-`KGaD+ zGR_oOXM+{A9|O?)gFIkQ1VDWs>8SeS7|IVwBM+K3{uCxp#6$!Jq_0JnE$VaIWk}1_ zN1v_Q50=CC?fcxWk?k~~pZD3u*XHT5$7$wvGc-A&Hb8gk`76d_A^Y5|tC}KruRIiY z=3+qZa}UeHPN*d>-ro!$u@ka7w86v>3&j7az5`JXu!w(bj+nCCCnB)?6JcSra(j*k zJY*KG>m%-Ih_m>o=JB5O5zFRc=uc01v6aowzGTJ^t5s(~cOlj$@h{{F1&mJa=3anb z%7>+?`?`UEU&$gDm35o@0OBBdy-;$;w>}1@xZiW8_{Ipw-4MEO3rtwquSC&(<3|*~ z{^{}~-SO{@Cd+-0^WqN%+HxjG{70qV;0n91b^!M$17mob4dYKr+~@lbHOV(p{XT7z zr9Y8s8)&!1p(gt6!eM}eS;^Td$Ke;K4 zg|e0d0PbJ|mHRj~@J&|5<;E1Bex0=0T{jkRs!tETt2;L0v%@o_a=a#V`B-y&w)j{+ zE-*9$c&<2$Po3#+w>J3r1vdFC@mdT4@%f_MpL0;Tk6~DfFBC)lIfqn7-Ybna`FOJw z*HcQj+X`tYTu&+8a302IW*(b?{2sO-FY@pPpW732ehc2{)8DdPZSr4%?;4}m#666s;{ND;48~J& zbB^V2_PJ$)z(3XG--4&;+8=|r`rO;-eUFa^)_B9I1>*s=KNz{*x5DoCxeqc*Jp3^1 z^#h;o(;p+<>2nXT_pOsim(Sb;*?t%M@)4}Oe0Kln2YjiI0|Bt#y#WJpe3REce#_=? zKxs3Z+FT~}_i!=}X}|&vV)&o(6{9@3=_qWuGqGm^*4BU?0OxaqBtu^s_G&Zrr_ry|d8XDlp-GKLv1t z$(!kR911wm(iIoG>!UJq*FvXkkcF-S%gD=1>fy%gzo^6?>7 z%%h$ya;)25>L7fzkZIUoWGTff>MpP_9Pm#{f!lEY}uaWPJ zyAN^tt2J-6TW%$Lg9mLZ8ya!d(q#8O4`ba{!1!YO7bxL4Ifp%aiEOHJaNCQuVSK51 z4L0ujiUFHj-pe1ruv}*AlS{Moc)Z-e0{20VS1Szc?Ji)SS!rOAJCV_Iih(8W_Z-bu z8#u;&%m;Xyfs@@hrtkO~1FPJXjDRx?obA3u&1V_7Kz|tgR;isYr`dgxv)*m?5L6Z? zrn+Bb0p4!lYP3Vnxgb!8@eiTwQ!_b@+-Yy3d$_=f-_`OSa8Jw=@w<&@!|vBuR>yZ3 zf5hAmI5XU1-V#o6FLD9z6FvH7^KfWP<^m$V2yRAs{{X?}Ar+Izj}h)D3FERIo!d1BzEcS4UV2-fm@&CVg19h{wd zzBIW!coM9`h{|p(PZ0#?VEh6KJHt_h;9TnAs+b#D!FsB|OqbS(ZV+tHGip4ozHylq zocHN$@)FJ-beZ6MT|%Z~7XmF{0Q1skUOrHxE-x3=NI+k_YKEBl5YjlW4s%)IoW`Xz z{sp1DN}0Dtip+aVZy6@(&xOnD`S@Mv%aH$#+@DZcqywm7_%oCgoScay4*9`fcx)+N z8b?a^Hdf9$!46icb)e-B#!zqNKZ8svKOZX>U;ZN)5B>RRK{QH!5|gx+Uhp=vjW6)?2R9LoXV2*NB(tr8`7^rT zrL$S#>)_xSJ*Y6f82xbMjNQ*(2&rc=!OnPgoFq&Yu`%X1t(LiZikm(2E+yofis#UeYMx^g{T|*sD>d^BN}9882&;<-9{1U(qPn z+0YZ{RgDUq3v+<>Y1G}h2}A9S*EH(w{0o!bjMp_PbiT(NJL3(Fikv1&?$>CDGafBH z<4ui9Os9Sm6_4=`y!{^j%YGJv@#gB&6~$zft6rnXMi>~vlKCX|t5_FSU!<;(mYCqa#)2+WSBmB;x1S&Ia;2w-+3wYGz-!ee z;Vy8$L?5l*WKP~~ayO*_-k@$1?h1DvLZo`LIwYD`yO*Z{-mLW5O{?AS5$x4laD8kQer%)-DWKC?dq*di1EoF9?Da_O);MM zpf=pin2QR*Yk+ZJ=3R&0V$Z0R`sSZ01I6!U94PKa_s0!U_{yLEd?5#l&S4G|8&Oiw z%03+t8k=#Q)W%gAXzERh!HWEcO?7?_+DabVsqTF2V>{Iae@G+h$9Af_xYC9xTvMRJY~Yyu;e%JG z^Dq$7*Tb=e)%}=JW`gQM)PQz6FZ6|zPRJD>qRjM9vv!IwW7UN>| zz;*C0N0BV_kLp1;3W_^pI|2>XagII*Cshy8C{v!-tRAX+b(Zw%>f%QvU#|4(>Jlwk zkk*Wd9sZ=Sx~C!XNA8n!Z`6Xm&=q8Lbp=@k?-3#!)S&$}Jej=R zKpFqJeC(;ZNOhNJjJXpr(pC>reiy8`OI1q5_G{0+SbO8m(-GKs$^ zG%u&Y_{O`tfg()~sc?}Pryu7{oH8D zmvDMwXsF&(BPi4PnvQ?rxOji*xOg|Sk#_Yf$GCbQAI!oLfmZs66o%kY8m2?=_v1qF zkFQ10gy5gCmiT3b^~btOAfcOqDKx+*7!Gg>06fa zD;+m&%-V=KUK_Je-TbVYW*ytcKeX`KlXW%OY+n8}P<4KG?PK`ID(MSW_FSxP!qv;v zIso?zM#CvGLStxj|IJ}+wYR2&dj^SnC>pezVM0)@O>mMbC~i#kM)y1 z;1JTz$E`4L6b)L!mc=RR6M+VL&+B)=I?En(7uo^iiIx5v3g~W6sJq7R8$ zhP#-gGtR~!Ztu{@c4Ay~-iz55ys)#29(}OANXDEzG^qWsEj}aWnt<<@B?{UUfbgUy;QM8Xffm}lAFnpg6)FMpsI z{AG!T`2hNkM~6EQtyRj-QXhlnO6+!0d{`5TTxsYWdA}0v?uxHFizIrsyAe~Z-A(-< znkTzcSo2;gd=+iqhYvn7F8Y|475DjE3C6y%iH%QU)X`thTbB>Vpdod$cOP8q6R2fqA00zIM+X z4LHVZrQ7cBn1k%GW}pkZsf>Ve>X0}x=04X0aJ+#@Sx-*@oM0Ao$?!uplJK0zFtDl9Bt=#uG48LjcA#AO3NO@ZYH!=SfziY8E z-!bnVZ}q#~DgUmtwLj+$zsv7?+3y*=&7bv97VrnAsXOBJWq;PY9YFffknn~$NbKnL zM~2ivNIdV^K4?gpLVAl`<)4PsUPuq&8q5CJkTQfcolW|QA+;mPJslVC_91aMULEzj zGg*nx%?r@@C}|0M!eN8)QPKr7fWI(!r{B%OJY|1nUNzn2cMCZLej}Yj_M0V&jz|>Y z`7OWO6Bj1-kEXnRe)sLsz(1*&IB~z%e{+t80 z+ou%x-!jAcbKbYz-B@zjzboEO#Qg}{&19VZ;l1S^a1}0?>_5F1qyugT_5o$~>vsg) z^r^r;vp;@+z-_}I@EiWafvhWNPr!#p;h>Kf?*m!)*+>Ts35^EQ9rS(3kkDu#4d9Fw zHY79}NE{UGR)&N|18E}N9Wf*{+RlLc0K+Wi%N7sq3b<3p0w);@cLy-4aa4+TuawF6 zLqu!P<{*Zz4PaceImI$W&6tRtMS73}M5ae|tvCz8)J;!5n zmdks?c8dAt6lBL^%qX%u`PWjGI|6pLpI0gz>-%t0&+*@dT4MXa${vdWq{*J?Uwu7f z_fpX;Kk6c~ybQ5x{nvoS@nZ$&usQxa1cv3*UAx}@qQIETZ5?~Q|5Je}F86ip1^)jC zjJx9dMgtS>wd25DWMHN{l!HK%fm!Zun!Ln+k>t&Fe_`}C`wLJT4xb}9_?#?`z?wR1 zKrY}iziE5C=$&;0^MbwHP%z^!$f{u%TVW`e@)uwgNe{4u80VrGQ)rya@n6V~u?Q~! zBN#Xy!SZ^nHM+=`$(0p^Pw6BFlhj<`p^*;^7VUw)+#|DOFo5B9XG$n4uKG_`+XCL-oLrt=>{KAU~m&e@LU;6bE z17RINUzq?($x5Mzzc&8CM_*H{UWd38{Mo++x`Or{_#0IZ;%|(9K-r1^`mbCz$68_E zVK?1`0(nA!z1`N!5zCde?433uSYl^gGPrlyT=8Ie;%*%Yc(;Ku_Y;uq9kve26m9!` zEq5`Nux~wJAYRR5^FAnr;#nL$pFAXe2hoAq1}j79UwC}VeVB`rN6dzQZ|$*1O*w_` z$GAOWKW4Z^?)6!KJB`Uh-0~RU<92WKOiZ;Mm(Rx<(azmWG}2wn5$;K&X^guI>lAyJ zt#6V~&<*vJfs@_0Ij22s>$P)*`#PtbXN=-1_xb*SyN#-uZkNe`&l)(}J(UgjoPqW3 zGaUf;7`VXYbGY^k#^ffK8?E+>HUogSQr>0wykvJ3oB8oM##nX?!(eawo&c+&J#ueA zdmaM-_1zcX8`A9YeAdf;B%q(D2y0hA7SQXMuy*cFlQ$*~dOT1pg{8QEYmcl?7-rlZ z!8Y7wV8UHR?o)wLBAhAP>h?2+o29FM02ryg0_<_ivSG4gBm_sl)l7d(3 zz)PP#00Zi*nKyzWuOQ8uwb)`k^eafSYBW;L6PR6R)oSE(wu}I()5!1KgvOXPM7a;%{^1SughgJFGkd z1MIAqP8DxsM}9ESUY*T${s!u-*E9+^SGNW_pb^gAI)5T&gIPaZKqXzN|3}Tjz8|yw zq>*w?Oal6sc`?b^hIQJkpN%EXEr_gHzi0%NJ<&rGHKkudrF>VnX1I=5e7X$TYDVaO zV5c=TEU{`v>VOHStz6z<)r`_8mc{|0W;7cEV~F!1CfAx1*KZ+;TLbFmF1ES{YN|+( ztD~CfI+E~6GNyx?861cab@CKeO|?d0hliQe%;f9dye8%Oel@dn3A3GN5y~|+8Ml&G z?>DQnP@41a{dW_)->|cUSMrk zz=ax~-^$6!1YD%y##T%&DXn1YJxd$U+&6!&G`iK)}u$-mg z=12h6l}&yq~>f*!OCw-#Nmr&HRl`>{kKM(Nw}h|SvOglb!!B}2ZKI+ z1jhS#&A3+)p7OL^&3L^pgL4XUAwPi%xfQ`jL2D-J&JjziUtDL^lI0fL3txV?-`-Yv;3+%&& zozuep!mw|~5Hgxi0Z0}|uAnT@N}`yVg5N3Se}biBCGnlyAh!lTL8arB z|0kn#yr*>hUrHzbrBn_Dv5JyM;bfOdvK!-1-3mM9tMikXM4Pn5e<9urElO#HyYxZz zEy(@>pbl&XWCBt{Da9T#_{!;62;8nz10^`gsN30-24YxOx3gZ`OU#O4)hYzQsJV+5cH*STJmjboP%fa0^>N`p!mQz(u#Q-J}`mx8p6kd1N2Z8TP$#Xy?fN5KqWr5`WJ>;$k)%~} z9Y*{hLdt)MDf?fh>{Bs{2akfW)i92lmfq3@X1uQadqLOLc%9W4#AhDt*TF<}$D$Xs zD$woqIpo-01?(#x!Gr70YOF4s)ZaR#?$>G*$assSp=`|-Johu9L((4#jc>!J=l*)BOzLt?I zjLsrsm0U3hLVwuG|3gc0f5_@u7x$-JXO&8Eddktosbh-M-%8NM`Hv~i78$E(B^KPF zhqcd=x1+ieybm*pKxmEsLY#O9XC{!Eul)Te!;@P>^Tj12XCtEKhvm6F|IiKy*mzgd zwP!(eSTiv@wl(-3Y=i_b=3NQ8?#OxUsqDyke|2O%>Phb{=mxemv=ZJf$fx5F7^9s76a&tW%hRO>zW2&IySt zeSEfT#OORkG626QkAEi~8VTs?!bw86GqHZtY|MhUgM6v5yn)MY(WpK(SdZ!g+%9a>V05FN2 zLS4^7)Jc=MuE4WWRt!INb18C^dvMD4;3>FaDknq=q=-<(EI@VARQwHHx*%#D%(!W4 zB}6@m)M=F`1D*)siuqK55~kfg8i^ltH>TN5_$|WkX_Tm4{)0R#{Xd}TdjBL1eLJu< z?P@mPXF4}?K8)Xfa_;tWe=9xK*lI;j zr`Q;$`ACnNDXmltT*oF$C>Ns&91{dAZQcG3md%ztH+Lho| z4o2dBB<5U1r$cHCq(YM`cK|+5fm@OIjEU=zXdM98nof-t3`@aJHLFuSjl;kejpay8 zrAFIG8IAQ6pvF^}pvHe7VQkEW>}&wFQoZD9e3f#v@lzzk#_o_>3n`HuF>E(C2JP(ny7dORX=V0BzjD1Z{j22@{r8kgcc2 zQ`87(Ecfv7VM&PvTIxbb{kO36#7tPejAD)p%e7E(4N6vP)JY6Wd&SqSZj!hZ4!B-i zRxmEDa*zC1P<{`ca~YKAB%CXF!B#uH2)J)RF(&zyGCO2hZ{3HcmpJPyJvtY(aTpm3 zr2`KKs^b#wVPtujCJhLjiyW2fL0b>zj9YKh%zZ587gc#5@K!Q-5x`uB$@pGXo&~%Y zjEYrAD2(dZ_cM?F#ho0w46R*uGFI%>$@H?b0lP0uRq|8YAa<_O9=x{<}kG~z^!uJxi)?8 z6!FOfVj0#}i&qu`*KsJD38e`RL#G7F?}t}7lwAm>)vyAbgZOnqQRC3*PnV2$fG4Be z^A(M(HWuoaz3UE^S9SL}q!{u%$ z*+WHV2SiC~E2D&yz9{h|jFMp#pptSV@K1~m!+m@aUR@A45!EX9@bN}dBB7-&hSY!S z1D=>EumRYFd2}ntJx#=|bWa0}oh4x5~rtt1j^? z786Im3q~yKww9tUk)n8jnAUcw(Z+%=lY&QrHxBC$jra-K`pGRNUFv5^n?S_k<{x8F z(&zFdCJP#Z-@V{uJ%q&#uVmC=KHKp+Nb~tC=}e&CrC=6Xk6$6AuWu>%4;EYjk}miU7CawN z7yJhcJ`HfR6l^J$tY~{8$5g=YrEHeF0lx-311Qx>k<-C@0ng^e zyh@d4c_tEb6{*r>)pHJUEr<1V!B-N?swgh_KH#c#_@l~{4U-mF<1Fg}6r=)}ir})n zsMIdlyN8X^M`eLk`2lEeAkWmyt$#6Fb*=0Hco=jH_FQOD-wyg~k{ZTrTxk7Hb~Sey z3c)SH4=>7A{sx?y3sxknLUBJLUypHpC=tNb;KDlU)S)o&*dBOx%V3Aaa ze%*~D!1V8C*Wf2T)+#f>-068ng&z!#pZP~yzv6_dKt_{ zaRj|VMo??o+a<_zx6Z>_WW_D(7pQywDKGr*_On0crXXq>u_o9dx7!;4XAeN3>RvxZ zF9ser7e{}n`}{8hze7HEvayok4*0-S;5z(K4~Px_L;T$s;0HzhAH;vd)wFs@aAO+q zblh}M5BuMMJ_|$o>~|u-j|g5$%otaX3f@I5Q^8|0c;h~j3F@6v`F9N4?TWkvq--(|(*FN<2vV z7IK?-Mg1B`^9EIbeWQII{2B1Cr{adq$ZUrSZ&ll3}Q_wP%ogG@klH|0*3Ab zV>Lwe_3ciZ*SDLbMEX z`wbSxboH_AgG}Y8p!Lc?;vFQ$Gx0JKbD4MwiPcOzfW!tSZbxDp6E`671QM1wWG8ec zsPhxM3w6>VuThM{;HMOu&YjWK5TmI2&_0i1=YaMr#a1B^ZI8r4Bsw!ugG4bCQ;?`& zVl)y9m>7fvA5W<4iNtkCSku`k3!u1}%0II2q;lGDC&g&PE{aKXkAz5Xn)-olP3KIV zf?kw`pZdc7l=(QDzrlQ*&_5IPjP3~#siN2sI|scQ=1vz z#zDJ~le-`)92m#kG_E~zi*Y@Xu(io(VeVOC2Lim-xd9cUvSE!oV!H_Bh$P@6Un4An!= zK%9Lx3z%|vh`R6Jcb8EtDds?xQP6%eW6U_D}eR7rngK1 zF9Yj^N*|H`3fP*q7Nw~)T{=tt6~Cx!Sr4?7o+hPt18po{@`UhR$T$pGYmbZe`M`SF z(^~lF0$a83V?a_dpQ6?w81kWIUZE&sk0cO&fl;EcX@> z%S?BU>~dW|EXA*r_1^u&vg@^8cD-H)o-Mnt=Zd~hiJu$~{pYFGuxD}>=8vNzfUi|m ze0)beu13NQa(%iMhHb!4U8+8Z)#V;O{`!;>8?{u=-RP9ZZq-)(wN>khnTyLMDA>C` zozA-wyP#q>)ofA|q2?t2c5X>*Y;}{i<$bUYlYPBf4tBYRkGF*qUu&tIkdkZjR&cXi z;CDenuFX9uV+z|ruFbDS0#(mI$w#3ifq7j0T^*&O&Y(TQ{Je*5ff2?p)L6M6a4++} zfW$$apS!NPVE1PJn^pF+FxSJ!n@fp8EwuQ;kDZs6Sbx4?& zS^y<0sOWZeDU0*)@x@VMwU&Co|Gw$%N{B2ur7|JK zDZt8{iv(5>d!S%1eg~jIk6(KgZ{l4`wp4~(er7?vq7r+MS^5UJQki|sil3>>JD^Kt zz7y>--6yaTs=`mbp;j_KXEQG5Wj5=}1ZT5ROmH@v#RRAOWlV5JyO0UaXg4vz8I7k) zTGP3VnF+;fsQexE0+n+a^E}14jCq#{E@OURg3FjtXC%0c>Bt0^F@;QU88Ze69h`fh zZx6yweWu#K04~FQCdC+>OOcS^gA(fB^35_U_tccTC`mM}q$ry*fRfD}w1nfR%%)#cDw?&0Gjgc4a=>V1~W2)T>e z7$Hw1Araz9nFx800*sJ9|0=E?N}8$Y2j#<*Rqo-I;$+W}5-YUSf14IO5mQ!rm%pY3 zt9Ioylo0Z(jnEOsf^Y!1Z=g86&Xs+9vgJ6H~WjqpbR&zm+K zxYqyuX59U~v{5gYX3K(RF4)$ztO4NnH1{x3@F6UsZUE;$FMDS96tf=(ZR}S=MVL38 zj{=*;m{cPJ6_C4G{4jOfQ{* z^itnuroTogsl~o)ke<%l`&(e$PA)%&`sVLN?^+33cGD?nN$M?Uj;U$7{hWz?sY_nC`p9*^pBVinu3%Mcqse0e$mydPaIgly$xPLkBD#AAZiXWay zX!{BlbCcMaCR-C8tRPsOw(AhL!B%oyW|0_(z>j$swoA!S0-w#9ap}vx+8-MAkhz>pxqv z?qOCuTZSBam|30$Q!gU;sK-(-G4l{wv6pOXTJuDxdD?U>RAWt+Wu4j+L)7bD*LqsI z79SQGBMbIteEihdL%?HSJ^`7Zk>2wru_{bLceb2xc8j!RfS%@KkuV0rQj~p zR%-4vxxw;+kLFc?Sw~myLODBZsCdKo@T&-!X3(~SSW z&N=9t`5-I44S({$ueSp5#Zy3KKs9?Q%fwqq>_9@ETiJ}<+iAvYztL6?w%9tEcLyo3 zLxf6SLjm;6D^MV&ev5>7#uGB8Ci+2ulk5;AOkqc$<0$pKGY@*oJ$QU!6tJ==beC7y zOzNUv)*vB;c|xYJe|UwxD1|NOZhQ)KWWfXK{gMQo`A8UE9g??G9=_*ZJTtI(axvXn~vZ&2b_;zM~~qH?qKi= z{2b79k7+MGW-~D#naPwc!6*LYF2xVXhr1NH(A=;Vy4K@&Cun+6+g>ipKZLNp-LM7R zt@x=dpWJRZ3Xa@v@EG3h1|I2we{!RNMaYeYR#u2+*6th!4L>VI+c$Kwtey~l=naej zatG&Uxr0*%n)KRV6?<(Rp$uQY$rb+D!1LsaUB79mPLfWU3vIpeQvu&{C@lAIOB3ju zypSl=QpYX0j(KE?N+@C)VF!xyuEVVrk8am?kHN*582=>*Vp&VNYGF~HU|ZV;*N`kTx&Dy$F(;5>@ldaI{r@Gj8L z2d(-_*o`SkKY=kSSa}=pKd8o98Lot$DM946tnT=|0`jUA!_iP3@CWx%ZEE=(T2HZ7 zy%X^a{}b6#DAuRM6+Bq&LY3{RHBwsVP{X_hnwCR$o31pp`$fjb!A=J_4c= zN?Gz37wY~&=#cmM%C(Lj_;2;I#n^$JBF~nhygN|ir69wOwuRUSYpNH~RsNH(dGI*j z?@(&hk4e~AYB&uw0pR3c|Bbd`RR9A=!xTQy41?Z+KyjsfR2OpdQI(vkbS#m42c1w69nNsu0P_POH`AlWN4}I38{&1F> z#t-r8dxtjX+!Nk1_3mg*3Um2el}CynBeXT?qGS+e@EsVPV-inAQ8gnPNI?CpNgJ?i zR^Ra)pn$)GgjrP}{6`aT`DD#|j#+|AQ`n&P1NgJuE7r9}mt(c7%KQ(56uKUN?8Ojx z*%RK#w8)-v*>Rr&#m;#D8jLa12TQWdNakBTwHs>{4S*a-@)vK zZTNsl|KDNz-(z((V>P}z^#4CtPd&Dwbf{VKnxZubA!)0}=AknC>fowIJuGo(dNU2{ zTRSvz4sM&|!Hq-kv-wAnyt^K4XpaR9mf;UB8wbtif5Gmxf*#?2zCa8LL#NF|rnW07 z<_m3Ih_TBKG~%Jp(3R*bDuX(GxIr+N|An51Ev;7e>5mIL=4iFDUtipKr%Y%Y#C=+i z9q3#G${OZzg*j*ek{#DTE@0E5(1Ykj{`@qhF&6c=pGM|WvL=nJ?z zm~|CksJIS)F6xD3(qK@-;l6z2HQF#6>3+;hLtZ2*Wbu;yDmuOYGk^gcXn@I4u}%RT z7=Rg1g*Mf}(HHsw(hoz@j-IT>0K|8oEpXZ{NGg5{+~kX22ED%cVY)Vc4gRu{We`n1 z2S6pwf?K;s2A%;*bU#ERgP5d2i&5ps;5_KV>&}*+mR$svcm&_1nt|4{Ba?WCDt;Ey zI6jvOmf{PEjZYTTL+^W$^yHyH1Zf(SMmX^-(39gI<8Mm5H~yx^hoNq1@h|Z=J-!!|czilaY#l#)4pw*Z zpWx-TR_jaA>UQLuI-0l;MOyJAFi6G6qX1w0WCm3HRupW*BfZWLKFF`1}6a_`@V9U^Bud))`G_s>xAQ#!LQ8+paWk&91 zCcIs$z4;!1iLa#3;g{UVy+4E0rg?6&6}gW_FcR8c1`~24G1bS$<;@sah%W$g)&Mh+ zIvcQ!f#Jj!h(_9rB;T!R5_8GT z#v>}ap#7{`cT-R-kpX{228bkHxlJ_Cj3G*ga#4aY6)9B*0?b>KI6zfn)L}rJv|=Z2 zMqTmsJxb#>Q#+#xufj&AsBeY8*-p%%@(M*?;1CfzF_BKLRC%Z~-WIhJ_p`KV1|P8# zd35v)^@rsD$xd`_0B)52f`fwsiSFp)k)>*gmUt;jVKw=>6y+VB~@`nP62Z^sT{KJ7nD$Bpw;I9LT4Re8SG5AOz@c~<9s~REY z{}izNYXvtWzCoR&KLPB zVu|sz{4}4KlXFch@iz6HZt(T7goWM~S!3|#SYjnTd#2I9C6<^-eP{V-s6S_GEU}4! zvDSCC;2p8VYT9$Qk-tBNI`Nsuwj~e?M|%3=up_~+jP#N;BmNWCu(xEvE8NJzSZ@10 zI%{TRq;E8HWV5S{@=ZXRIqsl>(Y`4HZ7ca5urZWV)PESo(OKeCpXH}AdP}gf{254} z<6(?JJE04CNoudI!{5wC)CE>tjCANfsBSF24usHkh=EvZlw^g*pf)jnKEMi1VKTvF z(yg#KCAPgs7^BE0xHWd?Q&0hWqbJS-x@)r_J9;Wy9J^cd!qE?B1MPqjkc>rVAh2Wi zXp|Jaheh7IP4YRI{aDt0d>p$&L9CNHfPxbLp-8qeB_(dA?i>T{#5$N8%QY~Z_%|$! z3w#5M#%tc!t}iNBHC)xfO8I@Yk8fw`8u zk*d3^BAA%edOp%gneAJ_FYGu;9Y#oPt!PJ-nB-22vF>)X5I#%lcu;s@t7GwO>@+Ip zOR}S%L(=*Bs<`$i$2sRaJ`-FzY_WJp@iskl;`|53#IWS+2}wx);Y?v+W7IjXfGJ&{Ju-z1{J*)es=yCB6&Be zj77~j)j@5|?nO>CeIJ~KRBqY@R&95DELmB=R!Dy@98N}P&TcS1^Q-=Y$~R0Bs1 zf2&G70B1Wf!{4qFN2ou^=-Z(ZiuqFvzF#E@XkDtw|FB9F(O+pM|4x-S%JSP7{w|ex zfu3k<_`6l2f%y|g-yW4X2d(L}H+Zi~tf8wi)obF7eJasNzjjo=DAs?!O7J7wPPSr4 z!f=e|KA1nx;P+MHN$M{!`VOkZ-Q;`tkVH1Aem z+Uw!%zQosTkCEyV(Z9o&xRtSTqWVto{k}vF{XO2)_hDb+4(6X^^zHN|KBNEYWuEru z?D8d+vVQZG9z^%}60O;u3l-Ob{6=C1PwR7*s?(&t`+SMHUE=P%*n~a82=oI`jA&_IYcSZ zWavmP87e5=W_i7pTsl@jB60vra_IC68dgkP{TMvfhR3lSgU-&Qr?D zieX4f9;FF5PAMzv0_q;E2{=J9D{C3Nn|z`s-~`1iROC>Y)nOHquA7OOBxzzbtMdhv zCzY*~vaM(tqB?2Pb%JcGllmQ2keA6iWioRnTNH|zS@S7<44~QIrEx@+PzHiuPs&uGdSaaI`&wEBOXC1rBeBPGfCv ztj9>f&x;3aYEIg~VLEvc{Tuy(;!V}!T`S7kCNHiNWJeQ-%j6~9kp-%dIS6|4Lbx0g z*a)QCE9R5>fIA84fZZ3;9q&dp&JQP_yaS}@W}3H*NzP3-vw@bcL7h1Yw&7ib#=Seb;V_I#)b*uww6)oi_7{dQkpb%{vNm!1jTt%^+KXGgHjSwNrbS zf|SP>XH)xd9L-yfgDq0~F4R;c`@MyvmGlc5Gn`sPdUWMn=pH!4n0hB#B6ScOOs}f= zd}5GVlkP<&5~;(epv~gC)mCbW$nX&rR=cC-$)Nt3Mv z_LYg0?5KIM=x(A;8l^<*P-0s4ZBo0qG(=jS<|U*SY55vuMz_s|WLJ%{qR+$bv>x2I z#Q|W^(d6}FhsOnRG=g57)>}(YoYJPott}Hm&Z@ zwWBX*hy+a9Kpik8vNe%5NRJF7qu;WGnk>;d0hg*sIQWT^&>ym34!SZ)0sC{f&)*-( z-p5FsqB}cDNmsDx(;6C(j&4PFN}KnCRK$wTMXaaI*QVRpQAuyjsiRGumEM+@9Pqmp zx*XL@PcU;*23jXK9!bF}Df$g+7EfZ5tZ&_&lDTDLNC;r_plpxJH@L>tT4jwMJQ}H5awXLD&XA@J3Bi00Lnr zhs(QYR|JcbmuG6pwWO1;9c}BOs2Wn@%)wUDVmKko>9dm=H^UyMFJ}?fiqnSE?|m>h z({b8x3Kiy3MshmZ+3BAU6px+*7dr!b3Q9!Jghr>RL{KJr?(Z;!OUq38!*y!Q1OsZo zX3<)T+K-W<&E7QgF@)MH7MLj-$V1)`2zqQ_>B0ilMY_GB1s7@Hmh2GBK3z3%T z#u=)o8+31MXE?+33OhHtn-wV5Q+z?2#aOhK@T~{VM9CxJTlkzhTK^lKwVhA6K8=5h zwJ1Kx1V><(1x?P?#baOuv!#yDG07H5j!`6FzXU?S=0#BQhiE!bJ^&>-RR``D!j1ay zsQrAjLTl;yI5K1nG^Dr2^Ve2>C0d}(;xGW{WuSKxdO|MIh-BGQ+6 zl`41*(HUvw=jA3c(xj!3k!Z*=9jqXX3~lf8ouPG1$A1NDQK!Td#SsD7hM+%e0vUGv zjU!BxJanqS9X0;z`+U zjA>o1E-#?M?b@^kCE%Y+sh=R#kN`>ar-Ez~`vc6?8$ z2YsG~w@A(UUZ@YWP!EyXDb$uVzOaS*4kEB!b_b!>worc|HK(6Y3tOoEdQfx63YGh( z+TK)B^J<0qAsSSu(kd%JlOQOtx^$#e{<$Lc0HydyWtSeLcHSh^4K37_q!!#GRPHZp z*>$9Ld0wa-+BNl3QoDX2)YKO0O{8}FQK*Lzlp-rOg>mahY|6H}3_|B=*P|UM0spg< z`V|?D>mtYX3$HVbMh2z+U!B1V`xRRH{|@`(V!dlOwoZsw5a#_m>oxQWY^9)Q`P6@$ zBowJoKiq@B6G6)wS2ZkK-fQLZIlbmK)h%Cc^}=ybz3P_DU4TD}do?bZ+qAO2p;z7V z#nv(D9`hTPG%RbJ+Y3h|Ep1-j!fI+Z~F2%EflEtRJPDo zEUTN_(5qop!;%%ttrmlto9b5dSh~2bxy3Y6ENgE4+#a|?-V;yXSk{UK%NpwHYa5r$ zTiSC0s%|Y=x}-GHwqo!hW{`O;;E)7-eE zY3bZWx~STf&01>tab!)?73|Tpbjf@WVD2e(o*j!9x0nhen(OA9au+W?ZRrwY(2}L~ z4U6lRFVe~uuUyfvS|^vCf=?Fp@JiIQxy>v8lKnr#y$zh*)m8WVpE;8u0c^3QHLanY z7St3nFL{At#ixWMkYpy4VP+Ci8}DIW&di+V%nRqtWF`8Og=B8(d+&OyPaAi+%Ay#HCCK=((xThGY#*v#Es}=bxdpKA)30?+tk*_>`iig7X z)KNk%4LhOp)73rK&6VatH97ZD^hq8vkIhj;Wwcz=jNr9WC3KH>`pi&uXwqZAp`i*+ z&>|lY5N~d1MA$|I9wNZ}z2%Y8?9gx=GQK*;y<2nDIJU#}PM(~c^B2K}&M>cSVU-`cVEV7o$^l}mG{{+YMiTwN{Ag@mu-Xn>)&cp15%sg%HNWp>)%>fOYINVt9k`z~ z_t#ptwk$3D*POy{IkUsvg?;k=)S35aT#~-`QD_}gXzMopw;{0(Z|BuJ_uj&L-&l6f zcz1hYox0$w*3}xL1#NkJE_1nhTBiKt2eaErr4}j7?MFu6kH!`x<}Y z$@s$2dL%FWrM>XMJglql(0EUGVQy>T?2f`e-q6vpx@)uQeWm_gtbd>ESq+Z#Tx89$ z29^|TZQ4>UeChfQ)qPAI@;bSO-9-amu~q&)`K_%z?jmN!Vs^{Fa_gbOI}2Mo)~vp0 z^@W|?-PWT$Dk1N>=Jprq(Fu^I@bD7L?A`Oq?ORK?uG!W-e&|-Psip8=d(}G!mu+p(s*ySuY%RpA%sKh;rK)=^mKxP-yIxbX6&ZPY=t z8vWn0fSGX4)k;-52w{`)2&=Fi4w5Xtz(7PY%Pp;tiHH#PDi0k(bspZ!$}E+)%tgl{%z|V zZ||hr3TJf`<~sC$qN8vg$bNlC;mobwzht#KqFSlfnw0YUKK0P{@n2fHckP=xKh(LV zdrf=ic;W0%S;E4uj>1J-DM z`&HXt1Siid{LS8u!X+Jr+C79k+0t z7vH+>O%SzJ>-sv^c&#mo&5p6wTU*X5+_mthg`)cAy-RP|(>29-bWe=aAQirL)x~Q7 zdM@sJ(^{teE%P?jPc8*XNqR|FH-Yb*AJhE*ucaOBU4?4L>Pvb$d+Fs9&8p>xZtPft z=PS?wdB&*mk?VyMf4yYur^gxi(XQ^o^U$2b&07oKxUu8ts;=HuUB56~IMRF%U9yf+ zKoh1%N8y}LJ-MpuO@){JDd889&)1Cv{4~@dx__ayqcFb}Bw9_8_gIlnfi{r2Z0qXI zi#k_d)Ya8pW*Gm-u;lM<)a>~A=8nSc;7(J4*?^TzM`uraS3BOfcNC^Nm_p-)NkzPK zLEZF$rMHaVI!?!Z%&`57OUK$fyAHMYbZzeG+&TnR(8CJ41ZjCUyv4m;c9|M6#P1-J?@I!=XP{X$n&ghRJc<`pN!WWvhcG82N-lyjM(ULKt`N{pw zmo{}OD_f;#;)R{7+si$jjPUF|h41Mo^mjnuL;OSEyl}0??v-oaqFz65Qcxa zNrM-2IoJsmeH;|9rQkkW3bZ74Zr6%(^d`0BubMhUYkxnc`mLC%<&4(C=RuPiGwypj zx=H$p=B=cBIHvq$Oxe1o+e$hXV~*!Bo!#RHCweICeK+0`SEz%9j&~9A9uFbkpD1YA z``7*SN>kxIc$y0ziCO(|o>gy8C#k-5qbhxSb4Rx(!iUJCUcbMz`h6h2`d9g@T_pX* z8=1vZhT2t%ZLwI`{sjt%WUP@TA?Vdl-}MuC7&`6NQiMzvbNSafoLJd_d3m`1r(l zPr2}4Fa`|UGPOap;34?V!Y6OIXU&nq=UTQx^}02y58ezk}YAHQL&z3|zVF~aYN z;m@{cgdO8rT1AUm`U}t9&~ebv?r>z2pUFB3*WY4GtQJ~$abe}{G5R_9!Ir|;ns1@^ zK4QfCt48EMa^qH|yCtUkSF$ENm^jYHMfVUzOW`c_ z(Au6)caM*EcM1DecZ<0kgUzRRo14)#MUmtFvzxlc+k4t!HJr`qTt$}p9VENe6WuiL zU#}M-KD^`>LRa@TzdCvSOT69=x76O;N~msyYR-OD{}(H@%5|kxu2uTZYAx4YovIMa z5={=Jy{P&IwNeoOa7CR*s(d*m7>SIqM&%171mz1+K^=rESGV9!)Ghd2aK}*#nh&Lp ziWA&*Er>j>1<8{{F`s}$dxb9w{ZuE<47u@ivM8zRIvqSNm?|`=%XmD~ zmcCc#9%6Wf@SY?*&x`O!Eu6e=Yvx+Qmb{z;G;$sBR!)dpVWn_&4{f^F-dq0OrrVp} zRk*F?)+L8p^LKaA#8ofy?jaO~8{@n0YQC*-Ys;Y}2V2<`_n)pY^tv|Y9owR9k(Ks- zV;glbU>Y9VIGTso`zw~EtM%@TbxGP0(b^`wfpqWvG}(4HpRBw()!Lb z4lK?4LRYAb*6Z8zGG4wQyst~icAu#}zTmx0KhgZ2!n<2;U-GWj+s?Rk>7ivkFVnGq z`?b;d1GsD~4mH2CaG*X;M~T}N<8JY|*jKt)MSb1#GViN4-1_MbmBAL}N4?+E{O-c- zE$>=#TkEZ799o*=j82g+kalBuH|D7W-6@W>DMNlbuDv4mh2zV?C7~~3dv%<90leDy zvXv_L_QJbbZd-C|>!CAlS^Cap2hPlKUI${;_Sk-%ex1Re;$j2^T z=6d`#@NS0P;=IG2mw&=Vb%3N=A_9J?%jP)U_jQW<$?cvO(! zF?Z($DSkf>1>Fa@-<=Nt9&~3ca~AJiJXWS0zu@r#$}}lc-iLTprr-hQ4eom96Ly@3 zG6i(PgIupY5{r72fX6*vK(8mcEA}$WvFnK7ghlrW%$RehfaZTwwlik=6fbG|CPAv@ zah?~e#Yy5`u=oLiGkE)yVbne8Dy=2c<<+sU7%KFMVSS{U<^d^UP(9h|Jek_cimL81 zs3kD%I>kR>+4QX-s*Q*G#~dFCv8~z6vsvr;OO^5~Jk6Y-6jW|W58NJ-)A`R@t{%T5 zW_LKmhwRQtvOA}qU5@uLd2=?iE+%ct`c=>Kt>AoaKS0Kh^3WMEVIiA4r!^*RHZtnf zc!qQ*Ep5NR_mLCLiB+_#-}PEkmRDQ%yuZX7if-YJLN9KYddV*Z)} z$9OaW1;u0HUY^FEuvhw?4bcg0dYT{wYv!K>F6C|NbT;5zcM2@$DP((ZJ|c$-NUE*! zm46F!a@i5Nl%SEme3xmsK|aX`Uu=tV-p!-73W{e=iH+i~I&dqbMANw za1JjgI5k7iev9oBP}WI5oh0ZCf7^((P5NpN)~-c_E5z?;pPFXBpkIgffvP;y{e1I1s(lhmLdl-Hmh z)UU+KB&k6k-a*epplHs#21-1^qZ$ZG+Qgl6TZ*6NNor6J%4<*$>Q`cAlAz8k-UZJ? zz+>};U*5w!s)1k|@+|J0W-9)E9%>+<=%jTg2zu6HcRU9;=}v(cc;E|eJ|c&|l~0uW z2vTN-Fmn8cd1g;8mBSO~*d^};UMYjR%RQ~2;#XO%`UDi6G+tNCU+%F2D=ju}`~`SB zEvQex-_2uRI_JY=_W>UG9Vm_e?!x~O4ecWwne1&j2_@NM;bnvwV zDcIONIUY98?6c;$fV`5%PK3lTahJukRPQpq^B7M;adpG|zgbY9K#OH`O{~-X1StcU z$ID|hu$Bo%2aK_zB1s`#DK4wZ=;bF`K6rGM4 z-a9NPpP_nT)`D{WQbBiH(15@vc$%~KT^k#J4F5wGol6KR%9G8;R95t(_Uet9;1lk? zKu{{7LU!Ym4T(<>LA3=g{a!hDTn5ms=Y{P0Yme;5afpZT!vJNGAeb8Zyk&6pW$2^^ zcu*r;3;2jTV^K=@06|(wjsusUrIfq60Nk7-r|xdw?@odH+<8Bst`MVk zc#Q`I&b4X|ssPpWD=S!cMhGxk_QIhIq* z3NK2)OWjp3wJ$04Bt% zj0bLxonbLC>olK@yjtX8-9p^+UyLtg%f4;YuZIK-wSbDkDKJ4n2?E?nkk8v6(`5ZO zp5|;JXDyWJQp4}-&Jh$;z| zb17Sk4J2t5po>Qsav4xx;Yik+*o%r*(?nL}j^ssh*$KkbR)q^{>=Z621XQ@7W8A>K zICTaUwL)xsD&6UO9LIQ2@5Jat)1#NwdxdQ2<3}Ryng&2hun2C2!z6%^Tlk8O_<7^AhBa`OAHp-2a>PxtuvUXw$P_;0O;&0DeNVP)_y~pYhwK&ZSh4-{uzrs9eL8BW}VAX^AVk&*V z#NXVPBSQ>J-drHreLTrbRghAqeGzkwaf{m)!yDQb1JkxC><%k$w}8q?+cq1*k{Z^7 z`eH3cNmb!#%66wg$}D-&KA2*7m#?Y{3T(ST&bG%~HWR3?6*Z8e#|SvV15u9Y9>x12 zvnnRZU=MWkHtAReiBm{;-59jEKNT(pgZ_Lv&ryLbJXAy=VL-a_G=%>*Di*SSDu3;9 z-dj|)dQi?Jif6olN3yu!QFqhr{!{!)o}{M~q;sdNwP~td7Sw+&;Qi*@eHY+v4^0zJ zSkQn#g{PIx#M$f(N93NhsQ&tk1Mx-G;ef^V)noI))5p9Pc+d$PI#Uj>L4SPvC_(q~ zsFi{z-JQ2m@%Qs2tyItn3%Xk1DRcHe2YB8?W8Ql2e_2ppJvOh|v&1Mk$ytTByvi#h zD7ykGhFI@E#oPJUtnUJ%eu$?fs~xW^x?doHLJL`Ke@MeW?3XPU2ncMxl*h2f-d>J)LlLGu)ze@g>a^8QIa$ozl`S60hT-r2^mOV8tSp%i<#S-5eogT8$WXN;PIlXrI%` z1_T;VBo?AHi!*#Igt616&l`nb3{8;waT5ML4-@im&UGqKIfl3CGd05ZDD?>veKZ6q zN1z2*LgVLHd^D~%eTW_T@rCv$nf9?FCAZc9);X2uN(`84@&O^N$MwrS}x z?3CslBe8w@hp+J9d}(47tE89Imb8RN345tU;5#i6ae^B{vON-h-(}nNiJ*-<$;zC6 zHK@J;7=spbb1@uTyd&rQ&n3HEJc05cIQuV#llX;vnU8_!Nn*O}oR9%zEPr`7Vf%TK zi4cPpS1N`#R4N88u2c+fs8kG0D^(AxS4y8N@~NLMfc2oAu|1mi-{zr++y4&{mlJtK zcg0%OgYvngpit2R|A#7i4wGc@M2TUiOvU*1BvvPVYN>$@h|N@*#Tm{JW*79f+&)Q+Yha!(~EFSnd?i9{LAc%2Q(c$fOGjP+Oig1yowuwsSfc>zG* z$07UM0s0gYPJQ9%5qGAq-)yg6Euh?!Rr)YNck?u7wH85-9!y`>=aA6W{^JojRHP(+ z!CA|yPhh_}cL=C9Nu}&f)lO9lHGBeRsx~-GTkhvknBYS^;In`}b%bzp^AS0o_V8x_ zC*3KaZx>k-Iohn0Tvk+-RiWl={Sj5bOJ1L|K{38nrqj(?o+kQZKOCZ*yS+$(ZnA=s z-I)`J{RFC7;Fv&&Ka|JoeFZjUT<_w);{>Tu30l^Jb}vpvX?1c`PuKSXIjG&I&3Jb` zHplaNP+pUI&?%`J$o2o5VlSYM!j9%_d*1mmtTnqwocV#+X5p67vZyDvr!h1|oZY0l zfd^z+{Bp`=yg-r+Gj~x4L7BYc&SieZZzhbP5KuIj8go=^j|E*V;Ia7(=_6>j#r6q! zY)%#Ao#9c*g8SRd&42$X{y`o}9wo5Cli-75KVh*~3+Ux!Poy5(uh{1-;Z6Z%g$!HI zv0oYc>v`1{NT{NX;3?^Zy)`JHUMSm!;if2hS-}Khk z9+9)ly&2whI8|zhmD4-(ntG|%#F{Esy`Q!==0{krR#v8JQJO9`Ee(rpOv7TaX;>_O zDS4_nLiJcvx#K(O6o_ea{vp1Q2gJAXfLP4A6k(s<$_4~fVqMXIM;{5!1MbE1=``SZ zJZH5fDK5pcJq<|9`R_L8a&lD*(k8~RQyS1i!Xi&XB^0#y{R&}1-tUNQvm|t^*bzG| znHMpebi}^fkySOitSWs1yS!Fe_#LJE<2-7-a#mf^j)?JjN5n*VK+NfWa(RG?iSmG0Qv7U~#)%9YuqI9OQl%+Q7N5yjufwYzIHkN8 zk=FKd5^nVO1x|~oN}~+Z_x9sIU|}~Je9qnZ5~KJ#c%beAicWCmP#!xNV_A7yj%49? znE1PSc>6fuad&3n_tJSkNaBZi&dBEO-<#TcEsB`QOH<{Z=h31is8d|&a;f;Gge5E0 z$q>Y%@vOz^9hRUh{9Xw0;lRbYdi^ZRcJH}@o;+Vv<5$BNMSVQ%tvoq}iCOBE!#t{` zpw5xurXc?*{%#&>DWK?N#dwOKr+KtuJO|7ydPfW3Y)2+eDaSewkNMxlTgsRw zpIj=(5%XZDDTf!Aw_n~K9#vLQhuUx>Yx+;|*YZ%=3SiotR|_a*(veCy;jsdqFc&2T z3DWzvcE^kg*>!g}*R#qySvjBJQJn;zcXzIpQ2f(8$uK_^f-HZ<>7Ark)flmI%2IG? zlezO*aFnq7dB{@Wm^t%Kx)1N8Jm@l1$sSEaAlm5WIuYY(&(oQ-wrGmYnNt| z=9s%QyV*llUy{AggK+(_hw-_j-}W$E$35(lb=j9Z4A;}R$l~h)y!I_%jifE~oW8a6 za$t>QuazJ81AFV$X2-j;^Vlt&5DQMx=?t$e+b zO*e#v!0XdMU2I0eThp)+zY{P!oCewrXr$EXxx5%lX{GBJULHJG9$mYJw4X==$3x&} z)4;VBj?B?fa}a59cM`o?i~;(rR) zSg7aEu3;u{kj_MqDI*lc{~qajGQLuOyVGg6(K8kq=rY(Ue> zZH~3l_$0T%QITE(IJsXOndail1#%hMTgv`}z~t`9?EA6X7%dIYjdPo3Z7S1^?CvFx z>b`6|_v=o+>p)3w@U1|0+ z_;jbHy;LmEmL{`Hu}t7wOhxrrR>ouT^9*lwa;Unemc5s-nNqc=VbtB6wd`*ehj5Sm zf5kVeC3>w44uB!q7U-kpr>{MY1yA5blV`ZmYZL0)0WRehFwMg>!Xe&ii%;S`uA|ShTA@ zGkwa^TsFsQ*_ZKOr)%}sA<>OGI)3d9(OI0PUxw^5$n2gUpz1@j6WKp95k(4WGkl%y z%Y^Q+p7_}x6q3wV%fnnUxRFGSr2QKZqmpu_#qsA%V_p7 z1>&|FKeAU|7<_Yffo-ugwKuy_VSHtv7{Zj*xZcv22VQ-V5S^Pz?JCk@b$Xh0z{2K> z`3lsg`Ga!RaJat3J1;LgKjGI4$U-Ke{L~8@ycWlP>V}dqcBMWVW(lz)xOD zmrc)4#i9D9{B&Qj>b+A!5cQDk*3CGm`aJhF(~-X@uTomZ$sGA-A}nljXbM77P3!i= z7RVWcX7Sd*@7ro2>yn`VYg3YQb|(qOhHCqur2(CGy%Fr06S49|Z_hTRPw>aCYtBAx z!4+<%RdpZU5Hd|_`aiA+-H=xCkGo^;Ny>j$CDd4^F67i_<{u71MnvJigablQ5?THW z+_NKNl_9MVC-LkF*Y0L>J6Ii9`e3=TPvQ3Pg>2nUC4!b@JEMzNhj2SDWi<0kcy%9d zF)S+IjQ-FktI$e~mMTO0sD#pGUs+G(818HbF}k5QY0XdkxCi+SMOpKZd+iQi($%u# z!%0Z?Pr=6*VaA}z?;P<+ytWemb@1!P+_aP*9rbhy&tCO5_k`-+1YT{bjKTe_2aU6L z=ibdjm9gy3+`D~jEIX3>u9>cmX1|J;n~Hd~wr?^!Yb<6ofbZjV-vrry7O&k)!~!x~ z9Gl9vjK=^z%A$a;lOoV7OPKu}DfWbSAmdZxnLc3^LWZia6 z6?4Q|P#!CfWG@gJa;1*L@S7KxEgb?yvA#UCy(15dq<^L!8<;?}&q_77vU6*&D*N--a)agm~a}`eu_cm4@Pbf|H`bm$m`^?8g zXOh<*43VX&(V1ydq;YSV@)w~`r5V`5$(c0v{UNrVE!V|QkEBUnGu=>sn_XG=qCn$L ze~Q5Te(3DiQy&BLN&MAeU+wVi`)0*!RFR16did8YgqFEkkd(o?)t#C(E`^( z?A151w30%E!QcH`UQyiaLiS5U(v2FLh$r7Bh~;@Cm#g-oDp2jpM%uIEc&&Z`KeGQ& zfPZqpD;OfG*(C=ocdjUpnNKn#b2X44;92iMQs@qUx<#K~__sr%Q?L&6C2BRBoqubL zhiY&aeRjodF#y6H!oGG!s8PuDdvCYdg+Lh*Zuz?`B;d|L;?)AK-jDS-Ne}~P_o8Q$ z@1}oj*lnEe#XB=ugm12CYCYWG1+hLyfTVfSXdT*p2VUGht?rc1BMm2?4t^0|6C|D` zV0aE`I_JRu$4`2Qu~xtLUVERb<-~%luX=xmsdG;g0OaEqX{XiZ?XJ#vZ zA$a#ql}BsYpnFHFdyDf`-aHVat)sK1Ukr7qP17+WdqA9IQRxn`LuebOtJz(_8w5M4 zpdM0CbvUaY@qB9IkO?GkjHl&{wUJ$~n6y3AXF^tNVi-ASds7@c$3KX`&nKiz9mS2D6%L)NA3 zW5&vbe&}vo3i*g2{*PHqSk!~I=#exmh$&xe2n&Hv5g6Y2XPhDQKjjQ=DP~HR?ok<<+UWjb{n1D?m&pXC(FUr@AsrDml>zpX{I! z{<=!zC-E&(Y3S?Zxk^KyDq5`4&{wt_RT}y@b3+K?vOYy^Z#Jkj^nqpzl}bZj4wff- zrqvyi*k22!RG_ivx@aR+X&fao;cxZfUiTV*tMBZ(SN!eo=04+ZAH!ScZ`+r~q~dS& zO*DUTK>Y2~cEQ7LMXG&4NAv7THUECbF(s(3cU-muMFBg~Y|01)T~s&4NAv z*uYQg8-N}V_-TDKv4Njne+~f+{Ios>*uYQg^LB}HMjzfvl{5Nao%0o_pK+hcZol!B zd7**b*4N*hYfgyrmFMPxu|M<~;gHUk7=7!=1DGuA?(=|n{J?@Iz&r>|QNGJYQFx}dCF5p?o6Mq|VZ|3RY(cLofcZfN42am2L(KRIT*TQfw z z7YkRKhj@4=N@CY&h8!O(Md+7iNB4wdwBYI29xmP zB42e`~=UFJTeH5KPi<@7aqf&A^y4W&eO?z%0vDbAM<nAWyW&i{Z}__8d>N=!@a9otxo_rkXKa7EIBOYu)Q(DEYofxNKYc z+L*^YGd#O_MtS1zJH?+v+H-l9^R)4#zn7w`F4hDQr8F~NWlw`eVQRe1{=v?QjbeLr zXb#>tO7)rZfRZ;+Te&{jcY-6s2?MzLk~KdJ&x7uIWQcFO6-|)1s&_}*hPHJb7k8}5 z%0+l|TjWs!NFjg{9mQ{HN}s11&4wy0PQ|gIa)r`!_r+O_EjUE6y^~4krLa3lxl?dt zMZOO=HEp6(%@n*;T@rk4j(t{C+MYQjN~7>#^ z~YOCFva|m60hM=!;}0 zwpJcyq{p+VYH_kW9`}!idlMPL@|h~l3n{==At49_D53B!j*XsPy{?udGSBc9>8qrh z>jN#PM^HAFr-w#RPfe8ct*)X3Q0tS$N|n*;%3qe$$z_-A|#l3jn z+!9W#-!Qmk=ceNN-tE1nRj%ud>3T_JAjGWD0z4KhqwlDJ=*wG{P!o!MA;;OjT0LCS1?qv(R&mrV{p^vv_0R z-Y6{{9xZD-qcSN)gPBmc{;3A@%|29Vq=?dVbZ!z1W;17cN)`ydOIb5zeI0Ff^se7A zxOr3W;Fb+SIFq0VIm8p25CkZ&@f(BJbg1S^M=~eCYXP z_pDJ{$hRmRZBq^2ESp&s(Hgc^G>|oPQhaVs$}3YZ8Tn#PT+_d0aMKmc@8aO5ZG9P= zUfPJEGYkadhq%W>O{b=7l~QR&qdHeXN7`?bskm`V|KQuOGpJ2!9ye|+l@?~oBri^} zl?Uy#FI=9gAfaxUNKE)XUE-MPMhi%}Zu`qAmhA?Relqq>v_k#N(UD|)umih=D{ z4sPkc8fsKmbD;>GIYr1@EYdVu7Wnc)Vc--?06Tf~$s9Uo5G7SO)lgufJo4oykf-8w zh0l@l#YLtXJyrHtA0kKth&(O@v?-nA-XfH7)JRsMgq)iaA+hay6nNIJCW+g~3^P#L zxSv3gm(_+ezqD9Xv!bn8RkVG+lc=pi%sbd7pzo3$dSrd}PIw_GcTm$xPYc~OksC~> z{_NX=MXFd$f~58-eFrKhU|@=)mxz#Ol`3zrsF@h5O}Mswf^B<-VuqQo)KQUDq_2kO z_@1SfLB8oY6O=$M^UWBQn4X&z;SDNA? z*E(cNO8ujinMBkoi;o&AU3ZO@%+>=-sP9)!PfcOclad;=K+Mq6Uahb5HAZnB6)S64 ziG`E#koJO=-pqIG)3gnHsUwp^3mO{RDWJ+=uKK?=%`OmhZEAK;R-J?fYH{@i)G{r~ z5GPC{y2x#8hDEi8P+S=)FBa99{ByW&ZRBbfzA93kHFh9$KGRvM7u3o_^Yo0ZT84aM zFd??xj;-6!LRQylYq*p@H5@Z`Xr?NyYox@c$T76knyn7D2_Y1ptSdAFqN!cw5qnv7 zYmkfLaEY&OBJmrY&e$H(aGMe?ZqzKW51^HT*<{PB71n@6k%6Q8ui3V~zq`0?OK+6q zqi|0RWQ?TGtk{YKBQ;f-G*V}K*q}TbN?$XQ{4jJ9*2gt$7!{?o{h|Y=bq0~0Nu*;< zBe;(e=1Wzr4^z|ZL}fvp!WK0h$M^?49+}!ZQk&15BF;kI_!x1C6wFxTjG`7>nCK10w5wrxe zwqrMZCB#tsIs+`S_^Ry>O?LiUNOj%lg<&)140UGik2`91{jVg!;tW`cf^-+FdMMp0$F5720plO zp|6XH%@Rk68SGfmcBWa-jWUnT@fB=YAwi%;@=Wj?#SUsuLKP7A(K?9UxfrIk+-A;L zKoDe7XMmBkP3ys~>6qB@iG1f;^>tu66Z>4V!TNwHZ@%{%R2EvXtte))HuIe; zb>i;W6}T%~!g`Cn+xxez?hm3&-r|P79VS|_5;%f8_4W$Ml*_FVz-w(pizd9 zKz00s-(v79r7;Np&^YElV>Ls~-nq#wQ8s7l%R1NIEKiM=7K-{T`>A`+F1uQ?aqCC@ zgW`;2!?7-PQ*N8*E=VKF4}*`a8RExSKxOz17FDOOXIMcdZ?{M-0~hR-B}RkC(V)*5 zKp%5kXXb~h&|V1tuqxrwsU|CHRDEY=dgf;@|R9yImuEX(b|MX zNwsrRG8}f~L0FaX+^9D3#G z`&5m&I6N|nJ|IKtsDhC`+oo72=sbp7OE+VRw85Yl+S=HU%uRs!Bo5&4Xipof-G6sDIlU6Bg+ zB9&Ay*C@imX2aWt7W%}`YUIsK#WOP-7oQEeMdL7Z zWH~Nz5|LG2KHU);v*F2pH-<3f;_yb30rJIAw7fT{@Jub*xHVhB@~NVwNTL%0N-ge% ziYa8qxSp{tPz1Fv3v7eV7Y&YM^ZW*J)TZX`lCbYMYu4i~`iuJ(>Pq4ze~Hr4g2ED`UU4&=mpJ2XOOfSz~@vfqqywCw~G3eO4;Tuxr`7Af)*ka%t0>S zH)(SD4hVdM941nWtP`^Z zb4p`FDA8D)Q9Vfb4c5z!`lgU^gK0Zcqb$vcr@?$Ia%83J=oyI^HXpoG7_EEO!3;a%2*I!4#s&u6$s>KxTpH4OMcFHGFJ2BO12Lt%3Cwc;-O4{ESzG;+Dwz;~`By90fP<|s{ zXkoPb(jWl!pqW<5#)!%MNR2i=Nm--pFwLZJ+E)rna7SFh;`(Kk4pZI8f!J(Qd&HAI z!3YDBjIcLTDG$|FU$S=fi<{-s0a`k3LBtFPQMp_cL1KnXpt+xgBZ-Jtt?iZQQXXN? z#I4gJ;Ychf`?hQxd|MyFA6Ti*wN|t2%1YNncdcgu$>=GzoJ^TDGg{*OiWqW~eK|jF zFHbTnCSf#Z5yxRGWMx&$P_Gs@ukYR1!?H6)zF=A4@HI$_ZPzsaYz8CoNCROi1Xl@2 zU@_V*N~?uhJZ&Tu$ZbQlYlt7>YNP2;0U=z3fSaY7 zQq(MrAS{FLxkVx9AzMuehK^b}^$Ze9R4)4dLC_56=8@M|+%!e(jmdYDWke~%OIpQp zX(HihW>~{{!2F~ix|VqcfWbzm!Z=F;lIX~!6Nfa7{%u%n4n0P)3VN-46Gq6Z6ATN* zn&y-vqU0kKH6+jGw0W_HN|=HXx?N#&a<7q1NVzRFtk2VCHcnlmrE!AK;jCF?B8&)V z!4wBDrAa*sz0ol-QzPs%;v1%NR)v*Ccrer5Tvm-r8D5Ph(!O8kj5V27wE;>iUF}LO zP1_EhsuD(>gI$j1u%D)~K9xwt7@F{E8UQtw{)c_Hy-aB`P2V#{Z*oqH!zSw>MTP=Q zwyA1laAnt}gdiyjYj{HvXJ`cw}`#Z zidX2Esi8Ai$z<1JWU~xW)+pWBjFU4(ILY$iw_UL^FU_-eCLtby&xD0{l*c&b0zK0{ znpRF@)y#r&0Giun{PwWMO*6BKmX)I_=#yacb*j$_r7^>$EU*PGAUi2D(=%yu9ABJr z`a7fZ8`*pnx~jt&oX7`6y5+>*I91!q*}Ubd&6zFf)$5!U<`h6w`(z?LFlcd&7jF#r zywRw=#7A}UXjnZYYb$}v>COa6Tkc{AlO6?2a%#0afNEr@g5Whw!+jHRjrB&|yw=9s z4^m}iwoFGQDH+?~3zqGNi0#vsN?9i(YZGM{D{X6tYSF*G@vD6Y?3C-OL{L-5V|?-O z^>B!DRdd4i!^bZa?=%SnU*cz5^-aVbJj zCmdm6vSl&|m2R+$;A7+htTuyoq)i_v+d6V?i6eqw2e#X4p2=R?<85RShc|`u9Z_*4 z4RO#zn3floXh$!CA7%o@-YW;9P;4hjO+WDtWDD&q89%}zV|>;uYcI%+;XR6CHOFNE zJis!xPT_PkmU~M2jYS*Pjd#St$#*4*yFGm&P~EAg+dr%bSZl=^$F-7 z)Mm2M(ZV23jWxiAhKdzO_t7{upy-MQUh%5!(v=&^BYR84@bw67aCLfNUj~{^SBtbh zD{o7YM|`|*tAxecwyVX))mheLGs(G#nKH7UIUTPUx#>{v#^VZ;dmuli*bAFiev%#p zF!F1M=Z&WdLu4GCO3sH=XFuQCms`8lCFGLgzI>PYby$UU$YhHrto zLN3s$O9dnqXKqd+U8gUQ^R>*TW-edN56TRor!+Or!povezKw^s!B=daFkUfgWu2cZ zY$3&Ny<*cZA$p50D+p&tby{D`mGO5X-EnaJ3ZMbrx0bW;zZF-kT~dbVE^SQ5^d(}S#*oG33& z%(26OJ=$zrqd{3|%t@Oa*bUn{b?iLloFC#)a^*na`HcUAQD>^X-~ zTMf(yk|=cExou#>`d+s`!h(YRDXC*^62JtAOo3PIu8{$XpmELM?%%Y2BNcUBqZuO@ZMMZM-=_!@I-ec3nV0N7F;J8s!#>GA za22e!GKeXnaKJhQ`6Ovf6nliMNU|cwIWdz6$IMzznxz0oL)W+KHo{)6{3Zu|= zFeQkX66m0pW6*2Nx5VkeF2U&y_s&gjFpQpyMuftaY`7tCr)fOFVX8;}t$}z4=i0hc zYbIkq3pGkeopFM~1Pxx~DXr(&OSPFRZk_EZF()MFVY7Hd$FJ=&w44|Ly@`}Nnb z1>^MNmhGAE5#-zTCK*cnGWz6}5!g;d1uEDeq<}M(qD0ajOk!mS43l<=6$YzN=VCTAy=)T??#h?rV&KSf`s{0^h-y54XHp?x!x9)hD)3vxUd*=Q&9pJJwxZ@Z2)!EOV*{v z(#v3I%0v)^Uo)i2Fu;yp=5HV`1}gMbA2xQP3rf;55_N8C-NTdR=k^wqxdY0rmF(TFjYQDQ}nhXd7# z^t|5dwjLP<2;qYv83z91pHKc=%~MEp2m3TWiqMc~uM^H^` zhZ0JZ4JwP0CALaqY_>zAY?*LGQrn(7v4QG17Y|)vraxsKtDP*jKNHtdL3cG-t2#2v zJ``IwyOF6px|6xYzy`L{Y9;xiK^J1C4-%%RJ&ll!tnDvVCue1^;XD7P7l1#esn9Gj zct-fJ9A)oeL3?ZAbUIvxsG1!+(J_(nIbGQ1wKohb%5c=}Zk?Z(1~=hl!T%AEOZz~& z5J37*-+eI>%mSya1>?a@8mQkk!PLr6W>YVn7g&4-lnFySz3MfQ%8FBKb|?e4X}aLJ z4rvj|MV4*r`}&wlMSfvO#a6%;=WDI65w7nIR8&~3`+TGV(PD_ES;QS9Uv&B~&ALG$ ztcq~NGANW#g$6z-h2RNfN*P3RbRJM_I>+&rPM(vw#njlOYeszu79Dd*59NR@yEa}d z-Xo@>G}AHdVo8BhS3*MsXU4Tp4pW)vW>Znu0b-O>ffMAyC!08ohpYi}N*e6+HAxsJH!%q8i?ItM6LgWx)kJa)$Akl6 zyTjT8!nh7wG&j8J1j2~0JJm{)k{5C` zhM4b%keuZJ3#X;ZvQ^xMFUDpv4rRy(U&#;}Ij*?p!WtNq-V6v|V&t zf{04wZilMlrW>=ou_Kuoug+xi+prMHw;i-g7=#(<0ETjQp@fNi#UI<=>&B@?j-6~9 zV32$@Fex|~ZcDvDYSG#&)(>#d%y%#&hbpej6ptF|8XCPY_+?DvIJ_eQs`d&YAmU=R zf(`*n1r77&=GOz!w-WTF-3(d^ohq z%sv-VqYIEEkl3cOw2h|sWwzSAVzhdpIAJu-Nsb*=facgGrA)sWP0N|G1UZRhrn1fN zGYyCusAg}mZ~MT&799yhPb&i)vwpNqELYCwWXjlXCT+YWHS9tJLBb9J)VZ*}?bmG5 zxjX3^XV^MpU9+ByyoOsl>R3Q|R{DMPyj*Z7TMFs9Wx5__*Dz~G29<5NWKWdJDvsbZsuc_j z;TQ^wGg1WtpH^xF4dxNifhKvB_o}5bks%ze$T#iTv!4T?s>kyqx_ov0h?Pf%<)&>=+rfAB_=9$tPO9!)+{WV7@b}Q)xa|` z!%T@mW;3>)%}WF<4(*jagYUQbbkd5DsA5PI#r z_J%w2@_VFQ5R?o);=33^3b(aJ5ri!U>muxkUk9kVO-cVg&5VKtz)0CG|22<%F^gxN z>gc?2)0OLY^bDe_VnK~kq+T$~TTKo&?vs1KGUOb@W*-~l(SpjP?5lyIj!9`|_L>L(eTbog7Y^lHz`n7la#&BR~z|fp|k41)Em@V$jy9%U6SvQ5L zfTJRl1L_nHmI*P1&(7SqL6V9l)NQq^fj$&RgU&c=t^KlCTau%|AZqR6EM02+l(Ae8 z;)e5qc8(MAq%w_#J1eD;TZwghO!MKxY<7j>u*PaZOXghG)EHWfu;W1*-_!AHeGQlC z9u^_*N){K6F*`-B&zIct87(|rWCyB~vmfHu)g`LB$*R#9(-dMQ7R5j>Nuw3bR;Nm( zRx0h$b?KCh-jcydZ#*b*418i9g_>w7;v@VLWXw%q)j4brhWRKrap;4DUt#2!N{BNw z%8$TGx|Kd4UK=rN8?jOcQ8)*$TtO#3+s~KSEVUjf%J3LvWxW2^4SS6|yUuo4xFEAK z>`{ylGl`#35I#w$R<40F5SG#qH2a3nGG#KVg`~|Y#QNh!+Ujhwl@7-3%V0vLxSZLU zVERw$a99EsauqIdhvjb@OJCrnbR9ugia?ev=grZ!n!$}RcPi1(K?iM9E@lVKj8(%} z(olUJ8@J7wD7S#H`BiNuD2Cl64YD>`<{b0lp?c#5T>0wr+3RJisV*7dC5GFM`H8ih z+>14tR$SYgO=NMkS2WV?+y*2RtL`-D9blTGuI%3w_iyo~wwJwxw&qA0QPPn>35@gkBrk{HDZ9ysF^4s}?6_sPX^eg3Q-$h5*h81<` zjd7H@t?}QIT>QGi#=DvgDdT=t?UWA?Ch9(;=r)OAY&E&#ybESTW_v2Ly(>7C zgvL%=?ND~~ho-pEQ2;xzgVdAT223SW)h&C%eD-Zd&grwL=9*CC0l2)$z3lELXXac9 zRpa(TI+kUE-Ck^rU0&08BG}VAuz6w3oO56fG4HaevYlIo!PCBaTv5~sIyQ#95r-3# zE~cLuCb%r*EQOsbQpVKChI@FuETN~sTqWZ3x$wjQmK1ZA8o97(QIJ^C5=c<{oOUZ!;M$v41hlD{BL9xTEbuFadbg898o0_caewBnMAh|(x=w|H(D$)Ixl^^N2AcJPEf&z)+~B!tgZS;m?{ww?G*JM!Feb z!}W%#OvOQJw{MlXMScH=TIV;jFhG%Lg?oiZoxIC5jI~a>?V$azo`)==FaZlR0zUic zZ<}smI{~jW!bzJ4cJyuP&)7@y0};r~IxWmy9L6dHO^;h<+l3esCaG6cM>5GlO%Ngo zJ7$f|AjveMSW#YX;k!2~P~u?bR&r*xff&zm4I4IfAtz}9d+J9jbOIg=Q4Upf*|y2# zdb7kZx)=mJSJzk$2z}C5n;4-3htdT47ItJ6qSzV_7r^Xjl!a2plDHBnZY0JkgL=Ld zh_(Z@8WOErZ)=^j_VV$hX#~>IcX0g>bD3Ri5Q1$P;Ut?haf?rzw5G{{NAOcaV#0h+ z)aXXE&)0jl(6fHV`_1wld=NB4aTd-O_#o>Nb5mC{-*hB63Zc1<0iCjaWy$#(`phpo zK#J#+DPEUtSsg)$ed!7bZk;fVWA!?e$(Zg`ickQ1VP+B}VLYN63Oo*&7h61RKU4qam<7p&suWNwV=!qtpE`Q&@}eBP(Kw&Iya+uvebl7G-Gb zZqROHGQicxfvcrbQTqv_g9^rZWERkpk+6o1op>3XSz^)8paq-IkOB}+S4)H1wcHS81!cR6s#%{)dgjFd5nO+AuN;CN|sVBLe|GYnq*E>4Q^ z5G;K^&KBE5x4YaF8(gZ00NSDdlpuYmx5TRxhlVbhDu`;C@im&Kyx^ zDHydhn$XQWsegJ$I}JIhb52v#qrSw_$-!tY%D|Bt7^9BbDy}!sRND>T!~Dm381iT8 z2Gh^%VJkpvly4nnadW4dtvzl<2HR{2Oi;l2s{a_ulDm8SLz#8fsJ2&G~&i`nOJ-DO|t*&H} z*Izfua~lN+3>_g`N;{oqwA3gob*@`jNa(l2pKj|g>Uuuw=A5|OelPlLyTqbsntY}z zM^T+}n<8j-dR$-Q!05wnCD; zTRGWz8ECuPQu@k^B@MJqi?s3E#@%bj-j;bRY9W`Kg29?pU9)qLy`Tn(2x4awLZw(N zX=KQnrL4lRqWKjya?1wWT-7W=?$Z90*9q;Q@hG!en8Dv#no3Jgq z;a}y8J7e3{@5;(sa%oRit2WS*KfzR#P|`xtBgPQfCU&l3buK^AK$}D+V?bq-T-HB& z9ee9Y=sLe)LTT6?lKvo}%PgU$pv{>;2uT#ijI^lwqO}+-W6vqe5<__FM>mQH;^egoG8hRO8(C(U63sKpw~o!?Twj#p(i7tu(T+(m zWb-*P8%Ek(C#V639d`!Tctv9w>VmBq`cWI-mY6j=r@sD8ee3&W<|OG>ck~(Z%X+ha z!;YvrRi}yg!~>w9y;cR)gx(bbFB(!K%8fP}P%iol7L^HKh2OH{M?)hzy$NbcT$lPJ zHwJNGz%?D%fw;kjkQXkEHInnAnAvf*S~JMl2Ga#%o9!2WfxD)dElbC3+W=BD=HG<# z4+-ibqp*IC*n%X%bOxjh>zkQ5IQhiN)eM4M7}Z!u#jTNPTZ}{=1->pTOE+ss&Txir$Yo36k`|&if9#TP~;u z8syRBBdjt8v2Xr0USR=tOMf6v(~M~R$dUMbGx3mUDI>Xt^LcicLu$Vov>@sf@kb3- zI(~%)#RyXy?|uzdMnc#gQ-G#93EEUQf3IJ}=9BuAt;_sI+WJEN5YoZVsS1~1-CKvLjpc^18qrGsz8zhC!1OY=35nB`T*BwSd*D5nnW0DXo0bv z72UbqgUY*LzFiAv%$`tcv6}SQ8t*Xb>Cg7)1+dJ*{D;^=v#*X`6q3 zBPBTQi?uK4#uXXe)5Hajw6a;tY}$Dn;RdyP?A2VP*72@huVdL^DmfK3*0j;8)9q1Y zjvdV~5pPKy8PH(n67KJ#pL|)aS241>&VJZzfH@(d;chVP*7}0fO>e=%qfdb)g$c(s zX__Vm%o<}8Pxy*$84MgEK(b{W1e;Enj80pR^Lv2k1MUJ+87c8U&8iRog}!4SmIy35Q?Oj(e9Tq$2{X|@SR#s!&L zDNqndL!y01ZVOto2Ihz6y1=$(ZG&%JgYV)7-z5#cH#hh$#Wy>FvN@ogzE1Gl}7puV^hsy+-MY*`dx(#5Kld=eAQ!sGWw{UIz)1Q{q8^$LJ(i zbtm(|mZ3m4Q?p%_khwQGL|e6phA!$wV?J#oqG-q|v(HyEMWZ@7Dfh)~ zHmKCoBciSqNNq7}JA{c4y2o|-OmI@#%uf)5Z^s0x?1;lb7A<>;m2~(qkSM86DZ%fx z^LQyl(X5;zfjS4_mL?5%{ux88J$_?@eF9nGyn&P@8>Xn=4;3+$Uec9o*EMqP3~CyC zu@7-haHDeA79DEe@bwz}GRWuh-a7Ttz_3dBQj%9H)-fn#tWwUE=wJeJt`4A+U1HB; z7Halh1JX2Vp&GV;dB48DizjEfY;aA!B(&iYooF`@al=G#zZ=*tT@dy5?x7>>@Y%(- zneNM;?$qH;3>b7uj=USs-%E>RYiz#VPD@T_foz?nruuYjIB$h|)kNlCEVKA7-%#;5 z=wX(`?KaY!I zuTL*q4VnKzMU(FtEm~M4mY(K9jHt^?mAOG9IBRUJ$`4k`5jl}Ipp7~|A~lm#oOOmM zA2U;gQdy3Ur5_*Xay>J4WLF8DslDmCXw!Nor#`h*uvmqY-kv5dgZVf```PTO4IAFl zwsOEW6|4K&uDa-=wjOjQZELz#ukPqt+rDn~o5BaPzKf*mJNN?FP>D+9iX?UTt{GRJ8Bcr#f0fF&b&h| z&Ev$Yt_t4u{o6W>rOzy(dnI>uWkyx1(Zh3?kF~?0cMKz;cKE56p9kL}6!{yCj zb!=yaVBN5O%jaAz{W9E3yY<;ReTp-F?r|ON_$@iT89y`m{kW4)HD)JX-kjaV2UNQV z*ZWF`HyaQBnBU6t2@l`;Br4DE2XLqP%`R`w4iKjN^a;(FAD>oks9)Cwjo%DaI{j4d zG{5J`ZzW;MPoKVw`E9_h>gbc9`t2q^{_Lm88_3(YvwSyVL>6FXqb^*y;F{hn~L*F!t+n?R?`j zNf)#J3(}?adz$(!5T^R^`P;mH{|mSBjrr{-!EObFU(E0C@u&Ii{{H&7@tMs$za_k@ zPp!r(J-Pbycq*Js@#6*39SUU%#B$FgT~eJ)>3&2nhF^@+2d$%9QEz@rmc8Q}F;zY8 zA`+$TsL+m?>%Ct@D^#wsf9sy^3EbB)W<#*y|nlpU@RQ-G&Pt0%oqWo4} z-juD1jST4kS@)v+o+rOPI#ce+`N3{JkmT7x8-qoBvNjl~C z2A-JT^rHN(+~1U4?OE9WnBSg7`K@@ojtA!_`5j!8-v`L=Tgf+AV}3U;%5PPYA5$-{ z-v<`uclgdGYeTGJ%PDGibR8SF~1Kl%5OLM&4A#_ z?@dX5`X;*GQMi7~f4(WZWske{UvYZ$rSvr2&o61tb}B*m#dME_bTRxn(xpG8)9(Zh z=I)I9_zo=TI->^|(|s@QIL8(J`qt)5-)E1%=oCy#dh9FB*U{DZ+iBS=2__VszZ_W-c@OMF*Y;eQ6N5a78qNdAq2 zf6n{B^MLwRwd%KDkbDmXc$XmMJt+7H?FjzIgZ~*p(mxkq%MwrDCinYLZ9$2#D7U#35R&3p@5-@I1%?ht-$2(N_j1A@Ov`vs3vU%_8y z?GgMi-#8BNWPoR%LHNfQAK-bw6~JZ&dX>UIl4X|*{sH9){ypOn;DG?|6#N^$WgXz7 zg4F*x!B2xT5Y_W&-*TYZ*(Uf5`3pWsyMX8YI^U@VHuL5A%LCjP;N}2(0(=Ol_n#N! z{TBpzU*Gc5D0rmx05u|>zf*)gC1gY0?pvLi$03QwTu>chP|(qAS>`awbR z84ckFLinA6e@Z_J9)nH@{u+2ANcoQn^4`;e*1U1D(68#+VQ*~^R4CeK-zOzfV&0hr-=X;1WA8)h(8v>pA!5U_#MKRw)uNq zf`3VQ!M^|$y}Uzy+J98=li(fjJm&G!g0$lqp!)4uLGXI%8%RgFZGz-?nIQG50MDb` z+Xa7%dMTWKeo&D7PYBXK&jxt*8{OX}NI91SwSH^_s(&g9e}eH6B%eD4>A(AdN_SlT zzXm_#C;SPZ-g{c%f8jj-il=xl!~e(BNARoENANeGCxX8X9ti#k^h!|e25MZGg4W(= z1%DMfA@~`_Cxo9Aq+ebTq};3tNdL41h%;O9MVG}?P8n%S?EPQ!@Z2{^%#digGX@HjpxH-VS0Cxp=ZGaO2&IGs+;DG>d5Abk+cLjJff$F4t zS@n4!#2*Xrcz}-v_;`Q}slE4P@IMvcGXbiXjrAoxSjHNhW*9tnaw>YwJT!9T%1XS|!YgNO2u zGVcYu9j}_(pxg3qW!wcB&!qvL8{l%mv%|Pw!a5NAmkO>8^&-AU{x0Zwh`0K!5A}Ns z^j+cYp?)i&L-JFe`m^~Hyib2LKj8YZ=I@2>DjXV!)8MNDe1qU?vg`*0S>rlF_@)4_ z3DEk5_shXQ72pj49tiL!1N`X#j|6ycfFBR=cLRhZTYbJ9;8Owqpz2R~s{`B|;En)) zEWlELGXdTZ;B5iEFTlG4{IvijzbSvoXM$e{@T&nn9pFC&`0oKCZdv+Q1o(XczA?b| z042vL-wgrw2KcrBM+2M=@cIC64e)S)zYySu1N>xwpAYbCa9icPKEU<>eVztuUEbA=X;*#obxRAxp!`JZ@hxzIFkMK+W#Q4Tu9H%_1vjNZJCG5{!-pYIVIOESCH*+U{NQ;T+HDT*xJSiLY@D-{A)S z#J_k@cz+8eXRs@;;4n_$49?@zT*0Hm z`yFwd6L<>G;U&D1V>p$w_$ZfgEw}JT{>6h2PsXjq#%#kbyoq=7K`!Dee48I}C;wvE z@B>KP&Z?}-7HrEd?9CjG<_(PR^Tht1=F5DWoB1^>ho3d#@-^9rr}JF);sB1|B;L*k zxQOexmAm;j%ZIV!_{Xpj+pr5WIF#dg3+M7FzQT3f%H8~%<-_|*>G9c!ZP(57U*S4#^?SHJrv-T)-uKkK6b?_p@w#e=F>Rs;tZAJd<5{ zIj`niKE|b7#SKiqj~2$+FINxmpT%+Ou?5?*3wv`Aui_27lMiwc-{wc$$zNG2yzdsr zKa@4un5}spmW_;f< z9-jyK3}0n@|1q|2<@fxP2h~d2k7RweVkchA{v5$cyqynl5ntuI{ER=cSnXu|imb^d zY|9In$>F?~xAJ~2;?JC0CmH7juHgpmXW6>Ra?N=r?%*A|- z>$#QR@Hd`UFPT>_4rD$jat80?vwVeb^CSMi%Jq}}YqAl~<29Vhd-yO9KOtGa7MrjQ z&*vrV&wNhgt-P0y@dduYjoih(EP0~sU;{Q|E4JZT%;8wx&inZk-{kKs-5?pS9^11E zFJ(4I@p|6Id3=&DaV9ypebFAwJ7jxsIRk8~(-v8YT0o z!dh&?Haw4)F^5-i3h(B_e2y#mK0oJ=EY>)g$I(2Ir}7;3;y{k#^}Lhw`7B@KyWGaT zEZ!s;zXGfCM4rMETJNCe4H}G;zL})xA`%@;qN@KeKL=#JdQ2df!*1cxxAJ$IG0ayIp5+(+{NEm zrb9B1!&#Rt*q#~8;aE=POfKM3uI5H==g*A4Ll<8!RAdb{Vr!nq%Q%tKIh!x=1AfK5 zEYUF;uM%srG28Hb4qzT9a2l6zCEw#Ve$V|Z+sScfT{h>L?8?h|J@4Ute2mNZGgD_L zc%jck^Ms#5c}Q`g!-l#OmD>*YJIQ%HLS(qGY*4S(A-;I?rV<4&X>mVY25iNS?7==9#%nl@ zv$%juxRUR28^7m%mhG9$t19cVIoq)tGdYaoIi2_NalXj4+{_*Pm8E+n^EiyP*o19( zDYH3>lX*Mu=TltHH@TTR_$y0alFXwDYqKRg@e=0n8qVN6KFt-}#vhov)Oo=gY|Jy* zl~*v2Gx<1Q;d}g&zp&J0wvTn#f*p7fvp9m2c_$y@b6mxZ{F1-0RBz+64qLDTFXA-L zEW^p*L=5@T05AzwW;79zLzp>g&Ke!(C4HxJH9`a6>KcoIACLS{02{cU<4 zSMw&$;v-zbRouWY_!El_wqIC-4R{*QhXx_lP_z<7tYkZg6xSN0R;2}xB zNAU!n%1*qP;agME^BBQNyo2}iX}-dD_zAz|A1pgG>9-n>V*@s0E4E<=c4jYTFpGmY zoTGR(uj7rJ!8v?@3-}b5aWyyabN)H z7;E!Xp2cp=;9!pBjl7!=@mapgb^M0E@qpZ99#vS2P1uI#@luBWlOTPbjpAh9&inZk zm-9_-=GXj%CGwJfE3qcq@O<`W_%D;w^BBvioXG`T%GKP&ueg_`^OOD#V_ml7S?ta5 zZJO!v$MAaI!G(N|uk&3VJR({D7}jS?wr4jEU>;|3KA++WzR8cdgL_$WWHNpw*5s+| z$Zoux!#SRJaXz2n3ckZVEIuk3w*rr23%270%-~2);%u(qo7}{2`74W$PR6ay`aGFu zu{-;62*+|NXL13Tay2({JAY=ytCD#%}pU-d=*YjiU;%_W9CK>-w z9?OP2jpy=W_GUlE?+%IYYhJ@?oW%uP!q4~}|KNdRlYS0o9X4ZIc40pb<29VdSzN%) z{FNofCF7On(L8~z*pU-CozHU}zv53!U7hrQBWi@1X8xRt5#$#@6zD4xJmcs6@-07r2WZ|4JC#8>$aKjF9B&jTkU^Qp?? zcoI9XJNq)1*K!8u@<}e|Tl|Q-_#4Yyo6MswTkciw|=NS924;;$D`%E*bwMwqqAw#z7pz8+i{O;S#Rm27bYxSZq=< zZUr90hTO+elau8tvo@RX40hq=9L#aNiLHi4UVKcU67xv~2yps>|d49|t{GFwz*dDfJN1n$E*^3#>;vf#^C|=D; zyp{9#6kq1s{FXoQHy*PwpIE8odAui$yzR3^xC4XkIsmVOb^Jt#H zR_w@&*q6gOo;Pzg7jh{-=1!KnDH*>qYq2XcID}Vo8fWuSzQ8s7fM4+!mYil>)@F0| z=9L`AksQZ~oWkk6lMiqaU*|@C$?y0Z54bs*Ulq3Dx$MOO9Kq{&E9deFzR3Ua1D-HF z8Si9vWDn+WG_U6!T*>wPmcO&iElK}}u{N9X44%)+_$GI-(Tt>@Q+YNoW)|~!EpOqy ze2g#f4esV2Jn+_Jyu+Er;k<@7a}FQlGWNVJ=_iZ%oWuwCB$sgwH}OmU$iI2;?MeSf zvK~)j2VTfN%;yA7=NvxD=lM1_b1T2(H~fiz@t`}B`BmfbY{~ZQ#=gwwWZuO`_&oo| z9sHH0?@Y!$mJN9h2XZ7Q^A0}9XZRZ5<1u$7{h!Fwcs6@-07r5%@8H9Ho^NmyzvLd4 zxH}oQ5^J(C&*1s&%^Z&9R6fEbT*YGdB;!NKFLEt6a|eHA={d>xRal$NcqY5EKa1a+tXH1Z*?_09Gkb9$NAY^j zHU+{iEZ6aV5t_b2nH#^ZSs+wlTsa4^SmD(CZK zmVO}VzcPqhxrP3@)wp~ko0#n+p#|<@m4P3Tl|!} z`3Ea6O!_^Rjo6VFau7#x1{ZP(U*+4}!Ag%N(C)~|H zSmv>0{3@);j=Yc=9K=z)jx)G~ukjsj;aB{bB_B`5Ka$6@IotAbj^|X~#RYtk8~H0s zK9P)bD36I2OQmY@lxUUkJ=EIIkuTvD>N(M{-Z0*veVX=%rc~ zKhXXS|6sAFlI0JMhUF`=N;HgLU3)#b6+5vfdq=~#{i30t!5q$OqoKc>EpT#cGF#n6SU&;*adAyFd^Fc0% zhV`G7Uy6o#tcZsBtykZo{;B%+>c29zC|R#$G^|%X8n(A8Yx2Zs=)W<~P(Pd9)O#>f z{YvKX8toIKVZ7VaXLG*x1=^oge~GKOJ{sn;f!o!;<6iaOS?ZZ&yAI*uJT@BosmrEp z$xiIdq0Hko(XhX6k#CQN?OG^5!4+J|_o89FucP5O?pFVqziKb{Y_i-DJT@BV8x7;M zRBxl+PQ8nIPxZ^x2dd}EQ?*a$d@kS$uH*;NFyAlaulY?hY|kF;f6FBoC(Ds@xm^8KzNNmA+tj!72ld}r{JCVl zrCBi=`me^i>h;-@r?4}-GLNG;F+x?R4TOSp`yqE*86HX4q{N9tSoMYKvP^(#v) zNpfW#5e@4d7Y+OUMENA`t>v?#;rN`x^R@TkfN1FF8hILTjfQ^j(tf}C0{Pi!=yxe! z)cy|NkA{9fk-z1S>ZO;4_ON~BqoJQeqhY+7(Xif$>W$ev8kX^lhs$VNl zjfVcGM??SjYG0uKIG>J&{$J;sXz2ev`7?f{{)b%h`K13cJS-a4t1chQy3x@8DeT0H z**hB6%Zi5iW^=Iik=n17Z{=O;&&V%E!}_mqo%%+3Ge3`p@qUqii-!GE{)J$e=MmA+ z&(Un8-ZC22Yps4J&(eMgujEy{k<+7L{h9K8@<0^*VCB=n<(@EA@8j9eJVpW%3owQNJZxEtQ(3ejgu*hVh@{ zvS_vNeaQ0v5)_{))U(UMFvmx60e)-SQs!Z@J`4$vn$P!+a{s$H=wiMsgdrSMMTsmowyk z@=$p^C#l~e-yzSH=gUvYi{)43mGU}ygS=J#jz6jYDHmU!Z0CW|a2yVitH{;lnsQya zf!tJXCAXG4$mhrx$UWrVavwQc9wLwA)#?+Y;XJxY{T}(TXgEHLqhbEftFM&T$Q$Gj z<*(#j{5=}_De-dRLDA4(1s6`nl}R-t5nz9L;NaQ#5SfEu5>qfX}EeiH7;SF2BJKqG5j9xJ&(e{-s{#)nuH5 zcsx&xhJH_rhJHG*i}nk(_f^l~2wul&yp#8FL9|%-%5*-j{wlXb!}<4>_Fep5d-2zj zc^wc9%TlXjrer>xpHeVcbKb;W*Th8)$FB7TQ~DKU?m_Y+l71IXxQspDEubFO;8@ zmvDJB%x^WZ`a>{ZsjKey6^d#a1QrFU5+i!sB=XPmP9owdZ;27w|ImEDlr8=LAmTU7W>7qoMz2 z`I7nyzNx-}Th+hd&+7YGYIU-G2eNWB^nWz#vWfN<(Qtj}png6t)_$q>{^~R=N$EUd`x{YUsQjEYog(C`M&l~)IZ~o>c7i>@xV37xRrQxG;D88Hc>x? z?bw+Y@p2B}Fpi0a{;uJ4^}9Kb3;7IRD4>fdmW_I=t*{4XpQ_UA#Y z!Wz-gPwi;vr@8v+JWKmI+AmVSoCBB}4gHMdL|)H(IERl%!+f6O%j&Q3ZS_t3O#Ms# z$X|HC+GPB4tj~sQ6%FHcjE3`~i~5DUSoqGA8sCqKaF_yRXXL;oMk+qgX% z#^1*>ZzlPWXjuNRXxM+%SY3Nlo)itsohf(Y#p-?J0rE&*tA2xgdo+x5H)m^qii@LR zoLA&^{FLAF$7on?Uo`ahr(E)_Bp(Tve|3>BWTtwK zJd6|6r^?f#@p!2(P=A~+sjrsTM#J)3)W6`j+JE35>LuS!=65iwM#FZ+|HCczbE0|+ zw$^?o&r|Qg3|^^y2(MG0B2VKi^@rqz(J=0F>MyIm#`o1flt1P!^`9C4quaP0C0R8Z zj$!n0IP@;(^hy{=uxOUXv%PH|A+P zgWcGJ{iC7(p&YF~jyI^!;B57|(Xic5t3M~dEWg3^+#C(_{)9XDE&pQica!BRM#H?S zv6lLAY^r`L&r&~!7qJ%yaVW2ehW>Bh4D~xWSA7AWRbLtn+r3(Sz4``j*DV_6(}R83pQAaBvpJWKM#DHS z$t$>0{atS17u+2U9=Y$ELTfz##ZWWqhb9HJX?Ej4rX37^fNwM zJe9hRH)x-seYQMb`vNXje=!>Rc|BSpm3o73YG1E?2U8o9@XLY^qkkr&F($}9LbxA8mv z!9zYw<`Mtz$T**RY{~Y#fR{6eSMdhk$p`r~Uyg?Nfd3b*7=E8ZeFHz_$I)_w#A4;}(9+@Axx+$s60@iTtS@3@DlkCW{$&4XBpRau>N*n}tXbhhI;?7@D_< zGQPo0{F0?Uah!N88?z11XK&_kEN|jte35VRBYwj_Snktg{3Ce+PvyD1l!G{yAMz{y z!ctq4eygw!Td)H!ViremGVkQ$e1U8DDZk$hb&fpwA%ICS78~8bY zWU0@R@hYe5Sf8ix9A3gJIfhd?i;r>{*K!MY@pqQpZhY3~DLjXl@Jf#1RLh+>!Ki3Hvjj6ZsrV?M#-h$Ya=wSMw%5#-&`v_xTxj z^G}xBm5g&7Td*B3U%Zn`FF$SdFcDHZNjd4(E8@%-LMXrCh}= z{E9y@^=&ebV|W5vu_G^HUk+#4?~?ToV^f~bOW2<|%;hb-pHJ`=e!$%<{(UlDc{bx& z%-}dqiIz*H9+01u*T@^>Pvu?m9yzr;S-)(wT6n)xt|6Z&x0KJ6JIg)gKJpNGv^+_k zF3*zZ%TLS8|Cr3{DAwocJeNJ06@4_kKU+FjEd0D%DOf!Gduy~r_<11}41ZOP zhW6U>@p5zdWVx%{T^=as$P?sA@*H`d{Ji{<9DaOBj~`y%rN`eR?~^NsIi=?p4S$-; zC(E7Xu5v$lpgcjIB+rxQ%PZuS@^*QLoC^CYj$bkwYRAhb%I)P&@)dGFd9*xEo+Hnb z7t7DfZ^`TBALKo9)o{$>e2$97`N${A?d4ALKsiUABu|m&$@Arv@)~)&yhGkEr%HzL z!kl-Du5J&>Mv_^~PNHw>4Lbl%I~d7$&?U{>J~Jf0^qeSU}g1?P81^>f*c zJvfL%Ig083Z#~?&gTLynxF5xo1#r536 zPx%A)a6eOJJlqkNLf`6}P#M(*PG z{FB8FOt!ZotFR91u{F=+1-yt^%;qrW^E%$Z>Aa2i^C3RLMSPX3_!if5H-Bd7vdMOp zWhEZQx~$J8Y{B;I#IEelOPRre%;8v$=M+xkY|iB~T*8<68sFn4e#xEO$Nel(F4_JA zco?g(ChM>{Pv#kH&+hEW0UX3JyoQr`Bk$oHKFCM7gvD$CG&)+p`mU@-p`20FLAsUdzdx#u=Q+d-*t@<_lcT)m+QX{Dfa}Cx7FgEO~IU zU&`=s9?4@_mo3L-M{^u+;w_xT`}hzS@@X#SD}0@6 z`3^U7Gq-U&zu|8F#p3b($MASMkO#9etMVAuVtqDb3%24JY|nGqg*|u)vpJag9L@1e zzi%4mJ5`>}J2{i{IG>O4DK6nMzRFd6i|hFTKjP>7ir?`^ro!)pq~CwzL9D>4Jc@N# zk4@NuXRtlb;|08gmvbodIF{pi18?GOyo>ko0Y1S+T)~xmi|hFzKjs(wn!EWkf9GE; z72eBCpO>t_%B;oX*pN-xnrHHCp2y301qW~tb2*Y%^IFc}9h}2?e1wm28DHiq{*Ui+ zBfsQM{=hxl&s3FUKUH95*5Yw&#AZB=XYg#E#~!?dgE*9i@7T&`-e2|auNj}3@ zxr%RbJ-2Z?zvU17m4C2!c!N8hKc#svEAlAT;Bh>GP1%wics6^nH?x?{Va(@Pj_389 z%3FCS=Wre$;bVM;OZYNhzBPcn9y}1ALrM^EIyKdT!vS{G5BZkHxDxpICvFS(o+Mlr7nsXR;f6 z@Cx?h5ax0cr|=fu&iP!xr}!*aat%M^$NYj{^Jo6bzZielJ3g)|vI>u44K`vkp2F7b zz_Zzv-FYc9IE1+z%kjLPQ#qS+`7{^vZNAIT`4#_WiSQ3(aeEKt;cUcaJeOVABibpI z>MIZ6XpZAF&fwjg&Byo@U*>CkmmB#dcXA*1v)qx%_LS#wJb_K4Vcu=zcI?ic9LOBz zaTIUhO`OI1_yiYm1y}NYe!#D|i$C%gmOd)kuChFm$FL!rvK3F~1-yv;IFO?_mJ_3= zhtIpqw{t!h@F_maH~1#s<0kIn_xzhBj!w3(5)We?)?*X4U!hP%0s`&q7fvLDLxa30AM*odupCeP-1?9QGXz(LIA zNKWRByoYl*p9}arU*hY0gPZvYzvoZW0LK!z{7bY8?Xsm@pPWY3)qvFaS(@c zB**YZ-po6A5AWwgT+HYB3SZ}Y+{7=rlRt0||KQ&&T_f2aWm%C`cob{!IG(_!Y{}Ev zmR;GMmokGxn9HkpHK%eqXLBwe=hIxySNRU#<5qsbAGn7H)=c)t!K}g~SdR^O3S09+ zUd+qcheMgi37o{4yq6DgAz$EfzQy(2#_jx;KX4!Sv%;~-_Eu(X9?#R+mYvv{z1W*q zatN>E4ZNGP`52$#O0MBLzRw-}miw8im25{P9>zMX$5Ysvo!FT@cnLF^#e9zDcwWb; zoX$HrlMDDbU*>CkmmB#NcX1E*v3TudyG!$6R%8v<<_T=XmOO=R*@4~JlLMK=!Wi*WYlf0J)9A|rY3~RADPi7}}=4HHsLz%~kyqAaWsb0MGLa=ywne2ee% z1AfZSxs%^MQ1UDjtSp3bv)4!f}jdoz;*nZrDe;sj3OO}vG3`5+(T zQ(VGje4TIb9lpoS{Dfa|7k}fQEOnym1&`p-tj7jy%MR?!uFPZ>b2yCGax(AWJ$!_Z zaT#CcI=;^>{FLAENABZ(mTQn~Z+TYdv24N?Jd5Y>0$#*^9LS-}<3wK1yEuza@)@q= z8h*%+`3-mTZO7=@BR%TV!WF4N!#%#+D?9QGX$Q+L21kT_ce4I~nDPQDk zT+O%nF1K+z_i!Imjg##y$#N{uYOKzBY`~Lw8r!iWd+-uo$sxRk6L}l&;=_ED%lI-k zaSK1^SNxtov3QeYdrR|B9?sf4o~N@dJFzo+u{W>e5RT<|PU8$d#D!eM=eV4&@?CD^ zm)yy}SiEVnofTPyby$y$*_@}c4bNvc_F`}5a2O|W67S$We42~-B46Pp2F5VpWT?rEDm8VujORk$~$>4@8{E8%oq6zH}FGl<96=hKK{)TEtBo7#KTyf z$Fd$9usKg=TXtY~_GBirIE1;pmXmoiZ{_`bh>!DWF6E0{%Xheuo4JGE@)!Qb;wL5h zr8KMX2-ajBwqPrEVrO2&UK|)Lo=W8~pQAa2(|9}Y=EHoHi=qdI&v(ho_^SFl(GuZ% zCb@;5vUDo6R|?-l%Yxjoa#AnI6=HiapC=9T4{s0uKR*{(#&QQ0UOucB{@E$Lehr4V ztO{NVG!?Y*!G7!G0Xb91deXCvXy{a2oI79M0o>F5u&Qo-c6)S8_c! z@I!vg9sHI*a1T>q-^Kl2l4W=htMVw;U~L}Hg3lqIET6_R*q#NSx9u+XKF!5^o-c6?-{N|1;5KgO4t~oYxQFS_0f+kqp93xv&h5Cr4`Njw z#Tu;5<9Q-a=4m{G>CY2~emlvXS@8MB%j7Fq@HyjQaz00M9H(#^XYdZr<9sgQ<9wbk zaRpbh;Pc8GCZif3_esh96iBmX@ z_izs9aXz1B(a&?fq`ro4aXmM18@F=@zvU0y!=j(_EK|z$f)!YqML+j>y!weenWyoL zXn5?jXQya5ww)QC7XH7t5~*-t3*Abj!it4%CF0}@-AbemD3ro??#B=J6}pv3l`WKF zd$}SxyznS=E0H>+P>Rb}D3ZeqjY78)@t2wl-Abgtwc_7GiPT~LhH$S$`r9o2EtN=x zU#co}E0GGnlvL@VKyE@v!uNx1dbw z*iescrxj{n9PTH#V(B9oU$YeC#^FxPIpI(2?~GvWa2j=zdj{ikeP?-4Fg_=*kw*q6 zg!8p|s1?j7Uh|S$GG4s)734|bPR#RzarwJ~@tSd>^&bd1ewMkt_7{R{LM|A8UC5Qg zi_+t@$L&8kzDP~qlJQO}lsAWZ%!QY~qELI>zx@j3-EzV5@wsbSXul)W3%2j5e;zi; zcr^;;_&pFYH!ie4PAd~uPT!K{<7ZwAa@^N3S17c6_XGcJkMp~tP;L^Ii@9H@$N97l zd1c6#g@mhdy`KVw)|M7PTlUveX{GGyr{6SbQ=Je~RFu!>I z#NQPwXph^oy-<#?BV(=_>aqVnLXN*XHcT!P&i$P5yHpi|1>=vd5gOCCWc+b8MC0u! zl;e1Def@Ib;$9m-$jnEb92M} z3+4aLuX5@;{l)Vm&VOIX@qT*BsB$R~z;Mxoq3&Z`rTrnJ*g1kKBQwrrbLyp&og7(cJPb-wa4*9u4`InGC4fzE9mk1kkVAy8` zxnju83*}=%&M1@{ggmuSJ~ia$3gxpy-c~4I9CEoZWLNLQ|46|twtp?h$5f?oec4;2{m&w~#6QpN z$>ZSQBDrdj+^|SKRgTxgO5ys~u}J&nMe?vBIetG$!7a}J-jG)WP2$XBDr0Wd{L2nMUgzDNWQU1o>?Tv?;k0+#qEE#NRHn} zQgDmyZxqR!i{u?e@?S-A#eZH~CEI^QkzBJ#ZdoLED3W^@$s>#8>x$&Ni{$x5@^eM< zsv8|@{Zk92{G4@m7ATPm61Di=-_lIH!E+%;4F7D`-P=*2Bq@yhYri=mzkfLk)NB{ zzkhb$bbH>2ykS{GlJS#XlCJYI`sZf-r;9kCYTm%1qcZwt4$Dg=_lAxblAn83Ms8M4 z93bnz)xJafW##=d(-A{*vj$}6<(quJ?7Y51hYZQ;o1b2yZ+>o0Mt1J-f5YIs0qHO- zcW58e8J&@znKvjW?6}%&mNN8AC);szXh8Tw);POJI`8iXZFd>${dtYu)AX= zY{tOcq51ha$w=vARJ0I!$Oy9^oIUj4jT#zuVS1co*nUHYWHs!Y6aQ|N%rQSRH$P)k zpMU0(UM`)64Gk^*hK?Fyg(i*vSt#_7_wPgoW)2xJVpzH{dq{S&y;-B($?lhz%E;(H zVo2YNjD}5GHEZ7N-_D1I!&I;j^0LQd6<)AK()h}ygMrM9~ zZpNr~$vM(4eKP!0&Ms8$mX*^!o;?3F_8HtRb694d?40cUY-dov-0YEsPW!?!vrjl` z85x7Jt_nNgq!uUtd%tDVe;$5e3&TS&+0wk+zM-$Yuo=x;6l_G?_^|H^?TYX(@P$*s zZb|Q^<^{VXotpi#D`GFr;spNLq0LVEPipy}^q3`3`x)C^hae6>6g)W*szRYxsB7k^v}s2=0Y3hk~c729F&{YKh7-O zQNg7w%p-kX_RY!495P~9!B~T{2KOCyRccWBN}7=oCzxS|9?fx%|6UObx{13dZe4o! z#0PsphjH=j@MsK|jP&I4@^iC?3`jp>k{M*EguR)WlhJ2jM%Iw@<0AHGiExq5%FN4( zo!hg?5l=6YH8MQh!{s$TmeTt#zu!L>yFp=d!bQLDz^rhQ2m_?|K;DQxgTwsdkt@0_ z>Aq6`%p_dt)7^$c7su!u&V=xk)j!)v|L)3UyU6Y3WO2p{?zklbJoZ(6+{=@Pw0}J2WRFKDC6CBY7_Qcc6IG1`kUO z3%fRdP<%MVD_Q6wTx#Pc#skwQb40(4+<37{_FBQ@!_w))H7YYZfB1;35m^}n!}*@< z$*@|uFou=F1t%|cWp;Q54i~k&^f3MZ-GKB(KODyJgprC5kvOEYE8b0>oWsK?bf1@> zJmbeXWF`+8XN?1!%zVUF;kp#qw z3WAE(2MVI%D?aM0ideO^tyZg8pH*zFQj1E6DX6Gat%{=D?|1JrlYsPh(|hlqm(OP= z`@7fLYp=cb+G{_~KEuWJQzq!Tu0{UoTAtQ}G_CbsiL6q|kf)VsVeR0=f{*mp@q0b3 zmv?z;Iy&|6jeFB}PTgy^UOvv#+HsOL2YG8cI*pEw&WY!CbZQ$ncE{-Fb(xxWWsKg@ zxijGF`tit-PqfCyy*^DFxJSEeFY$h7OZQXZJG!+%N9U8;9o@`}*Y{c*E4A zqtgRfUgw5=dU)MluXE)-bIxUZW3(BahmIWiy`^<@vQASwty9xFJaL*9S4w@to4Pe^ zMwbPg2fcid6$;$Z9dPh5uHMfw6QF0>&a3wxy!`3?5nJ+aCO+rj6H^15K}TPpqsw%z z-utku=eF*ho;~~QHBaxqAN3@GhjoeCjj}%2D{eFD+l;z4qpsHQTe2-C^rVc4yseZK zzO7q#lJ*)-N0L#KwAZZR-}RjV|_ylEZYZ~`z;f^Ga(-HJbzqs7>iyOO3iNfWGtu zw(QfLOZIvK8}^y#(^ze~>`OzN*`;Y)yJI!&UHS^-cKOy^jlWlSoA}UI=uZ(Jf**do zJ^Xg3;w7K*C-VC6QGDz6(%0x;7W}XlJW_A?m9LlYpzb8J^KW`<$MYCHuV~t7UGSv` zSD}w1zSJMKT>`sW@TFO>Z4>Mq@uhy!-?w(Nj@~*&e4X`Df3sET;=^A*KGY=!dY~&l z?(L7+$cX%-Fa92%_0VM$eG+|ftj{fhF4S!a^osbLrk&gcfAg?^Xp_2LZGr9L%ssbt z*F1Yix2~PpRSjA-Wcb4!I>$)}aw5KC1(g3AXv1>oJLVW)Vw^dGj|YbH;`40@bl|vf z^`sB!a}Zl<*v=V@DRH|zcXaPc!Y7CN{$14t`5e#bs4p2~<;@?DeDV-vMeNUV520KK z%5|VzGR6;eFMRl8BYt|9Kwd2J@{otV_&B1&NaQ=H-$DH$=)(HLz33c&0puS}#3x(P z12yZrh8)9l&_LV4v&-diz>{$d&ra|>4xYzdo-lY)dhtAN+>t`vQD;;?*5840t5I&X zTP^_mq`CI-z&`z|pYNh9qiS83FPtrHb=b92b@3hD2OVRtgIGcv&_;|atS5lK!(opE z)E7n?`o`7ZZ!YqjV{~w!!?!_vvXl+pCa(O&c)_3I`!?OpmV>@`Z zyF3Qu=-?aBi|<+ejuiA;9OFTxpSC0Kc(%C}^5#I^99Q14wmBGnK57%{{2SLUHSiy& z2>t`x=xB31>N7O0(m)zdL`*fOe{1Kk4Pp|3^Cu;2X9Z3oKj zaK~N^`p7)H25>DdY%0Ui)?;ErJ>o(LF`)*ZpW(9-pX=~> z2%nGf5isH?d``k=2|f?tvk#wvFvv)J+VQy-pI7kt44;Gb1s~;ePU85UgE<{>O|R+b zY%05>+h|pBF%n~Ddhh6-*&m?iSez=(5O{Uh(_minW7KCtHE!}r{ALmu$ArHXzb z=po<(F5Uu+7_oJai#vfaCbqui;+-g;2K<_fzXLrPI3u>P>nYHJNI&V)9tTDY+PdAv z4*_G%u=RcycRtv$$pStdWhXz-u?g<9bqms0-E&8G=K~$p1vb-d;4?qZM;l z8uU)XJV%`o<0M~9FTO^|U>y7E$Pr01hWE%X2aWdl)TOab+JkfEvzVJG(}B%72RRtS zY$xZYNV{jbHua*+2Fyv37)2Q$y7L=lc>HNy!;lxTRm67B9ai#ne@Yi)I_toiH_iYq z$Gk|nfv~Du3v=x}qiZAPQ|e5cILFWsdg9tquL<2vlxN+?>O8!c&TnC^=&f@#%D#ko zhvjO}&zLjgB5kD{>U{%sMjzK`DP5c8T%-D!x>AL#Tg)4gw#7j=uD_O`?0(D%T&t%6@4?)_HK#zD zYjMs~Y&+MaPog~6WU%#vlyiaeTvsgG2Klldu*d1b`mbA{jTq-~;FJDEKI|K!e95#G zFnQTO2Qe=-L5C)HUgG?Ate!i;!}%?uXZe58lWk6N+e{lgj&|pBuXyRv`=~QCP0Jgh zYoV7hnLVd#;}7ZDjwVC%-RaQ=V&}SXr$>8m7*<8B>8-50z&w>3~@wptIOYq_TMyu)Q+|bBA zx*@91YUr~X`m8=mA4O*yBl^w;oqiV4DWZo4eaf{pa&M}IH+TC3f9uu*!M$kfKp*2c z`dh}3Kz4Tp`nos&vHP9tpywgzUXAf{kovmoj%4n0pu0Bbx~Sgp;ckI3C9-<#7-&@I z0IXAkkD1}Y-JbBeJ(knaIZ)Q!*u{0(9&P>J33K+y{px;abN4Rv75F>ff-Tra%)cLN zIDffSd#l?Fun({AUK7*N`E202ZjZU9^Cq;@qp#^&qpj&`4Xo?t-aQZNoUpd8dr8f@ z?x=0%$TJ;TALX*HC9G=>#v|&ZZJ7^m{aDjZmGfLf;6}OE6*|^SfwgyL7`r5M%gl8o>=?uSzhH%~_%&X#1J ziP$Uo!p|p>SMjMl9eLzsUhgv|)>(==^H66V>g2f&?Zy6$VgI^w`Q6_i`DFDmZGI4K zUWxW{{`Lksk~Ey@c%2T<^O!dc*k0%xyFE@v=QF?ow4Zx)%GPQc_acf63JxD5e~DG%-)7W(3qF(`sKFcspNr@osCk;_Wax98g*~dT-M(F0 z&$O>snt1y*YfULC;=h^rd%x$=HEB?S`8zN;ABcH$%@P=C`-9e+m*CiEt&dytAr>y% zw?DMzemE8BGqJ$i{ws6Mc1+TK$k~Cv4?+$s0>15Q9(Vt;j_up;UlaK|zqPn1yy~ol z&FyE+Z&|ir@j}hbXNp;+AEjSB4A26(K8lMzK%W|h_`C>@X+Lq6c2rI2EF0QRBA5}aqTwYsTQeIwCKd!#4LYuo} z@!Yo2E86B&t}Ln;KcTfG91b@PYnnf-sSTgjVTYd~3zXzOWXR z*H37z4~HlG-%Bkjt1D|o{Y8CYEvsz}mxN3Dz&di|NJ=g318YfbU26sY^?@}!zP`1- zwyd^KtRum$pvmo31WvUo7CV7WYY4sX$+K{U4eI);@Sv5p^vuEvxUNuH~gg zebu$Rq_(`TQcKGFYOL~-(mpFtJfUx%1q&2c^tEHli_6CKwOPf*eP=D|v$2XM^x0TN z^`rW#Yf*jQrH=2ruC?R)tUzs9pIIyV65gb17me(*YZsOFxwnc+`xc1cSw$s%*R`as z&lV^e*;m%^gg)CfT-Rp>!sGjFf$*rlvzGN;*O7ghVWba)NA`JehfDhG1L1IAn^jcS zr#Y6o78UiGH9VoBPmyrk$ky8Nqxv)#)Q)S#gwQ9?sx51+tu5|DZ-pmdnNt)F{|~Hv z=-7zVK6Grjd_o-;Bz@?uaCv=M>&TIP>4Na6(vfUdAM6?~EwA8`tWT_?idw^E|8<$u z)QpvJlUzWmB`8;~OXn_JJb!d?VOe2GabZQl!g=#bo3K`OT9-FBFKumimbNsVwPM+l zmbpz%?ewWDM>$$`$(X@y&fvC6e4GNOWktKwvH&aQr7g?PFO1WwM}h3pPFCyd_7<#p zmo+(R&)_U?K6gcPTYG*aF*>|z@G7Tm@z0w_4{kzc+lnRaNX5lzYH8dy0!!WzO63u1 z!%;Z@sCu}%cTnP}Ow`uCyk&_q+JXGS;#Egek5R4fI<+iVptUSJs;2f8%a?K2Aon=1 z%F#8=o4W$7n%mwCO^(&EX>R*mXWruWHqb^MU92~$?7x#n{dZFNekn`}t_tv=gV* z{}=OXU-TubH@LX=coNTqq)6Z4uq)7W9VZ{a|lF5jf)c9LD$^m9OaD8yz{XY zUx{6Iw2T_{?pE1pYH4okUBqc$)ZEK4<#>w9jx@ZSy}@wSjKJasscAoT=15TbKPVL~ z-l#mBGJC6oqCG8$GWXOK?UVndE*WcahSDUPur$(DbOMIA(pAU(6RlkqKMw=4`TuG8 zqeZnXTA{kSi9un-@_7t;M^6kr5w=-P11Hx`pZOE61#=fKfx#H{=Pg~VWXfhjX1>$B zd^t`?j*XfzkK@1 zy>lq<2Os;V_dk#JMnBI_%D&OhJWihXCwcbH%C5Y zIGS(naq{$oJv>ZNo^hN!&vEk1pX9v|_-P%l2hRRUy$>hdeDksOo}7Y58b|%}XlM8L z;CV;ye;)1a{(A2Wq&?c_Y5n#bo$1l4YqcAW&3j`2u5SNN|I}pjKNb1^ng0(KU?1Zi z68cQjCQdt9%c%e6te4jwxMX_w73~){ai$lII zk{_R<5Ajos-;#wAlJxj^5}9WwL?vLarS%&rSpvv)%QH8aqN6>@EUJ@)qYBYZ+GB{{ku55>dUa+6K-8%!dsrtW zDds9S%cAX6R<&D1Dm>a1Cc&7}UXsTGL?ze6xfD&SjYlLL=W@zo;|V4umHGw7M_o^a zs=E5#N(J>qy~azgnb6Y;0|RYhPt}ACJ(Uwq>P3b7oDiwd0GOPv7bQ{dtoYNUeWqAi zQIddpr!qm7X=LG$CX1$>DDxq7Gbz|P_vgI zAUhHrb0RZEsP~*QxTgu4mfO24=>S9M0C_$AtsG!z4;%Y?SPvZQmk#jx6PRpKk`rt_ zzV(EGn)Y&@%#mLXJe&Uv(__Ybi-b8GU*qtx_@!&ezT_0l#^#BDF}QV&H(7k?Q!yX^ z6Sq*Tqy;j^TQmVV%dr@+l2<97%OJ@2)@0=LzmhqIRZxkX{WFl0daKNdnVO57R0y*M zY(q}0X)RvXuKE6fYOH~*->0EkEB#fn`z%aDnhzInH7nyinG=&R2@8M~<(f5|wZ^R| zD$}e&3Xf|mDb}norN*sbvWVj1+R92btAyg>RxnvgIldRMfbsfR%=cgelBp)F60c9h zx1SO;-==A3ywcjVhK@$g(*?*GNUHC%3M4b6x_hP|nJIJ67=>ikbja|1TZ3edOuh{D zV?vT)aXylRne>{ptM7C)CT5tF^O=F>neL z_w07$Nqg->LOQ9Xoc5atHWWPuy(;N3T0$T;r2)_$g~r78r>+odSNB4uUE2%!>^%F@6g~WKFp=DLx08OBzRA3Q3ANMU=I2! zFE;Ua0D%R|wAiFKkb>U*7s~C?6)v@;zJ6qH|&d`M|_@w8w~q%yrdOBRKcs@HGf4htlX5>WNHHh z%!_)$rywuo@j5UU{hi7Le-+ZStKuupW&PhH8pKyJiTX7Ys%dK@GP1ScUs1($H0c?Tl=Ks1ML)v{RQzPhKxvHlC*x;)%hJ2XBY!57Y-m<3(8)HMi-zj< zVvM}_Q$iAM*OeM1$^p<%e!IEkk=P@@(QK+*8p+i)-mT*CM1jEk))kt+ z+|}7Wn^G!VrR^GOQ_1_d(As_sz2mP^v?=!M2)X|1!%|A4{m}_Pqm?dm?9tPJ#<16o zoF@BC#ACm74^K{qVXqtuSVJfDoSVcL>MtM;ZG*U1E49+!RcngbLMLhfo2LCB;k44*=VPD^JKssE)0n8%K`svZj)t` zMHQSq;dK|L2|czK6ynQ~y`Up5g*g-6a7Bg0$}+&6=9u-YH!mGGJrmwELzfbT({XV$ z;jiX+XpHvh0-FFWq0^L0hMbpl@ibmtO!$`+<;i(X7qj8k3H!_~Y2@Fji*?X1;Vbj+ z{fOVvg_Z>TAM?=p#JlzMrAxJhZ_HEM2@mSx8+2F{f2E5zsOfjIS)QD4b@2{W{ocig zb#dS1UU-cmh7JTi?9$g8;vB@Jgdbh?HW(Sp;5rFMBsTR-PtH|FhJi^cK@Bid&yZQ2 z)WVRX&D7In7DsV{*Ub{lN^f192MT)f#MmSQaw#W#6G^)TR37Du5c=T?sxOc#&f4v+Yj`j=arC_Op%c*N`);0hN% z!5DVW$`*MLBtmmb@H<)7IMBo#wmnFW+6ooT@Pqa8<(H>Jg z!~Tfi4pU5^{ijPM z&am#3>h3hf_#EJ~tbfbyeG7On@La1~^6xUm`-Q;stWPA~ZHhl~Xf#HA9Z%Z%uJIuZUrTwwB`BD%)}=pWi5KbKms&feeBgEC zfiJiIDEXhV#1kC8S6MqGe%2B19{yq};G1s2EE%B-i{J8a%r0=oB!weTs zSpSgy`=KQosPCUGZ3E>2H~N5IafkbUOI%2Ie%10z`aw&aKMnY8i?a=ezm>jx{t7MO z9c#CY+}~Ql%l_JJbwX_ncdsbR1@5v|OZ%+%itTjY1Fn7>z2YExGT~DfZ}y6l^MF6M zew6NdlUE!X18jNS;q1lIkkfu5r*EuD52AJEQgpc={4&h;!_Tr{qhi{bBaoGemkKo7 zVQ;65$GX(c`V7oka38$DXNP8i#r8u38^@uXxHNkL3fs99#|3q8bs-kJ_RuwC3>4sN z*fx~s%4lAzW)EjR`Ak;EAtrUuwcy9l&#?;`rBwy)a$2)rJ{eg>Y!8>=FTz}Qu|huk z7I>XqO06(;Yr$tqpk==#+QQCagpma)0zW{b^-DLV zB8>u?^NWd;<;V;ng=IyE;t=ZTmu1Y5yc9x0lhd&*9B`U~nZ6s~qJgYM zfY~z<9ki2{=?PjenM1}t7p%dQGmvDhzDp(pI%@#I5&B(}WAKs)$IXZz!SG#xzVqSA ziC5FJd?yXSUPHW#++f^P^gxo6iE$|xdr4X2R1ery=(407Mgm&$4g}Ps5ZSoc(v7YlK6<-84`*wUKm9UMp zzZ74p#Diy)0I}?3uz1aD@tq^Zd(B&r4(YzzFl8lQ$=A2#smqf{NI$_T{KGK4nRc%J zG4gV&;Cou`6!e^)`#NjN{TlW)a`Qm+0Y(Sq#qHi!nD@xmTiNy}376;CLkW?jop?`)jl{ zHg|x9t#58Q{5n4OVvKEn?pDT@TpPo{&P{@I^vgZZfve^&haSP)dPJ7Q+z;p&x$9uv zJ#h7JH7$$YI{+;BU1)I7VR;%a>JgMv7a8H zhGh}X)n1dn>DzOJuhH5{@7Cb%P3o`DRQ zsLnuqsxaF|!CG)7iung-Uch3pwRo@Axm%Kyb_282SXJ5$%vK_?MB0S|2XjyY_wIHY zmNSDA?uSw^qvkt=UKx}?f${po_>Ro3cOo5Zgd6(B0InSEhex0jyHrQn)Kwm#2X{+qR2yq$TOp;bw zZO0>MWPD2`kLnH;0UjzGLbzVH@2v+sd^_ZLayIDp6As`H4@h{GZhtru@JAJIHtOl; zv}zf;{>=h1Z^rq>R8S2!9Nnagt%%_nmWyx2@yP^Wudal5=t76xGh%cl{T^N9!n_&r zF8zL8d>IGqcj*u5Vn#M_f-4WlH4o+k2VDHPE*>I(&@KNY_*s9VTmC6sOkw@~UHY@S zSjfhuy7V2oNJAXTNOR@k_-7@Ik}=4|IR5z!#$txh-;>tB@z03}hZ&jr74QIg{BwIQ zaJD{Fns%2i{sTj040iEuU3^FT#oGnVa}?6&twL)^{&J<*l- zlp##|Xp@|maVBAiyD&RsEYwxd#2HRU0`S>7SD-j@qNdaxjj9ZE45ESI5tZZD!0Fj z0V-pdGIFYA5HQ^^TO-4cS*Zd3WI}L!4uH;KC_v}eD=Nlz`Q^;M6-wF0WDOjBMfH2iT#;b12e#QDS}C6 zw$fY+EWw-gnK=rXQuE9Z*1?fErVqf!uHuIptUMm zx&1r%YUa5L)!3;-%P~A5rNN#>v$UO&O*F;+GrBjk{Y}hjMoy!B0P1J1UUXpZx)p&kmBi>Vm%&OeQO$y_5|h5?-q3?6I365>wS+}Y#8MsaopV5bXb zi9v`@&R%1_EIUUm83NelYSko8umC?aZk485B;I7%Zey@i<7_dE?fsXbx_^my8neH% z&){*Uk+TH9;{&+g;L?M$o=B_({>a!do_Hf7@dV(Hjrr&(IkSDA4g870PQq!oE?Tfn zaSj+4fDH?OUF>BmKQ*2hO^liCAGGIZ#vdfc%=QR;!#QZImHde0=b$5-(cDwTYrwY z4MQa|?PQLeD<(1AXS?S*u_X zL<8}2Kj2Uo2E}yjE1Y4La_2NL8nZXO4Y*4ZZEOuzeY}t__qmI zDi7-sQN-=AnKM$J#p9WtD1gzNG8ZlquXDVPl1HN)3fm~E%9cf${FWA1;99Zne;mATIt?cA@0Grck10^ zVT_}dLEs5iGb)$k=q+r^oQbYHjH452-v;X=Ohj0b=%N}c2ImA<{(eKWVZb_*Ewv59 zQ=d~YPdHPpbELel4DmI_g>z!$7~Ug%v`nLQt#ofZg}J*B_!Rdk2cE)Q!t$rP$Lx5j z@}vzs$5JaIJXHx{nsgSp_$d#3ZV`M=J}}$|Pm@#Y5ck;bFf#n?Fh5gZHQ=a;?;}iM zP9?WG-OE9)Vq*$yoNK(M4WJk}E_xXJF4u@Cog+okQR+mb<8_XfNKUiN;fPT(ICFsU zJY=NGl^KVRBC(a~f|1v}2D!n#7+=1u7;a1hOK}q_%l96V9KW1{vtpGuV&gf)l8qu` z@Ca<%m_6p+TohWotVPQntEK`ifVc9r>>792**07$yH)_o-34C?jaC!BY13~)V<>}bnwQqJsGoD3g4b`iRbY}2o zOlX425X|^bEHWmlj6ujiL+A}&la}$CY>3zFhvo;*fetfMF8d5=dn+dUl*{?7oDPN` zeAiMosQxkSGW2rF6$<(6WfmacuD9A~0{o0xi_O8bo<=!6!YT6^gn(sF^e%i83f>s!MoR z0}mYs0Y_pmun@KUp;bGOXRjTA!sq`3Nmj(etI*HClE}2*$^yDzptJ+WE2|)us*e||D%Ss~VySL1`*AE1hNPhkboATln5>5kP$+&}h~W2vKpD5n!nnIN_dIP#rb1qA2!5YHGxNMBqgd{lh;~};cUWQQx$mR9jNH@V z4|r^`9}y{#S9~Ry0?U@;S~5)yYXz3IX?Y_zBAZe70IZW&rZ#y#Eing94r8&B&9sxd5&Kt`;Db6(QO_;#)Y7R-7&`d6v z2&D7j_?0b)EpRdHk&3wC&#Ny+mK{XH@+KL2pt~$t1_Vd5+dL5B!ztTh47={DGCK_6ZRb5pM^M!42GeGr*hlEvyDyI zB@9pV782#Fi;M))7&v<-TmJ~=ox`fNTxXHUDh2{AiR(k-KEFksnar^>>VV|`{lZIk*I=;bpQ~t#?3b~M%3ppRqA8Z= z_G{?*{5I<%qIP=_TqVCH*AL;#Y_x&NI5}5aLgh0H4*>V$2ltFvU54($)IQCyEe}o#%A50P~CK(8zgSSB(yc zI~xFZ=xSk=CJgB9yx>Ad6v61upIw+I@J^5B{6$wC6vj>#v0{~Tm4_MW3vis`Z1yaj z$hK;t2zGaF@N9!QFcQRBNq{$bxFzSlY~d+@H+z(WCyO`W6wX!;pCs|I-8B4lZjsws zc&CWtw&GR~m;E@!5tpI{=QfXOfg|#%)a{cVwVkgpWOc%Ig7-{h$_yn3@e0CusW5H5|0`^Lny>w>{|Tf;J97tb4WK=NRs31sDIFs^lhuv_>)F{s-KrV68$vdpa6Y zaEU4wu!q4U1?v<_)`AzIhgu7Z`y-^;$>^TKlAlTWn#}{b!cv8Fd+AJ|k=IF@VgI5A zs7whl?U68g;iyP;f5dPsELSLCUj~yGRw#s)p9EB?kYhhN8K_F3Jo}fhQDL=0VS6on zqHy%xvc7Wr6g0JPtU}dxQ3$9;=~82VlMGa=&^VjRxx#UZv(6p|4=x<9WH#7$VNe&= zDb#2mBC1ztmK|RWG(nY{W3NmEny6$p+0RgB!^KjU1@PsfTO!7Lh~~Ocp&I*L_5;`-#7d0*rGX-TTBS zw51^4g#j^)Zs>Pmn#e#*D@f4Qp`Ih!=(4u1=I(N_6?zr)(|I<)al8YjEC}d45W+HE zBxC~y-3ZtqR&hKfxh14oVKLGuWoH_W7-IIZT zBi~;+0qg04-@XdQ;K|Ugrr?G1MxsyTF#mI>EZ`3F7Zq}c`AZ4~>~F?Hz{?7ysX_mW zLXH~ruPT(M2K{Rah1H<{%T(!7f0I0yslgyKSFX7Y{g77Q`|W z&cx<8#jvs{5cFmko+zSyN?e#P_=KpS z)P-R&lwCK{wO*-c;P@Hk>Rc}V4TmeJaFwhU_fU;0JqD{6Ogmy7$Ilo&N5VSSVl;+- zFY1gKla^A(q+uip#w?2F(mtvHT`f{-VwAp`booU(ie7?@7+c_DBKO)lt&Z zQ4&)iacSx`@0SehTiWsH{zpc6cSonCEsCb?h;T z>=b|Rb49jCbt=_Ah7*nFy5P|tSr_vlgbOII`6PhXoX+812ieaStk&mZB9Yg+ z3NDPUwzucNa2L7LmMLr#@M0GV@ggJ58eJXjm&%Lp1#6`o4xN1kpkAV%3$ZwUN^fax z!%9qF3y8-x*jjM_kr>%(arPlKf*D)6wQzB803xPuMBw+xvfr-Jv=NCaQfu~n3n-~c zm$4YldKN4(EIQnD3XFY71*5Ufa7Gv`trZ5GVMYN0geXiy?r=kGZ8X74 zg-*T;&Gfm;7vhnJ!MovH;g5!0oFexElwTY1IwGr6EUWUG6z41&fS(?4Mj2DEpca2( zjpfEtxwzKEqtM=|Fg8eNigNUbQ)%!D3T1D=>dzT%{0@KkkmnLAQe(U!VL+UZ0PKu2 zzLGFmT!;|s)EkAEFSvV{Hv_Q2m?xnS`=$X-H7=CU5&N+Eb*34-(aL8&kNW^mG;WgA zJduL&<}@15NtiE;lK`h12P6!OZ^M8m8-A$HN2hmY0-ow>RW9&Cy5`I>@+Gxe(9F*1 z#zYBg+)*+Y?NhgGnL;-$#Gk|yz=OjLnn?{NTE)*zmgEIn8#3Z`S|^foO_Z726~Fv) zW%4nm(*ol(IA==}iU+W^a?X*Dp*exQf`z2B#K=YX;KcnmIF+;1efAm<%_jgZbD!G= z#N8QyEyf|qoGikHfUWL>X(7hO0-o!Z4T*bjlHe?N%Z9}4big+Ev2~ufaXetV3-iS& zEJK_X##CvcupD;IN|#zHUrBJzGtQLMa&Z=$u*$8dT8tV9c)qI!R*Mw%bNN6Qt3?>B zBWfNxO~h!=AgwG+-%%Epmg5b0Kf?%${yoZ+hkozH#0{uqQeTpq4i`rmUR=bPV6-Hi z@4uIn*R18x!!rYLrs}gGnjWh9kqF`zNzyi?>7L4Mc$Ns#I!WR&G+kB2Z64A185#Ui zQS=u%Z;uM07c2QBsWMdG&l{iMd@0K5uZeI5^1|VeWTpN<^+QE`46r zSa;|jCmWm^o zvYo43=5lcZEaF@vRbmwX0>Q$$*7fQ-F%%0gXQOco6y~Lfa!w%EyVNOyk5-&buH;6s z6?>=!@0q&XqHH$SKsRT{2cLDIFNIPTeeADkGaLU({0frSg;8#PHYKC zved>H_ZIlpipE9I><}#;=ms!#0))SH{#5If*2d#G{bj0P1BVSnG zNf;8|69K=pQeb$VExkoA`N}GiFkeiDot*zz<0TA>4H!Jm*OuBAl!{cg@f#PGix1g^ zZ>=*WbG0~u)I-*K32Q_cHgLYPo{+Fk{E2?>z4fky4dTZ-z{A#e5>62>ul6uRiPc$vx_7OFvtj#JP*uz{dgU#cp%*!?SnNT;`@hbs zmg-wvM`GJvvz%$F1FoRXZjdk_a^nGax-eN(av;8G zJt3)Sf^Y6Sf3*R|A&U@CU5;lnG9H#H%y)`O1Mf|21@B?dtgpJ}^ws(&;Tf&**k94U{x9lw8uS%3BVRk_>FP>$ zPoAlsU^oK*ks2=0$SeI^AKlH4A7*kb!n=722=4V(y z7zmsAZ8WSgQ()Bj)(7p!CdlnXlIE>HA)kFF6Aus@NpKbm(KeN&N5Hr z!2AaGUj+Ka*K9?LXB$QUPOfpX&Y|F}kO$p@&(55c@n(PQo-oPljP&LSuH!zAW%91pneF6Hc=we0l+kZu{ELx*z0h>)P zTB~Tub_ju`=n_Rsvwu4UXq}=7`;V+|y`nkxH(1yeT{=#hC}dX@0A0qXU3{AK5_+=e za)rY7OvII<4GNXpi5WmwC{$zL$r?6KJ)h+o?4NmoZdkpVXo`GXSF}YvuA@6_M5AM9 zo)L5CDISv#GQ8$}_)aXtz|ozBXs^$)%zq$DoJ+sO`({Y9pU$D9#+ZjCBO72Ax)vXV*&jUq2iK$fC=W)lIl|$*scbC zr9nTJIUsmb%n7(KSu7d>7<47$0SG6!M3aFYL)2YWvD%|lrcP?X#X5UPk*)CEQTi^@ z^!+<5J(C?JV@vUa}QEv27KSbe_%il@BvQ8Twa7xU3 zP@v#ad^x4&hfuR%Dz_3N%^}FjpNqH6oeFar(%8#kq6;{>#i%3r;)-Lqcjq)Q7cSv= zTxg0!4s=s;a{c%+OrPosTn#$w(Sx+rl-U^NN>O2jzQI&Z}PJ zOFwv?(f2j43K*uipPK%~`{qnied19Dfj7Jl$obf>rrn)hHSGrEJG0K4QY<6)Uocjk zzk1c8Doy+z6Snh~_dFTZ9I>Sk@b6JL6G7Q|CknT4ir5u}kDdbfk0^YP(f8d5MBC!f z5~qJM9z-}vUS5HeCznpL_eQCyCMGjnrFhk9#}qRduTx#<6I(Faoiwjn{P@LhX`cZu zH6Uhl8XxGwWHAH7-WlZDAWh_QPze_bu{akn-K&m)9dRmjaWcHmNHsztk<(SC3-iQh zen7|jFGw9LFMi76J3n6YJ$$Rk;hl!aFcgmLr#Guj zq1-<5iK*HVr^?4HTo|eytt8XgA&AA*b*K6$od+NCrjws}U}6Cr0!CT6id3Rxojh%d zu$~lU;@Z;RzYt$?OFNv}Q4l1pluX-@<`Pp$l1+FO%>w-vNgs#w&M2KJklx0h#3DF0 zdgc$3Z5#5r7FFlHj0I|U&k9jsuVmt#Ij&GuU6dTz^u{1pS(0m1MURC~qUew)iR;xK z`5=vplDKwNrMP$l>5M3e3s*&ww^FGn=&Pc1u4I*kT+&TZ5?8gVFJ*&V`eRW#m$^zb zNs$TfZ<5YK1<@Fx%U!-?igr_Edihea(@tC$D{-=$j{btq*`O;U%_gU-&J>x;>bO+) zch*LPNLP~8(b6bCFUrYPw5mxm$uhk;uacasfD3HJ$JKBrMy%_v`R0#K{J@<4YcX$UOS2dR#)}HdHzbZ=N=Cy|;M<3{?MCshk_M*Es zTN$NuKYI+_&)qkKY>6^)m)nbJFPaol@()oa?tOoHqj-;`b69aRtmtn0HDtu=+!Xg@ zN8Z64Bx#&8WWCU46w=BX+zP7_?gN@hQPM>u@wT#}6QXDrGH~b-<=RFr*5`)IUU-xXV^d(Z~h*9!aNQZo7MgfTSSMs0@g1 zY#M}I_3Lxok1INbs53d2X_RDQ_61QUnUX=5U#NwX0e&7&va%XZ%kpstaxX_ZUgwe` zl5?Bnqe#x1k=#e3x$iPpnvN-m*n>Zb_hF(!Bzz&t#@|~~&s1cJ1_3X{;w9iH*AQ~a zFLoJ71;|LOfq5Y;5ot9ga3)p4qy?hZjl}VaC?_Y`UYxRbWyiV(n=d&jh4ZiCl#$6j z4!t@`=c>!kMVbnKQj+X;SJQ_<_x&Lrzxgcp!@eA>&PwFe>1)S%L5Y_k$9#ueSkXvA zBJS!YW7S!bekro-nZ;ns_!JzNitSMdb|sk#nRb!`b;Ni*#*_Ex3w3VF5QA;7@M*nU_P+7>p^Bjc}gh3v#~ccfn-!yaP;C6J9m-o;Eg z(pEHEGnvQ)Nt(sP?~Roe)lr}W5oIF}DS?5u=J`=%Y6Hh%Uh|a|E&yZ7{%kOg=m)RL zY+tFBjiNBk_d^+St0*bh58aVA%D)3?o7d$>C8(t^eqsmf*HJdC4aI!+9vs_^3hV?M zudwoA)~KMO1?+>Een%zkmb7FH6LLkSYYI+WpjKvYBklVF$4}+KPm%PRU*bDnKZ0*R zzmQ{{3Y}g;R|U!kR3j~GDj&EbzAx#6^GuGv^=|D8qjwN<=Z^OtN8wFNekONw5#}G&>U)AY9Gu5I#MoC zxoAd@R%p5sS}krK0I0jLM!aAF8ZNAprz;g67dD7r#Di+OaEdsCm0J1?DY;SnmbH3a z>P*oeo?8*)!dYT3T(`ofpDmeZi)6xBeXWFZL_Mt#rz`U{iJRfT74iDLlDbH2DFsZ> zUzBi(xQk_NeZPdQ;(Y|>ie#OKsJtbZR+Ok|hdq`1+Rs1-asyhqpOK0^%{%^;AE}o$ zO#1@#c;&~N!3GzWhv}7{c;^!N<=0nouyo5`7Pe+s9l z{6f*fb`BO{m0zlBl@0d4G0H3dQ!Ev2us^BoK~ro-fXc7;N?N15GGF=48B*p<`@1U8 zzU65dU!SxeprVHqyh)cYP*;A(;l-D}*I#>IHq^VwWrpUz<|U+yf31CDjyr^oyJ+u$gbaW2OD z{4vx|-HwCh46&c|WLMw&jf^!#z$toc5ft$#xsg|lqm@uxle+G@p?% z7a=N|Mf({Uzs4rKvcD^y1~f7@r64QS&C;1A>JV8g({xT8o}6ul_&Y*Z!Iv;qbi?_#! zp;%H>4s-EKG2)NZcetzHo*1!|PLdyKPmJhKdll#$q0m1@^cw;^!gU(pa~Uwg`h+IZ zzm37tiT=uupOKB)k_~hvY21eCcc->w6 zivihj>zySg=KyB8aCSO>X`v$9g>%Gpg`noRmol5gIqHtz ziV-fxi>Ys-y%k}1Xg;LNi#Zi#I-{`+9jyZNQS#<0LkFzR=&rUgoR3xCu$MpzAR}Jq z#C%ltaAc?woM!y8OOJ$QiE*+7r|YA#&yd-iDrGinMOw+=jIEgY8w`;>^kq>x=Ws=5 z{6Nurqa;q+5rKb-=5q2@1*p_fhaT@pChnUD&H1lPhrtxDbFNWRm_oJeK^%?&D7|My z88~BrGzJ;*a$Z*D-0ah2_F8!d~ zbzV6t$s|)Z;&V?*JD+y)p{&XuE(k_V&8GW!1Y+wnsSN4HlM~; zt-W8CE48`8s#>RXDYrjK2HNnlq*dGZjRv|>=~5%l^{cK@$JTZ7g~h6CRErwWLELOp zPuX{{7!BlZ0wcNVFotnF@){%^75)%qWn)z5%N~|~?(WtXD<%}6=DnEQbG>Vj8?RGy zMU!RahLbv?mTe#fvk>}xRo8usv|N5wUC$(Y?`Ol%)=jS&viHCqM2`nY)*!Z4R$YMg zf&8hK%4#ObUW4#bIoj=Pdp$$?7`BXCljWq1jdV625LVVG6tEw_EKpgiP_pdM%5e&% z$*o0Y-C9|LfC@iCo_u!7^@;p(87+94+?7zH+c}L)QtQAx`)P#7 z$`h2fdA5dNRykRreEVXI_R1*=h3y@1xXP(Yhf*#0w*r`^@(*R0jqEcylRce|iI^2! z#Ch+TQi)8t!>D|2fcDtD?CbiQ2{3-qSyy*m5AG@!qZlbj9q`?WxSQwYEO!usA)weyiA ztrV}*B(kBAn4E)*c%9aWw7(K*Tr|aZ47(1$1IoT-gyXVF?xx48zUHz=;uwXmj^K+m z-{@@I(n)>-rF^GjQBj?89g`uPQ&snuxeb^Ys?(SZmZ9$g)ej9^fPNeRr>TB;8ziwG zC#L{yqg-zAUyBENMA7hbrs)0Z?Hrcek~|4}RX?gwg8d_$y!zKS$#S;lI}^*W>c@Tu zSeRFxrN4lRL?Z%CH70yjlNeSHnBziIOvbrMH5O))>J!(nuEDxe#4ldNva32*zgtoR zqSyf(;xZ?TZ~6n~xiC!(OamP1LLu;SuvR_Hg^pMUm#!Y}!jLv%aUpQNJ{T(c9ykgA zM?=nTByqHlZ#A{>7tz%752ir+0e^x6&_T(ghs|0D8#20&9*!X(ZD@@J%KuCv^&fYP zE>Ose(~ov-bm5y2z)jvlq7f7Ui}t@r{talpyUHM7@O(hr|G>9WgJgC4TB?y`jt<|C zEd1K=LTxl(H^;9KwJ+C37r&`;kt`X#2-(54u#azaIrHsH5XweZD4*5rGIa3hN;guW zws*i1L#e^ki8yK*J%$1TOXsfAM%TDynlmP{95YfoW`_Ldo`Z zB|u5mV#-XjCu0naO;$+Q$xwT2ib4()rb8zl#AX5uf+JLJ{S25mBZt4=XFq_Em@yc` zLn=q#$jF@}5q`6o!@3S!au`=>!QF_yPDar$S#T&EH=~%puE19DHwH3FUI2l^E#Cnu z{aB)a{VH0OQKp|w8Z@5-G%8i1G#SA&%7;qC%K@BxpFugl{NfZXy$G$K9$u4GD=td! z#We}4MkeD|L5kN|pv%6nlKu3NnfH#BT;ByIa}XLQB=}rnuR*^WNQIA`D^rLWh3F9?bJzZ1J-D9@ zXEL|`Qe?{7T!0>DZj*+5&h>KuHEYQ4`~yZYw?#wA&K0?U)@dl<%!JpTi<>9NCDmDj zmOQszLqX^2JU|^93OP}{TF=GFCTU$|xA^Etl>s6glIbXrE75z;^mh)#cw4&GA!P+;%CxRCJUB~%F z(4v26C`kk@dR;@wjt@mDdP74gqL`vLHJ5-WrsypVr8+++DB854$Z|X22A84cu^1l>s5em#DquqEWsZ;!@=Jj;Nr~2DIEY^N@6m0gV)64QRVQ zbnZpte7f=YvGoAHG*GnKm)qeLFLos3HF3sw(Vo`E85hvh>*9>dPXJhNK);(yoi`XT z$vux&(`dkCw}_=}GGK}tbqb2>FG{v+AVtpaU`f zeAmjlmTNxHi>vsU0_3beFQ|}AoJJP(FCT*ihh2l9m#n{PB}AM~s*oE45f^nV zG^VWQHRL*{qyl`+NXO4&yrkcNbDgoU+pL#0l;^xgHNSF~@GNwm zWZbJ}!<&;0Kalk|{kk^CxjYTfYg$oroDT~D{ZF}+XrZ%4R1|U>1*C#1n2m_^x}okJ{+Je*9YSGWKr-%D`6&%stgmGwE#%EmeMK4%++{E97;=kmI@VBC{snJMq*ad#5s@Xme46nzQ? zKUubk#}qv$U$c_TlsTs8bJ%uLtU;0+rs(S^OFwT)8+SuR0H<31bmoUC`xoIIvs^hf z1jpq2+~311WgTVseZ+wqTS%r=2xo-_PbgESe~E;95l(5rpNtDp{6N+tHzF*@i)ZcQ zvBUIOdDPRRj6gF1uaikm5u;iAUnltqkR$5}ZM(P+k+$@E60ubsV$uI_4;0158noDk zLTroP2V!!-G936UnR^MN%ra^kjU(651|cs|$^P3w7q|k>bAcXp{tVfKjz6;&k!K@c0 zZXf<;v|!8>S-5T3Mr3+03+zt08)#~H0W`hvRNWl>&LwEJ3r~AW;sVY_*wVt&DH0W! zaTkgmS-5>Bn51{ts)aiaY94CvK(s!8Ny=)(WIc$iN&@sBSyfdC_M`7qfxjb*l2oP* z2TCSfOhIbU@0CnkiNa8jOJQgwlXy@At2&%sGVL`I4S=I8nSO~OnwBM zlF>I`ijKErCS@S>54fC?S(*|zUqBM|KBDy8S~yfP=jctI2y>4Rp~#4!`OP!@a3f~P z@$K;>3y(;$$V=h`k!gv}G~nDn2T%}2k!a;!5@q7uw4{b}^dL%)HP)+=6O9s7|DKZZ&Sq#^w2?2tN2%<|Ehul+p#=!e zroNAk;YPiZVrn7lCUiz6i>ZRFoVf^|z@lX}!sJR;Q7k3PfQEvtGzb?5cVi@RdP!~_ zP|jA0Ge!%5lixsIGS-OW>_neeGR{-M2k4SYPGT8oL4iMER93Q@Y_p%53Vz{-eB2P= z(*D8^`%EixzaIeb5d)h0#r7F6;O;=P4nJzZkesp`e%ydKOBpUayx)Kk_Z9S5;XfEK z>Mn;>g#To=;JNN>*lPF%b4qizY!wN=XwFj3b(5oreaSa_JEhM%s;5bXU-c~#sLkT za4+B&;vdulWxxy%{$~6RWh<<>h$)>s^cxiy-zQA;J-QV?`C8hS-`Oz(ahK?^S-{~f zSQVG*QE1ZZP5Kc1hpG%pAID4i1kdwvzXXuU+xpPcv75}`uAB=e9KB*2#FITo*lT4oN9!s&hu-D=tFeJB-efQ!}tm`qb$*ZShJ-VlRy~=Cgm_lWg!_Ic+-OGdL&2Z@eO&UxWm|HAPIv zBu(CZ94xRi8H5t%-LF+1l9rtJfIbx|U2Yo5d&v6~@jZ%=_lU04Y-h?8K#yvc+0MVn zwfPD>Ntba?ue2Or3+s%YcRLv8c z2tt62OVDJe=iPES!t(Z!cdOQea-Icg-fbH4JL}QT^KR!pd1|bIV%}j~lQS9JcHW)3 z{|fOO$h^CCQPbsnl?O$fuVH|BzhYi^p;5Ba{zd>|J1J^N89IhgQuqz)BOv9(itwA} zOey6i!HtFAk|=m9_exZB_>dX6?nrh0u(R<0m<2sMQel`Ip`_Cc^W(6K6V>B}4_ljn zbKlDW^}Dhr0bQS_*3mK?3b`$j1Tft_l|97= zhB)HB4Hq5}LiH zVLQuEa`O4UAt$*r)%Izbl)f_6Z$RAmxfn^4e6NYUVan$BsGw*#$2aYCBs~K_c(jiK zvFtNK0CRoXiqmEDWq6D^n<1ixWW&20w!)Kq1GghBPZ0@EHvO$~7m(Ey1Nz;5jGZPo zGf{81!+^pwm2D}8$ZXs7!H2KwP;KJ9!rAB8uR zaE%m>?}YBd6mpH|SZ))LyIku;SzKqP?{aPMz15!$^nm47PXT?CFtb>m8I{x?KSCf zX~7Lt+eQOp9oww2fH%nq2q*LU^xd`|j7tkbY(*Y?q0e27K0gj$;?sBAZZ_$!!22Lt zP1u964(@~e1Q_e!Dih*klOU7eh!nSd2pJ_YS9hj8}BsY=ZXkCn@&fs_1~No>Tu zi>-6A|26@m?u|-fi%r^W_Y7ENc!?n%>Ar~OAFeR5xvqmwC0uF1Jol#K z09N^*6wZb29c*DM{I3f**`0wG`f!c^69IYZLoq@rCk{c@}J*M5xkfAj)1jgx$!U{#{fL z2RPxo;v0YWR06!)Xg1*H&~En_eT3XUvS;{}ymhiGxb!H1_Xr>Jc^MqjIDp7p12rSR zTY&KM)aJ(#khaOWChi%Rcl}p9ELv!!KvEC|IZx+b4l4AZiMK*~`=Nw06|QdNzgtzlf$`5+9+CY^)p@apZVW*RVGea4IeBy-Dn^+7QP zfnR1ldIX5N7hwpDHavN4O9wGe3g%hToP)Xm<{-m7(hK3k63h4b%)8N+f%!LMZ-#q8 zI2k1j6rr!EsyGTk9E6U)11)}jn2wNcZ7iIc;;%Zv+5ue7xPbt3jz%IYrvpmy(%mzhV%th%d=V z0Z>T#38M?oL#CVHG)~CXwWgf!mI4~1$LM}1ln-dEUTKTzuy!Q#uNYU#WS67TR^;gl zMWLQYSyzlF!;GWRB#Kw;UwS^Mev7_t#S_n7ASH6<%?I@RHw6OoWI%t=ak#}9DqC?t zLm}q{H24*N)DZ632>^OhLs%^^8qiZ3iaJr$4YLQGFPBl*ALj)@Ms7_UVs+Dya0l&(15X@!JzncQ^A}d>n%iNcl(Ph>!;au(h8U|E-xurez8h1Y&X!Xyn(GuJ2 z?nHB`-f2#~ZFMh519*)!Nn(54b6_IXyRA;)yxF}GzPS1Z>t(nx--ylbWw5U5o8%3} zhx>avP+QeE8&=!g*5d)*Vtow@m20rJp~9+fwGLfE7}xcj3iGMH&06~t!dNBE197Tv zw`fmXB@K1c=7NIoD&R##j`~R%?KURm%{f)t>?b8`vv;8-`f}Q#D?8_wiEOjiq_EA} z3s89qhXtS}S6nTnaSy=Htk`MM_)&2~M`En7Vwd!|ayN;8=(VZ9Tw^e}oW$?mgRE9u zYaJGY4`AyYDAdY+84rxW^iy@t-B6OOnW-L~xMrq0_xy{Phh8&NJ?57JrL%iSfmy*J z`NLIDDD#s*Wb}t(Cs$8mLRrjJJsBoUIh`lbKB}ke5gvXg?^r-nKNcw9C`?gRPsRB3cWwB)SY~8A}rBzoSH(%0? zlvZ6mM^omecfw+eN+l{U9hP6bO2UOG1$Chd$l~e(vIyS#olAhl?r>0LSHe?7s;62k zh07&J)zd7aKbLEcs;66fFBJv4dD$$4^_qa`VDMX{$vB)r2G_9MTK(4^q5kWx5UGs% zci$@z6Mu=sx(j8q5(^74gs5^nGRC82Os+ne8q}4r)l>rR20`Q8rrV~znzs5>y;>;X z3}z*qrYS?t=di-+Gx+AtN)WYg*XoOCweRpMfxF5Rpqu4yJ0p34QRaS>7M*Q35W2dlY|)~(sOz+N6g97-s2$G|t_C)Pu3>WZLnp&E zXjMO~6^L&=Xmiz%Xyy8yYI?Rue+4oQP{jHl)7BqyTJWY&{kUGHmG0EhaXsPL`_sjM ze*afVhwCI*DF@yY$aS`2z+C;uBkcXDBkbMuMq1T>PEhr;UkHmrEILS|34TMtvH^`X~1zTEiys&~T0JdJHS7H=AiH+#B{!v|p%)q{;qopd_rG6Q#ZdPMI?> zfqOWY(+|DJ^hND7G2Af#3G8FM#qz&`iP2Fi8xsP35JmN(ys+_b#}{icG-?( zSEaKX=`kRpyY1B0n=v_8)`48AFFdC-%z9%e_+6GO=hedO5fM2lpX~bY6-s}&=qZ%=Yh%UVL*pF#M6bLyv(%#R3pbzge6BZ)+2^uu! zW-R9pitu~R$77*`<&?t4>_6xomj^hY`Ce*^%gQnaErBK5?;oPRL?<6G6X**c2O5?A zq1g|ob@>U&pf4OT2M(VC&>tU$d`z3S>};$3r|dmxyTdH5lmsJJDtd%$ZbZGiqU+H@ ziI(j)p{upWS*Ic)H_L5g$qTG20NNv-#r4;;{0U~K;Ip{?nYKSs=96(9H7*@ur7^L* zx~3`r#R&5!@X;tN?Ztl+F#N@_cOqH#X((&DeVp|N#JDeIgYz8gjjbZJ%HCUmg|GGk z>%l7#`Njl99`B8>-7)h3E;O^+I7?_0z(vN<1>9eh11zx)i6TR8Kh}S#0mDOIWnGn- z0bLq2GPHFLFpCYwp^lEjFwibH{L|eKMXR)a2{AdLTTJ^|W-Y&(;7IpU=3ZsSyEwCz zu_u_ch3>2q0G?#P$!=H{0{2I#A+JtU>VVIFNSM2?W7ujxY>1V6 zn7V(&`s3Lo_PZ070^Db&%_Ah7iz9SZ#ry%kP z!+50o6z%m7*2rWg&6SrK`;Vr4h4Kz!KWQ~d+Q~;XbQUW6DT^)vA9ar6g^Tu|EZq{C z-CJpU&sZ<5$AfprJ_nxmvsN1tV>It`U#E8dYG6#G{*#sSoYgJym_{AW^v@d@%XZG9 z4|&nruH$X@1lHcmW~cA1wwvt$enl$R9`Q@t6->Mh$#2r zWk9_p>c&P*+dYegc-w3@#toqVqJ6z%VB7%OvmEeY13zfH?_qdlzh^df?z7zy`GDV- z)*y4eVnzQFE5h0-+fBik-~Pnp_pI%%V{`e`I!~1NyzPpA`rM26yYr}|FT|42sQvCU zXgT(m@pYrf6!0%p0JN?$%Q=a6eW3*;}=WRz$ za!0ZaC^J{SC&_(i31G|2P2Zd3uA&k6O#I%Yq1}|nFJC?2<+05@Y3N)(P)P=bN&{*P zb)Rfds5GF4ql>ar3<{M7)Gt_;fI*?sfcl2&?q^V_vf=Yz9jbnjFs$= zk#K(!+!)m7PTJ00<&v$~B6M6P38!lXE`QBl#wzGB-^t%V~Vs6*kqXi7e5w~`oeY}7nm-9Gw zqrFzZbe9u3c9XqXz=$ilZ#H1mwa99n0bO?o8}WJrX1lv7a+}RlUg$61ruBB%H={K4 zHh-n_=@doabk?EiwA~FH;OQQ|dFVR@z;qc5y7=ayYuLoP4F-LDGlrdaApvs;vGWPZ zi89#a3`9yMd=Yj=Kp{bkg%t{5h9IodvCKLhv-M_C$H(KT1RZZ)juywGs1T1~Gs4-Q zK(=)I@Ad%zF4s=j{}4f0S<~3AUpJuN8wL!>yn_9vsY-kX<)xSr`yD&$8gP=K zT`P-c;S#Y{0&-@@HfOi zz#N0e)ZVVOs>i;~|L(QOko)oN+x>d{fe*(E0N&w8wqiTiH~{bT>m>&Pw{kAPy9^j| zc@(^TcYG3DWdC*i3&I<0TlX5!buVP~{zfu|b?E-&x6*cC9q4V8eV?>1EM0QpULhgvk-f~iJk6lr5Aa?h&;=^EC}#He<4~XrqYh;Zo(+hfBkiYirt;` za1R?!3*9xa1N#xb{y<%(D{7wsE8OLDcaQq@V7bcuU;x0!4C89|n#lkkH>_5_b2IbOh7C50h2Z)3VJZ< zLCFmFD-1@`hfHL|y`7RhV!)_d#n^pGj|s6WAJ6T_Ol-C;#^XtP0V}8b{{;i{p93g<{nvY%Et`T|JpuNnFQFgdHyR8&sUY|!NNmY_5_|ENTkDtZfA*tu3s z*>l%p0L^~0X7NimNa39gC~eIWZsSGSWtCD*xh{IO?53@$(7S1?ot?#?T)J75*6B=z zE!3E|uO8=kNKsQofiTtSghl~c-X@gWoF|I_t)LyqGVA*=WT>g8?&Yr7@23D<$&_4X z?VJ|?Si_`TPvp!cxJswRGV49);%iRQX|c>Y32wY*wN8s=);}u*7}II7%=(gYfVDa; zmRbKCWA>W0IxUu2^F^knPN%&UtG!WGHT7@ZztCo}N0PKW^1FM6UyiV0@;2@HV3!LA>7;3r>pyr`iyj5OsG(OILcvYBH7KV9Zzpblyd-6c6x$sA_Q+w+97+Sxc4aqp}YXq9tc7NEl#TH|n- zQS;t|ZSS$ z1LN?g;WWu~1Mjok11{hU1MlZl!@DpP|8Vf5C(CmzMx)8}58R5t*D<1mOen1|xT ztj#{+P~vGa&qy-XU;@EJ)F1@;Oya0+Vd*WaNC#rtt2324vD~s-0Ze~289)Ku(J`Ia zt$tzwPwkvu2|s&c0ejEsFQO+k!77;di3K}=RWo?+wEtv_B=&h^v=*Mre=@ghsTp^p zRg5f`X$kumjO1GDk>w0Rwma}h;YYz4`%r7XgZf;bH-SB-9iZgOgE&l(--dk$CD)lF zV0P8NvNUJw7OcqdAKn8-zQdMyP(DQrZgkpIk+(A!z1mVObgjptZu zNscFvMQoW&CCuhwjR+S(PE|YyUd#U0Z`u2iWEMxwfY{$kHQ3+D;B~f)Rlk?f=xiB^ zswApl_8bg0Y)b}5vxm+{*q6is-fS8B*+Qdc4jGDwdu%P)Ta--R`|h#no7Mb!^sSa& z)k%pa!=>}z!P~I4N0jz1OOOZD0x8A2hY*A>QVXOY@9~&~lL)fztoK+GTk$)d11Rf# zI)a}AT*$NLtPjX_KVvhK5c?sCKVWQ&0fNYV5npX|oVB8ay8i^JtRz%7_6Ph5Mm?EH z@UuSs9b(E}1nSwcr|{Rm_%ZyoR;VQ*Skn$Bz(4EXH5X%(pFV58D8J|N?RV2 zMUlx)Jnv*uE^I_37dAcs+%hr5uf!1l47f`4{ckbSHvntq{}ChfUD{eHO8Z7;609oG z47oxxnJi`sC-W*6js_;8?T~rzhuSPW2j7AGgnvX#ay)R$q(UQNmZgNHMzbtd>1x7K zrCDM*d^M<&Ivr@SQn~ATxm0S@Vy!;GcoA@r(7(laRI7$UkfKWJRl`#NO93br3NRe< zpFmHs5Xs;?lr_}4^>);;tUv=*)n@}*c`5!_)it~DKvGus9wZg37-v0$ zq*CV`OG%w~BcRC+f@}={tI+zwBRj_<+exw$$*mKi%_N&+38%X~lE+D+?PS$OsUR3= zTU2tZU#XYyJQpR>6+O^qMSlt0vi}SdLfU&O=yXL75-Z9DT*(PnYp}7RdeO{PS~IkD zZKXtrm8Po{X0qyH#8@v_7IQujK;iM6awl?=YJNegxd*sqKS$4Ey(ras8R36J!v@|1 zxat?lfL|7m^k=}8x3B@eY>}7m((20B#sYjrqJ5XvS4HVPUls5iv|;ry^-u*GSWn{^qC5h2&a)1cj5MQkZsCH3pm3c-x|KZcSI}TjV<6ZYV$) zjknoGk4n*Pus|k)W&)A|kPHRr1n(0oz$=R6mjJM)*yXDM*Mo4ytw5|^2WUH>l^YRA zvd;t#|HMbGdLPwl{nE0Sc@;X>8$owE1rY1|rIhM%FUw1GmX{*+iDSV!8wvISuzq7L zt^(}q+E%_0&o_{ud=>(qBVdZov{LktN?``Y3#i0Lpu`se%@Uvbh#VTJ6}nF=RLtoy zF{imjV&P9|+rlO)7`b(__K_5Q5Bz5!fDJpp@(k=`;WrsLU7VAJXC+|m1Gh;mT$#VoH?rM=T3P<}+p z^QKK$L;Y5h!Hf90V3J zuoZ#z40IrH8UpI1pF)!h!Sh1=te;uscLTnHBsU^(3j#4OcJ%|m+)vDAL%;F>Fuo0R zmfBWXda1CWN})TT%D{&Rv>>qZ-w41jtxQH~lI&knjM_z0kmE-_i#)iz*LR9~A8gj5@BT=9 zg;lY%qn!W@Tb%0-6+lRX{hsp9Y3U(Ft3Y%mzLUu1%^jF92q3j{*Rm zKKYQ~o3~^Ezt;LhB2r$#qp=b!22P}EEUWq3N&x-ryaAGM9FV#9m41hD&P3Qr>mng-ysQFy(H`Pdnq@Wm!{FU; zex3k-Ku)m_v{Gzj5WW?=_sdlf<5nEVon4}3J=T@bypKdp~AR7f^w{|*9qBTk}X8A z@_h7QR<(VGpyv|J_R~_90d$R6gsSYCEx^q}^9X5Pf{H5_QEN5!gMtQDrSJ^5$}=(r z{hXko9+kqAn?#<I9+Re93!AUo0icVFt45j?__j<6rkXh#1A>8$_DXgu>+uBm@) z9{;;dG}9)+kEZ-zM)Cj69@Zt)uC74!0p|65>J(Ij-@2v_rF#iqCVdUs9ndBG1y0K6 zPnm`O-yQ|+!OWGPe=MShu7OhhunLvD1b=*1;5b-;&q^LqBhVf`d`ao3o0NKRwg&c+ z%$IVY2_D^_)Y9IgQm(5;#9;FD1(GUO^O15JWa-yCVXCt7nWA4WPGhhpkS66fAopoL zxI}yGxe(S1j616`7z5~X}s3&97Xl|w3DI)qF43^s4i+|S4hz{;NU41*s- zMEf4{NcGzfk40Mut_NHD5e6|ah`Z`Z_7UW^_w@%Zyb$FH`1{w9w4oVVi7*J#U~dBC zhafY6cl@Hhtq6+xd@8LN{H-KEQRymaP)Y`LoHXbhfT=1uawnd_zahKitP2pN2r2W{ z0L;D;V9JVB_;V4CI9B1gm}3hBCce)Er=Wy^NlZ&Y-Xt`c*-P@@Qt4A42bkpl7JoA= zt*CxzQJGfCJz&}Id>cUj080?uVDbGVavACZyTg&#irfM<`69n$B}WR^LKl(OYe7nF zgEXxSfE8|nTJutmIR%*D`yfr7!5{_dMv+rz(vI+jO4*d`B1DNs{3@#swdYSQFSL>0 zxd^MsFfxoh3^TGK1vI9}H*1;eznE*}O-Pm$DXxcBA`_5NO5~>~Lm<)tJ@t$1g>9rp z4uDTEvI5eFB40tUaAY-vzyW~3r$zpWzv+=<@HZn;gtBEuQbE~2@&YiCNCk4tiflo> z42UcN&w(myD{9@JdS)#}JQG=}$X_9Z6IF&VvlBQmJHWNGp zek!sFysgM6Hnd19<@-U@xjO^_Q#}YV7wc#O)gL2QLO)>Kz&i1W!Sp zsdqCGCg8O;{|3O=SNM<6%gEGUe*x5h&bm&OdJl!5B@EmN5k{tltOw%_i|e z>o7n}C;Ov2P}bCPp~jv}|KQfHUX@yDeJJs}{n6Yy#8+9=1=fA|qsyq|6Rc4vGxk{e zqfaxp6$bvuA5Ej8Ypm}i{b%6625^hC7cA~dik6{)q;^=dB>nSA(cV>nFS49u@_RWc znnd|7HvA4IMgL0vKQZv@Nzoyc_X_Jxp+A%qy^8RaCjM|z^gnP?sW%w-{iNt+Y&bU> z_@kug+YNwkwdP6wpCu`q6;I_zwLpj}ANJ&Wa4Op8D3Y?`SSC|>_Fhy4Wfph}C|-0mtEth)SxK75wnl(WzAk|Fh>wENOiJGDqfO$oKq$I|C12;G=fHP? zQ1l^|yu){{&|eXXRy6=V*(c(RxGEIo*{7*n4ZJH9{fe60X5ihS=tYE2HT-W1MJvhg zG#>@Uhk;P^W*WxnzB2^g6N=VQo-+*ny&;r|yA}qPfGm)j?~6c=D9tjpK*B82t1Mxm zB*FJiq@XPiJPgBjQ;U5In4+i&B=db`2s6bMWU#&H5$5Ww?OdgaA={sbzC6$1r!?E zgKR(<3Z4wZ4*g0);oyDD^4GUZI=qU%%DnD*8sJg6p<&j`$S7)|C547tCa37F3Y)+ha(^Dph@{KC`uq!gniYVaY*>3qIGC>I9( zP?__^ixRgv_&JQz`BLY;Ex3|AzanH~UwLo?@^ijE3Aynjc6nH%8FJqagu>|S<$hClP%4B zw-x<4YTZe(H20gV=o@f9PSC{PYDMpWvYn8Lzr%_iCjYSEx5tVOWBPOh-)lv)DP4w1 zzt@UBxdw2iN&lb~bzv6H029B@irzy_3^eikt>{TiA2s|ASkW!0O=pOKpSGe`P*tw= z7tzMERKtu-DNf*dD|$EeJltYKf;+aN-%$Qh20my-pCJES!|!z~`U~>+;6qmQ z6~g08{9%+APAv|#w4!G)|3X85g)dsk@*HQqB=TM5i(XDE@Zep( zs73ka82a75=sSt(^ihR{w46e zzUV2`cd04wUSD(%)0Z255Bj3tQGfN)PutiMADx00;xu8thUGZ`nDx2N;#iPJ$_?g< zYNx|GS<3sYFS?!az1HWF-}AociG(+r^1SSW^I~I5^4Gzb!?&PtBhzN);MGQ&O4=;1 z`3*<5X|ug%R0~g%b}a3m&FD+0JncB;5K0g79QCw0vjvI_=&o03a~BB^4PJ<{r4{W4 zciftgeJpA&ZQd*>PFA^RXCH#<(~30$OW?Az^I&^v^ECo1;IgyVL%y^H8i7^r+1V}7 zZrbr0fmQC=D9E7zi^C#>cc5+q;l(GiIG=)fcuBA1t%8;GALUmIurd&fz=grqk9_zrp{&meX2K6z!@Y zOPkhKE08}}xC&5v9+Ge^eUd*J__SK6939v^gojv6C*?tGIl@W)iJ(6EHz>xrfwT>K zfC~PM;&m~|zUdBDQ1>>JnO<-JKeD9t>_en@!C7k%+pA-DWMF|Z=ol%z>Cwtw0{Ab0 zhqJoAPf=k92|{U`11MndDpW|?mZPMs#`aF0E|5R?3his_YJmc%3}!(}m-_TdKrX{9 zRtl3H5j8@hn5z1SD3>6L-2^sC{$l|o`6*yZ1Z^Z^M6V#W;;+tjG?|QXB%!vhMD1kc?GnfzGHwRvJiow2lh}4-y)tq4Xd;qRJe8i+SnK>GAgO8(`yj&qNE#oT%d_2YG{G<|GYG59U$osT@0ED})$K<}un}=E&4U<_zr_ii1;O z^_i=)g=ZOFRS|IT6D6TNjDk35%0wmk-+}t%h42 z6Df!aZihd~Y|^6pF{9Eyi(SWnTGf9bUpb(6m2x|Z*FVa{;Tfo%k&)DNjFN(1!r?^1 z46=64LrlcckU!Xr9wL&ap+N9)Ql@Jt6nv%@P=G}(K@S6vBK#Co7H~#zcoz)8Se#L#Oer~*baJ$!{n{0s z2r5zLOclNeO27uE2bpj$Z zX;XmEzJa+*6tF`P9%4}f4>K9z@N+0ap)>P*gr&Q2X6x<-%^NoXILGP{_Q>EN7T`GD z#pe!a!=QD}B}l`bC@lxNh0e(%%LYHc^A^Xak!N7)DpCwZSdl5Ha*i$@Kt%FzDdX=M zWR0W^AW4${DIk*kd$W3z}IvR$xWVw9+J z8$qo5bHP3x$5x>N2OV{{V6Ts3_mOt!6N23s$NrhvqyHvYo`SFW9wavVW5H&}vF{N( zEM*`|{5dQ|(>?$T95nnW!9E$szC!GXNrJsDj_n6mG-%`^!S=+l1Bo3K6YQcmmN&=^ z%IOvC&^UGyv7;{#?58Q73|ooKy36?Vqx)e7PJMJyP z9v{cvLu}sHf_3BAM~NMu7Ns6OhTUoo&k&nGO0d6=V_ze-V5VSq#VT(IP4~N@@<0MAIIKB?370Y`|~*V zL1L%AAlUXe_6g=T?Vp037stLz+UeFHN*0Y{4-{)^x5XZI=d)!XJ{?qnow-P(& zSAyLa$DT**+&>8Rr*Z7hh%I_eufj1^X_1 zq?UIMdcZ*orU>@oIQG#KfIYrcu$RZNCz5tytzetuSl;J0XwfFY&W>X@5nFPRU^C;` zvxqI_ikKwq?DJ%}oY=D83HHG__IhF$KO@*nwsN4TCo44JQ+HPt(+~``#r4q+)CiYGY?l|R-Xu}syd5XV<*thrSM%G>oXvWQh!3&r#8d#eb#@RFtW5z zYJAO8R()5?#)hu$g5K`61>Fr@Ew!zxrM<4Tx4xmEwWYmxa~!JeZX4g!&<>J1RnXkg z)=*I2+|b_L&|Xm7v8lbaqqe?Vrx-sme`@}uiTTGA)OOW1<4;?G#}Pc@{DeERjbnPc zYU>&b8a6hx_jD^&*Ew-Q;pY50O4;37yEeZWMNpvE0it5{4UHPYC&lrtty3ohLWz5} zbT)J&h*s9w(cQ8+mVoer;MLRI)lgd>YiV!n&|G?2+8T7Iv9r6UwubZohz?(XQ)q^&L8JvyShvjs}2Td(tu^>+R@w8qu;bhNe9jc@H}Zvq1HZ>nuE zTw2<_P+MEP6cD|$w#f+B)^>77yOFxRqrRc7wtKy1+t%CDuvrJYHsPG4@t#N;SJ&Cw zM_bp?*4f(7)6&sy64do})@ubIHw@=`TTLGIb+stHrfQ^;MVg*w9irAuXiK*jy&k9d zHq;sXddwtmZeVR}81I;;WL6m?x*ZMHXd$MC;J<9iyq+Sa!87)v75 z((xkz#b4iNHw@7ffZf#5wSGfyL$47NOSodXtr_NCaTw8B-_l*D@eQp;JzD9VwOzGs zItJEM+ln9zBwisf#@^aGS|B0-AOekIV@q8_PwiT-%IcbrK`a_Sj-SKY^4>15lGpZW zyREHPbAVZx;vgSb4X`K-ZYF4#%xV1+9*?%iOi9(!WZIAhG$rk#tE01{i&jNSvT3NJ zrD>qEud(1@=Z@a4I-{y)B#En$ZK%G%B1$6zHWaz}4_Pm44d@I}4HU?Z9@d_hB3 zS8u1+ghU1%wZ1RQPE#_iEgc;Xvy|csfrsAKw}~Dwcxm1QYXlMm>l?b-8(1I6zp2p^ z5Q3XFx2~nJu|?bv2++~UU+hY^Cfg^M;Fr&5>lnY!?#eI2;`m5o=}Sxew!J;|OhDiE z<|l?988ZnhFMI|3GyaH>m7JfvxNM5OC7+R2@|npGO|-ZBUo1S^u5TPTX42S+f-Xtk zy}OD3=1(zXXW8d(dr@Q=GYOL9SNQ$**{9_r@6S{|!WT;TTUE0CWoB5;KmR3bNcnuf zMx?rPBPD*WAEih58~}grM|QuKh(Gr$(cwT*nMiPLa;cHz@8d!Hu*5$mv=0jtgm17n zm)QOC?dREUMvr-NdyM^9l>c zmj><jevqmXGv7X}@|*19`v;6&GB&@!Skbk~c6o_Cp~NoFw@76&FOu^MCIUKZOMYqTXZD2rvhh1^ zELc=vm*qpaKz3o7ed}o@6ONxWru?(Q9fdmzO3MmL7sFN`>R(V+kYTUPk2GcYd>Dv% zj$v=IHK7!ozf#QQ!qd(yE1kI5=Oj@4DcLH3N%;K0{S|{EpL&{qe>k8^7;F9iKVDP+ zWw?m(TYT^ZfsPz;!RvV=E_4pY{j!_*FTb|iS0Nq&# zRz|o;k5Mjq6#m0(p86jDEM;wTLSb1DD-rlJ8JQJ3*%w>q`_8k^^`Db;cJf&%I|5bC zbj&3gBGP0dT>~kE=r5e#9+g+zuT#(xl@ynmhhG|25?A8anO*xm9>X zFSgF|?Xb`EpOJKWay*`I!K?6-JkIu=W$*BpIk{RUvfy3^&O{VDZn3kFMLE|#$A5Ox zS;;$6ygazvU(1O+&h?#RpY1;@X-8ikT#bJRcojSUU4|-5@~=W!7CMoOt#f>5+h_TA zBtZ&H0?I!w&t|yT30!P#_r+!Bg6xBW2VX6_l#O-5e_UwIbRNtF)DT5*jORa0y=lH! z6YS+je0Bn!FjRyFe2P3-cL-9Exmhaw40hgHKTn?+(0#&_cPgCsqIiq}ECp|VxyE+5Hn zlK8lu$<@`IiH&DY)CxgW@Ge0vWkJZ{xN zkMKgUxI)-e^07+?`3MMMrAH`>QjbjQp^{MN6Gz5PVGk0&j9;R8^x;nS7z)idKcHhe zjq9UpMy`}Rkson81=mMM6+A7tQ{+ikh?mB(1H}Yl zMhxiqcx@5n-ZvU6pK$dIr}Ifai*T-&IccxJ51I49=!BdYdzHj4OWzXHN%5-qSfhh{=wihM{|3Uk;O0}8uHjRwtc%`7{t{x#szmR?ry)zl8{>X}&*O)JR=kX7038_e;sg6M1kD`?QT*V0 z`EYfRkG=RY;e&V{5OgIUPwOBbl$R8qF5-IyRRy;UYFXocgVfx;L#^`3&K%)*D`C9s z9D!3t6r&T0!fkxp1ht%x({+#!O&C{6Hc<2MgH=ZO)Rb|R=bC66(aC-Baix>n9g_SM zd2&dRC?(_f_zgV8WZPXjK%LP^orL3y|YG8w06#%dLw%{m<6lVcQQnCr15?Kb?7 zAs>uR=mr>jy2LK!L&wI&=`^uETvW^G3-I%)9(g{9Fbwr&Jh(m}!Dd~6xq_e+?PP5<+dbOrH$@w9PyxUr9EVbT6%od20fs_{KnVKYhD|AL>Dh>wB~ zbizkM(n62qD>;JUlq^W+xnMKJ$3;9MEL)qK+>HH7Vk`O3 zvGFEC@K#~B)DwmyS}q?*kdLUnKc?Czs7gM#VaQTH;vu~jnd$g=fteRPFAFJ8Dlbt- z^h)#wtW`WlN-%Ca5rA{>OIETuE#Bz^bp+RJz=>SP2#i1K)88odI)1SjCrj}?!AzLO zWX6;fDjPqa5Ppm=E`P@_7VBwl>1GN{gp)+Qfs$dcfPZ9oBA&5W_jJ`Jf!^urG>yS# zrb{&np&K<0yPA*$^xWUHPvfReR)5tvgbpDD79a9~WMAXi4N@Mj#w2NYc7tp%VLV6i z3DFv2J*p7l`nK9wZGC+gKn`zXG5sn^=}E#XOyjuDmU^H#V2z`?TTUif#}PP#JUJ1` zSy~YCYSVb)I{nQ0D6mOhgK$5K8lZQ@p zHgD1h!p=I3Y-^wf6s#MV;%>IGmnf^lt=0l6TZ83x2u9U2p(NqWLc#b-PobHF43em<={bF zoJNW@MpN0MxKlSF z$?urNBWG`KG|%sKDD^YIa7HR7AA5i}8huUzq7f*KzjkPe7YXG6)&>JJ@1IAl@LC=usT`+G~(-8tQMa+)y;tTrBD*ZT6%DA z%0jp>Y?+Ete`*T=iQk0E?rN*;THmd%1+KH9E5=IY7sqb(=?^hjZtB1%OUkYW=&%JA z0eev^JuEk6Z8QLuL1|hpEuUz@l0A1`cQ#2);=5z5;-PNx0aNj2BMFJ}8oCrOrSC$e zdY=K+Rv^p_o8tB8CJYtu2*tinn~Jw*cGdN2O*gohqr-=tn0(Mw+`KIzX=B~$Ex;SN z`n7l{4OWcv!(m=9)&afL%9ky5*C>cy+taN6j#o6gg6__SI`tN?>qQg1)1bDer>kWx zKFBKG{}6{_O3E(b1!LpA=h1{JU#R8V!%=`T^?eBT$mK zFb`C8k@(cEmILSoq^{Ih#rwG!i*Nkv)pP)+2g1iQScmwdWk+Ir6tD2ccK0p@$DIh8a4p~jee*j1N!06#&h7XaY{EmlkKEkvZo%5zC9wb>OA+nx%s>-QIBD@+q(2{zj zR{ss8L?@cgm}3lOT~Dh}`F@yG^!x4%kD=r=9wT5`xlrHGUDwspsXLtGfMu_bZ^3YQ zSV@tX(F3!85UJ|tuz%tL1^v}i9d|V6)9E&^Spbz`O@~)iNyoD;S{q_rT00FYy-;J+ zPZuHp(KlgT2o!lIK~f6igf`+^WV~!!Z95!ESE6i(5XTSil12(RxB61rrtne~+z9>sn+U)WG|(-7fN)P;V{0w@i@Zx`Tw$T#Y4BeQOj{My&>AWdi8B)iY}oFzP!4VdF+4eDWoAIufAt%iOs` zZv6b8mYXZ){X|#i11)UG?gB z0P&p%NxQeSDXx;$jFti7ia-N3gY91c%2yq9AU(0hc2(WvA+UFX2%afn{FM-@TS2kj zq=6f6Z&C;QFtuG>wOdqOv)FfSD{847VT|R_?Q*DuzM!QMOQwP?ajuYYEykP0z<>@f z6tQ@RpbFN-k)G>6tq-LKZ#)o0CsZlx<6L{qc!Z~YB)rwYEAw)J1WcdTP`vVjF&MEm zwlu*Lc>YB34iv`7Vv0t3lZ42}O(gE->+AqUVjQo4VM2JJhE6bU>r9Nj!Nm5l#h|OB zE|G*cFeFGTZ3rjf9*L9@>9s({m$ayd5+PK>0l-~rb)UvN-4T|as~BMnTfISQk1F>N zSWzNg%;G2tUP`6qV$9qo<0sG0oZQ0^MHk+CWbv4~&4YE-RBjOF#-e!%GX^8(^G#aFwcQP>ersPcj#LH7dw_quT1aulzl^zbckmPRY+U`N&IBH7h-5US zcolj}$3_g|+ z(zS>KSG;6fSt_Gq^$L2*%jX4#cCD zWZjnHZH2P9O1C%OfZ5p=!%(=J?TBaD_JJ@7-jK!@bRgNa@M^$%gmoL@eT*hj43M`d z5~e?ucLUykhr8qwye4n|BSuC`Je(QySOaGk+^H`w0!G%kCZxIlC#Von7q1i3Z-0G$ zm=|9eCc>0g<{7w;h&N(+IbqI4x`+n&kZ#4pWOa<H5v67l$IyS(!jv4V^5$p0=YAWA=b2 zpv#a0x;NIuqnjnYtml&fiQ>uNeK_^*4T+#8wYBF?-@JaYujAYTX4%mRIapuv92pb2xoke)K)hT!-V5I6eud03tt z^n+;+?g~zr(%9RV*o+!@KG2V6Bi;x0$FmXKN7XkQ!D+L^*$93&?wfYtK|ep3cHluj z@o5Jhsq@2W2Od~+&1on9m zZk6tP`{$N+dHd&HI&TQb9oKzt|J-COP{P|kHyi)(?Vp>x^1SRz8!d84`0N<&TEM z3nFo(rw^XUVd!+9!OadDfyTnq-n_|qSb+J*&k+2#Nr(OmrU@Z*O^@81;&@4|04es?6`4Uz7>lFC@={K_Ts%VNu_=FTfsWtGcg%a_bQVbQ#*xkY93F+C=; z8=Pv}$m#Xgj!m3e0`rD0a2B%$)P`}WH=~EWHa&EV-5nSUau{dEG@>Uih4hN6mM<%c zEm~4FzjDFcdGljMic)eT=YU?EHJ%X(Xud#@bjT{{FYAr5_9qe$f4|UBs6< zzQ9(%fI8~%-rdqsTZebJX7mPpb;ZC<%KxJ`j}0v`J%6X_Vy&FKQQff(bse2BY2&rL z&r*7xmo+?hUe%%#=EvqPDPJP<9DUO#P%{d|>g{1A!wAtRda#44r=qeJ{8QKQ0 zs8{v9Z7@$vb9S`z+nk=i@0MvSTBJ6ey{6QUeP>&@@(5E~=VegoYfen!mUL3gK)e8m)YS^kzUIZF@&| zYXdIfVimXcuu-us#fleIR;|SMx9&FXTRC##wPAB-3&>;bnCOP%Tf3zPA6kC&t^t|w z)v#T+!HW54q$kX+TqLeU)L-AxR@>4J!(cz#it#$O=1re6RRnZFr3uisiPq&2F*+f~p1Q`vcdSyd$Q{t#3|jB8|3QBg4=VF)U&AX#BR z2F!Yy1dL2#0!dae=gcZ*%qRxTaaD|KSVb4ZVisLjU9-EUU48$m`ki~v9sR!d-u=Yi z)D3<5^y#jys;)k#sX?2}d<~*7*CoRzjLVH5Ia23olSyLJVpCJ-6ASz_YyPP<(XUvH z`Y7DhK&7n+=vvx@IJ;RPwAl(ZXdGm@q{X*xOY+M_3>PdHhVV@!a4jGV1WGfLDdvD{o?imAM5ZYb}x z&5E?7oWh7tT0B{y2vcC@%_z=NK3mPKhaoO7K3k>Y`Rs>(VhR>t|Iq&rU*( zwMZvvGq07J58v28ilXxih?+ej&Kq$;4-9%vhGtDI7uMShNjLYNrcTymRh3fFRZZ8p ziE?26RcMIM$Z0sLdp5Mz$}WkSrL|t6v#Q**Mvd#abyhbE9b^|N{PW7jIE7qXzbXra zHBU!-$lRfr%BITZM7n2sL#?z%s37mVil1b{eZG=x@xxGo5mVHFFx7|UW(gBE8J!brb@ndB~qOh$@RJ~1qvNYX9XijG8vRF4zxNe%}Pwl0yZ`R6;**CH= ztE=l|RfW#fskow#2(B+y$;#D2U??ezQdvEU0(KgjH4Q#?rq(oR*w^`_9#*hAZ@An= ziquDrhrX>!7P5{snP!^_YsjWiYB_BpQGxiHMa_Pa(v~%On~V%o@imFhel6d z>7>@W3JtN^+RPL`a`M=*smWs|9FqrOb{m-r>QtGPQ8sqyzPX7bhK(IMW?UErwv9f` zOfpTLl-KIY+KQz2IBoQ|t6W%dSGQ=c2!q|0BUj zZ)X-N1g+5ARGIe(RAV=QJtpTK)!b$&4%vt`4OP}FrCS@ClR3GjFt26gy9uVX10UVt z(x_8clxeAVdaA}f^lgTrFLV2K2wjjrJvyfQ75Y5Y9lu(C*GhS7gp0Vu^^~jCDAa{1cpt+&(p)i8y3C@MWvvzQj@cnL z0k(}ldq0e6xI%MWLu`OA_^rC+`;MPnI&6e~scKnol^bP~xcM`>esy&|cbe%QboH;{7}=4NvuA4yi6%!H|C15eK{ zv)HMG>7@qAyRYtkMT|h|UAbm9!}?HEfZ0}>B0D2=adaI#CZBmqbEV@ajvG2QH*UnZ z@e>b`n=O6mLB&jNl=abA2sEv0zq9t13Fuxf9fV~h|E&ciOLM~}Om@FTiaUC5sNSfM z`L}Azh|Fn}D3aicInKf7M)hV}Q8AUI_OENHN@TG#hGI86C1#-Fl`6L@bed8+v9sPR zklO00Qsd>*v@|`n+52i~Yu%XCS=K1GS=E18Q(sjrWuO}&qydLQ?9wO4_}VmYVEdnx zOl4A$)}@eiSS63TLcLV_-*Nz0XHqX}YM7_1s?HS6VER?pjeI(DU)8(Q6ce}2;*$HE zF}u7;3O72Sx04O$LH!5W1W;kM3Fpv;t)`%&h2PN=Cyg05VxnE`5t?WwPLh=^gWK-& zAp2JCL2a&8B`d2pl!AwYm_#)~B6}w0%2xF@xu-s(sJAxTHEfZJt(~hof3!46^;Z|C z1i8}DTw(65`)1}&w$@u(Tl6bAi4oCO6O6kxD1S+99R z4XVCiv$gt#d2joctu&nCdoGAB7bMX;jNqn8-pgFl#>tdsWEZpe2N_{eV_)etXAmH?RNEn=ziYnkrgI8 zEX;0mQR~#8iu0(Ytubr0N@im~{+3Qf+AX@Vf2M}kd3)f`K5vzurYR|=LmPUs>RW7- zO7pcU7NaG`sY=IE5NA%VTrP!_syB+fzlN`e@H@jMXuLrReo3>l9m@iUm{mpG> zyZesW9&)v-3bDXs^q9OYpAL7Mfn@5aAIBW&UUFUeQED!|8NqBB4V87)3v>iL*L=I1 zgFmM9z@cNu47Ywd<Y4+G=BqC9CCSbx5HX`BA21<)fsBQJ1KmTCR|lLfi6~%xfi+ zE_!oOE<oT=FYRtI&>E` z)~|07v3pz&-Q}RMs#=-SW?w64mN&1xz&eeAI_aVoImzhc0`}sIEql7aKs;Itk5d?$uQ#-jTHTB)_YqaNcv$ z2(3-zG6by&%)Zwos$gllv|*jtQe@}knr%cyhqRE9q9*#f?mDHe*jGpPn4Xkutrq8I zx$=|V^_d`T^5_q;RvSEFL)A@F-ZH)1Qp0pO#;s3PielJYU2ns?N}9&@B)GRf*VQTA zESWU4Z2z$%Cgrti80C?j7b{+29jl-wTPxIAMkrUc^hmY3>fe9EMV zd%GoFVe^%Z(VQ7G21Z`^|P)sN9* zMvYD^Fl;$$US}norlFd|G>iqeWy(hR<^fv6$T)Tz#Jpx30AcKeA!2K?;U{QX(?*5N zPNIHL07Mn`s7^P1!ah7pI8J_?Ed~MoB@NFje{ViH}$< z)hTx+7t1Z`u-ws63p6%c`?8Fkp-(=xXj*K_Rg7p8wO3@7vNE9rkGsm)nOrK*P3!5o z(vfAUd+Ym^Jj8I6`~q8@aT7!nj4p`IN)xeqt`a{Ly0tS2!`(GN?3}QXV}Zi34eV@+ zwh~Aa)wgO%*9k7v}VuV}xXhNMN(ZP%N|UF)1#F?wvqj0#9IcvEO4JDrSU+OO0l z)h?^Nv!j5adBVOrC%x&uB94l+psu23*_l$=7D$Y$#b~yxp}W#4C}7S~EIvmd$HOs& zz7Yu#l`Tz{Q|g9bY#=lD#Ma~GqDOc?kymBIn4UPZRWT;%J4J9>s}x>SXHs|8f~w6x znjIA>u$t-MnFQVZR9&#&$XxJF9)sT8Gn>e?itU=yCSzjk9yYQy8$yg#3bNXoXZRy? zX@|Dkn>@Ii-?vv8;fZjq%!kvICudl-R+P^ArD&_@>IF7#v|^|Uv9-=;d|Ui5J5e6e zEakFbJ`f?ZOcm4lX0>V5`$bg6a#eG6a#|8nQxsW`qsCh(+xx!!WOEi`PEsVdsbS9C zM7^}3$(*vJW?Z(L$(6BXGxOb8_h91o)n6UOS~)(-DxxqW8fzM@4_dGGp`gp$K>f{& zE6i^7S?)qCvv#>PxHtGHCYI;bs9+W(MoIINM(e(*4r#)Ypt7VY7a$rYZn zMIG|F7#6pTiEVasQf9${{H#8Ek}cGat*)PD(`Li~iZ%hN-zp0zA7GWTjcgAeei?(U z&8}Cr9oe=|n{nJ+a|K;c=28S&`tdo&mhddZudiusFVo|!X*Ck(Smr`Ls49J<>+3rt ztasZQ8O!IP{jF-URh9dQNDG()5t-a^Ies`|8@ zpX4oJ!W}&IaovJns?!q_CJY@lqD=mPEM}W<)RA@D+8S*WwG0Rk8`MxRrS5XJ18D)}-#Z@3=Oic_R_lnvcK%91IZ_or-SNKG73-$Eoz zYc}IcOGhYgNNOQ9e>Ev_JP(dg2H{u>o4d`0zalS3_Zd}SK-)IN>qBpdFW<>l!bHp@Sr^#**1(QtL8pDrBGz^SxZH zX-=J8{iLGk%>zBYsIIB1sulanDCW<8g+EK8S+qRqs@QMc#XIx-+6w zl>$E=CNF$lSxwsiGG=@dVfOqIwuQOk1_2hciFASDohIx9Fpt}ODVb?@x9@b)v<#qB zZKityH1*obP&Sv_QsDFRzeQ7BSt^k1N{o=8#oHD0^4Lw|G)=)4iL$i|cWI@Hl*u4d zCy}G0k#2EV?|6#vM-a@@X~KY1gvpH|#TD9ah_WuuRtGE}pN1IVR5jbWm=e)O4y8iwscdK zS(ds;O8Yc_L`yf7tx37Z1U0GJ)a#R8y7(0Y< zYoHq3K9^OS4UBu4HwQ9iWj+IBsvkNg5gGfQk4E%5GF`H_8<2tZo(EMGxAo{+PtNB47O4cqdI zw$ds4K>NzWOrFs^yS&kIThypC?C@IIk#A*62*1vil<5cyhPu7x$)hA?=&I)1)GQk* zY1K}P^l4|y2D`k2#)`i6=-=Mjqg*@fvXIrIG-WfcvDxegeyOZmlJF!m+iVR*$O`je z+2pbbBT9!W-se+u%qO;*>{BeEP}@WyQ>Dt1&%!A6sx`|@^XRDGb5?zVR4lXZltOAJ z=3N8R*Jckh8f__0E{xp$=$x|Dd{>(f6}5=^zqM8(lioHyRi=()I@?5G&|MNO;3y}; zyPpcjw9_2yJuK_au;5#`KR{+Dh3?UA>b7vF0bRTZe@MmD%?GC1Dm4q%7U4RySFwYi^1@Yp#KkvHUg|HB|@7Ue+bW zQuBJ)wJQn|_~O1MJ_|#t+Lm@15wW@!DLUyGThexqIv?h4YlSQD)T;626Rj&UB{nKv zKgSl0aECOjn@+O(S6CzGrnTC=bmFYMPkKgaq#ww&)rg&r$FZ2*tg&j%#;Puwa7ux+=<)u#!t_EsM)nf|#7CRT#ZkTew8$(R(ep+ z6QpdF#{wY*zg3#Aahfdv%ZMym7p!sTDW|qlH?)N^^ov>BHpO{Pv9fI=tyn&+>3U_G z)XKP0G%w>-7xW}q-!>X_8Ddo&6T)Zj%IV4lw2UiLsNRL_5)f-tk4o!u`qyNc(>tY zI1~ngqIGiqW!xwnK3lq_+7~KPXTWrL#1_*{lGXyVeBmUPkhSV$kBIR*_VAb zY6(kPL1KN}jYV=Yb7uEy+EA2KIbd>&)%q5KFl$p5hnDXAW*?+b*r?H*YZh>IeI`r9 z*S<3eMY=dlbe5R7bomjPTqQT+WX}#n^T3J=L@FX>lKa&XDIAHGaw3m zEqa=)3|oYE4WPr6D;G^gEB_&I4ynW^tt_9ycqgA`%;z>!dfE?-O1v_fO_=85+_AF29(Q=RGA#aS-T5#`Q zVFU}>TZCKjOWhsH7XK}NYdO*koC>M`)W%Z%sC^pNs8LR+sp8rD+P0Mm)lFk;$eMC8 z&7g_ImsB+q;k+EZ_anyeUG5VXKy zTq{egNteK6^lBXXfcLx`na{d6gVeYzf-vdrAfB_IngdcS%G<&(GIOgzdEh#6&CAnU zTdI`!V9{2qU!0`06FoJCn6F>i*=vStR9KQ561h`rm6c1Pr9}-j-KfF*^te#5s8y-C z((+y~u;Qa=N#6(N20dB(`88%OG28O7yZ+LNG|w#c=CBD1SAXd6;mR*4^XX7~(Q*;y z^L=VkvR>!kxD%5agK)owj-5ehHZx~yyd7jj>e}Qxq_wt2ae4zIcKP`D&;o%hW)D-D zqK}*o(;WSX?@2xR8dhpX<_lE^Q<(}K)Yzmi6_fQ_?L!ZWxSgZrSF>+T4>xGw_?FB_ z21_F@Y1&LUrM~>AeHuz)og?LD0R#0F`J*fWrOU-S^P)Q)y7IQwbRFIeVW!vc*?hjz zycHRyIC1o~A*u3F9YDQvUv^F=g7d zYsM+gq6H~@p|Yi6Ms>YUx4ywM4U}l6lJ>C_XN`jNt~`Y`X+L&8&=Fb&n=8)443GFr zv!Lk(AJaZ=StU#3n*J@#x@ytV@x$4gQRd5?iEYOWe@?ww(WiQ?GDjbjvX>G`_X=5$ zw2q7=U{gi9-IwL-NN=%9m{;n7=O%`Bu8N>$8e(OB%tY|~1j8p(gS!RdW{Z?>(H1Y? zUngU~wn5IK=BgQyj;mA-?M1gcrkQ0jwV5DLSSR&U<@>7<%zLw&4@Shn40#&RlCNyK zF~wOJDETy3TaBmbGur|@aHl4*YPu7brs;VGMYWdnQEU2+%_TlB)YdjvSI@B9xki0- zNwQnZBLp88+y2(vsqto(8rMdHL*~7z9UBeJ*Rz;&y1Tx@*YhkkqT;og#?$u9yky^_ z_k^4!k}A5EraVkClRB%aE9^qs&MM_8xHaQ`uG-Z)i+Pu3+;Y{eN5T3nnHdWm$W&YSi z$RZZOvubyaNPRWq5bi)zH?Z@{Xw za?9{nd)wNespV=}Wj2j#l`pnS#gd=YTr1Xo^gS$dk7%hw$ovW~ zL~U=L6Z-kpR8r{+(J7jz|0>BP zJzp&_nn{s1r|Ey?7gi;6YpTtIHl3Yrv$9>N-V0+6Hq*ikQL`E4oyAx&yVJd(S0WD1EDiFOX#d zQ(@ifb_$j*XxUZ!YR8CTNVbkDm8uESV-1#P?Yk#r*XP%Iwe56jjfQ+-FhyntBQBPl zv{l)X9n#31fSZ=JMKGn=lE7=#{cV*`>7=owY1dVbs+vY~ z7uPN(Y>gN-WKv(_8$)Y~)}mZ3rFw&ItOOkmHeY=XKOiP_-}zw$t44m=D~4LqYrT4O zS-KwBoSPQ$ko;|a)!de{6|1@hv#Yn(e0Af<^rjD)Y!!86Z;I#>zCc*e*ZB-|+cJ^f zchf2pms3_tn9Z{+(<}`nu$rZ0a$UCRk%GsBN*kzuxy9$JP<=3b(br5~$p&9nxxMs5Jjw!xSWw+VT zim>fIv0!c{$;&I8w_fs@%<`K|^;%MHE@!K4THEkp?5obMx}_=eS!EtDo?dC=H;rSe zO>J9$MJ6F(a_Ro1;}0rzUE)fh?M*Lz_Gz-sEit8dKTGf1s~JLVp<%6Emg=J9Zx!7x zDbf#ZUA(Z;plarCETJossu*r7SQUCXO%j!nH>m#}iDl?$L!-PZg&5-L#%66xy~)W@ zFR*5h!K_C1;X>3}qD3Y%=Ug^yTxU0U1PU^aSOs*&&~Zd zndYIEEgTUmgyD$fpQowFtn`B`UpvF>YKX@(P4&vxw*04W=^(Q zHOhaLjo`UUcF33{ZQAqcqN2s-u!v2BQuHt#t4D?DxilvG!o5VLAl$Xn*PGaGrao>e z+B)`BUpymB9OFSrBcTFZzi3>#=byLp)B7-D1?TVAoxdG@wv%h{+GAUMlFO`^nn4~n zAG1J@CG*Px(~-0%cB7QX0*5RSraTy*4eW2^4y<)Fke!Ypc;- zo%|&;y=F#`+K1Se+yajT($R}9jXVF^RqKAaEHCRgnp$J|slq%A^M>T-_!oV}Nj+Q_ zS~;&%wLofhvqfXAf%*P|)Z5W|m2$0J^IOWAoLvu3d82u7BD%G2+_w41Lti!{+1yZA zkE?3dsw68j%JP;Yq%kU$X$G^;#lFuZ7QSusD@`1?ebBi`Ickw!)s}H+bAc;T9l=`J zQ!1qWHT&B(jR@N@b<0AO#^ttqX_%?_p-8TFG%sb=<>iB^TpdoWWu~q5hBS%7{SKdc zy&p!>izPNqEF?C?+OdYd&*X|e*v=ShL!GMJ8ySv;^=|WVW#Q>+*>sdtMIgx=Jg;^w z@?d*2eGh%k1Gr@X2v@}e!TUcue-tTIwRU7Y48YihW=FjetuNrILv4{{$ zvDyeAmF&9*JdwavPwWSf){XSD=mW}kPhIEKEF6EmYF3F zIWtjOzPTIMnhRa)Xo1%w3T|!qG=q}1=yQ5M&-7;Wv9joUbz&wTFLTX0c|>R90<+L0 z4Itmn-AGdg@r;^u?PJ`~gOi#u7BDos+;4B|*H#;>ltCpg)svcZ%5Iu?+#?^q3;Q<{ z-*gAXa=F{wCAVs();u+oEDPP8Gu8#%(kNU2PvAG(&#GxkQQ4SEd$Tou@5|mYu`caC zimt2Axv5gj2AZ`xM3mctZlQLHpKKxbTM8~FeKoxxsj6EkhtU=h zeFF8iwfLGTSYKqb(?`uo4=Rf-y=RH7_-luXs%(dl73qs)uC&$2cK2gf4=P@_H#aqD z8F2Y9wKS&8T&cAfEmX?8o$e*)xoT!=$34~*eD1A9h-rQ7e|_zL{d^#WMdSA+vt;H< zA_wt%HGqd7d^n}^v1^uyK-oo62T4=8Y+Ir2PE_GC(k&$EX&@6Oj+iji1MTL6*}b*A z=UM97#9@=uc$}TEX7KzjGL5IyKKE(Bl(W@Cg<4l?)99`di&wCvHq;if+%(9{An~wW zd8KXsQs*(3(l)i^*UG~{4sTq`-Al?^6O(Q7@(I{uOv)w=J+EoYV}GVgEOeEB zIEhV#mS3p5BYDPy-Ppv2yJoOTp8{-IqftGE876KfV_`H)_45o0X#-6_b_vt?psPop z4mGLyog~zvw%!=`IVCJba3BLVeaL6T+k{xHT0R; z-df$9>^FtNOD%G>GEW3kPc)y^I)V8NY)mk7)>p$V1ZWv%;bZ$;FtAVYh8^GTolV`t zEw}SFyP_yVAvVkFpwC6=h3i67a>Yl9Z9(q46P}9%-NN0JV(k5DQOa)~VnNWt znqS243pq84Ir&8@T5`{XS=b1db>?FbF`@3R(Y1SYw{$1BdXjc?7a1OU%f>BhI~o|4 zS&(KIAQQoEZ9vcS5Cy`qB<{9{zdz7wt&z3JW#f|CI<6}~eiQ8=$*O@ki)zNI0 z^HcXh7>yts&Ft`~d7H>bT#KQWht9wX4eVB8agto5Ay}4bn#LxJMBi?c-M|gK)O0al z7pj@bGWH~G3pkXK@Sbs$@Mpx8N#v9u@v~qf6ZfP>|ebu2s zt&Hqc@EbF{j3&iT+ZdLa#eARhq9?{l{`wx`GAOfmNVS7zw6zzY5U;CrHAdNJyDd>+ zgN#2sAk!TO_4ZK`KV$X5jUkV-pirbK!jkY(Gr#WJH`}%Q_A8P~ilqKU(tsjqV39OP zQucYeUbn1EUI?L@j?_sO>5t&gcFtvYUS}t}(qceIGF{_)b6@BAc z=7jrc^ja)59K(Knilm~(=+{qfLb@-J4g1-j7PUaXq88|9El@bf9+JE_htuE&fV+hG zO=arYQgZnT*OhHJ3z>3CimF~xRP~ags+Sa9$C9G!SWj-h@viO`-?O(+V!dQ%4m7=?~xg%uR0q*{Ua`c1i7nTsOfLFShK}Fos&opeml46fd z7d-oE|2B?m8aKC6|6ex_>m-Yw3L=@?xE3ZbyM8iD!nVlQJv|lTVqW*KQ!Q`b?sBJb zq~bE^LY|Q3zboo@#bLjqHER97upTWTZ-jdv@F;`cExPAQn#PcJA&F#CaF?)>HGs;B-4lnuU;DetE5p$zj2a-?;UH;#%%uWTWf(ZGmaKr`u0V zbNdLjdCYcPSPaoZ%>~0be?5JRlq%ci9#y&*o2NW#wOJu+|79!=c=S25P0}WOOR$R7 z|M-qBlWDPZ_A10BlTpKl?b*F&nXkV#&FwyFmtDG#RUEB*-`;)t^y=Mjw~{_P@$8}h zkFO5xr6(knSC?1RB<*_W&ou__HZ)nY^IAhYwOhOWMjbb9w@JIrI&9uqzjUbPX?Qht5^y$^dt3pO{R4cx1#c7LFFN=mWD3P>R*68nL zmbiah(W;!b-Q=VqJ??^JzJzHdQbgUX%0nirSHU#bka#L%Y`wMJWfM%>~8A!nti~Qf~S_*8|kymey_jvytDjk`mODf@AY9Hy<@+(@97D1$u#7& zyzf<3`t&n>lrL|4{hcju%AM_!(R$CyvxkzU<>}FoMfIDcr?7R`d+95!pVd2C-V&9! zx!$w#*3iGSykYv=>YF|gtwrV8_tIBd-bB5j?=>FJ2WRSgjq#qplYXyMQuery>bU3X zJv*+oM|xa6>AL8+|5bU}m(|H$dLnMoaqW9nPWqs>^terWFMHexceP9Gp>1~Db@VSi zuAXvQbli@c=#9)PJ?^!7FMGcBJv*+ooxRfIF4o`K<4(yOSC0eCANPL!ZDptJ+(qR* zDLH+m$6c;Bvfq12-y32lz$^XUvy$!azP!KTHc9eU+R6CLK7Wh9)8l@*qn;|qZw%>q z{9S)%&!bW2(OvIZ`&su-+wWujZRO_Mzh{zk$s9K=??ZhjTi&@UFYO1`${mgOUqkVztuw^^X*)_dy@2^EJIpecYQD0kIvQi($BKr z+g{(xR41|T9b*UJm3}s`&G*(Dm?R&(lzyvFMn8Qodmg=Y9&;+9oxADl>3NK5Q{LBl z>gWx>(GP~TDR0SU?epV&t4w(ZwJGnijoT$3=)Lrno_krF@*Y)r)&SNIy6azBzv+5U z|K(o`Hf@)*{6_t%^rh_iKDv4PnOa^&rWGm-jYmtJLtP<{jO|N-urvBOM0h;iD`M4wkhvE zmDgRL+xcp!zj((QvF$K z$ujbK8uk7VqrTT@)b(8?TKSh5RsLdltx@GKLB1K@Cw9A6^)*^KGQx~!idN3KMwPP= zE;8D6MOJrAx;-gX&rDW1qs8{>Gh^WdqZF*^Nh|kYs6Uf#kAzRKrG9TV ziv7-BJ4^TZ>(;QPOt#}Dk4v8kJ4<({x&3?QQ`qO-VNci_4uV6V)z7|f^)gz$tURli z$y4BTC?q>em-^F7?S zPm)v_2T1=I2WvbV_t5n)_S5w+?v^Ci8h6xnH4aabn~lR_-f6$Ro=k1Bj`O_n3H2l6 zed@199dD)aE?pm;Yx~>7A8oI`pr0h|<$S8j&Q0Jp#;!@CqLcPIiC(-v0v-hYJoNh- zf(OEC=ysBR z=XQ&srT<82Lhhx@?sFbA99NpKN-5IzUrfS&V{n-k_;63SA3PKu1?R!j;U(}U_yBwsu7aPyA7STp&B>j8Vi z!Eir#2&{(Z!OP)Nct3m^z6#%mU&1vuh~sVqw}rdIKfohl9h?JCgKpod{!5V`fKNiR zZ|(fvfFHqs!wxbK?DGv_cX%MIfQ|52cm=#4J_VnLFT>a2+wcQuHi{j0J=hH%1S?=2 zoC{BZ*TXxY*}+!c!|)0CEL;I!g>S<5;XmQ$@LTvJwBV+dzb5PgH-ekPtzZwhGwclq zz`<}|I0jCJhrx0<4c5VCI1io--R@UC&qsE9U-Fg6OX21A%Q0;gd!0xa&90Di6DX!5TOlo&*=d zYv3JlIeZ6x0e^w(%g3?v-x}@?_krVK4mQAJ;W_Y1cpH2Kz6jreU%+4B`Z~5BAMOtK zf#YEgHo#-yIq*t&8+-)52;YHUz+d3{-8eqn2abnRVG~>c&xV)5o8W!$DfmA868;Rk zY#GPx3VXrUp<0L;NUcr-i>UIed$ zcf#fHE%+(?0j{M5VLSdNa68xs4uPfc2v`e`hNr`e;SzW+dCL_M~Jec`@vBCLQ-@OXGWyc*sCAA>K$ zFW^sb?QP?@o5Ag2KR6VQhc$3EJQ@B8UJLJpkHMGVyYLJ6GhBDOs7E)r3)~Zqfd|8B za27lXE`-;>JK%Eo5_}JS1>5zYAHZ#3A2<{q0L$S_cpN+rUIlN5%VCG@<2bj$XW;Ab z1K4GU_+D2y98QE&U_G14KJe}Zf86!kd**1$RN zM0h@23~z;x!x!OO@Kb1ui>CK_z&>yvcmzBfUILfEd*F_{L^=K7P&ghQ36Fxa;EC{j zcon<_J_w(IufY%Dk8sUhZ-Vpm zgEQbSho{3u@OpR`dt$AGqeIINtBzwy+Nz0>{H6 z;cR#UJQrRDpMopl`|wNnGwd=tj^7pbgahDkI1x^P_3%Qt1l|fCgwMhbW8yd)z^!2~ zxHlXN4}(X+x$r~y75oLRyI+*w4fcd3a2PxoPJ;{JneaMz2V4$Uz<1y}`^WJ%hdaUn za0HwLD`68n4xS6Igtx*!!{_1q@C*1eTz4$z4R?Wi!ZGk*I1SE%C&7jA8h8g>4p+c; z;OFpvu*bv|0p0_jhp&}JdGD14drbC43)#34exN4vu@EUkKd<6a#z5zdm-@~;I zr50?}bmn zSKtTm8`%EHINpY^JKP^L2x9T1S?=8JO-W#FM&70d*G9BC0q@^ zhVAO2J{!QT;qGuS+#enaYv3Gs3cL_r2k(MUz?a~=@C*1eT(>^z(+%zd_k{bwgP`t9 z;Mb)Uo(M01*T7})5%>ap3;qlK1UolGxm&=U-~c!n?h8l5QaA}72B*V%*aGLl1@L5e zCOjW5f>*+&@OF4Fd>B3hUxBOPS8&b7IKPeH05}3pfR%72JQZFAZ-dXlSK%k{-*D}j zalFmo_HZy91508X(a6UW(UIK4~_ra&(Yw#oZ9bBu0>jHO# z1K}umBs>Zp4Nrl8f;Yi?;1lp=xL#`JK=KpBK$Y(FguRBA?yhUz~OKroC0UVli+1=IeZ?z z20w$}!wz%exLd zzS-7;g4|b3@CaB7kA|nii{TP@FMJBV z0zZJ?!1gD`aW{nB;qLGUxaLXmy-ncuurC}6C%_!6hkt};!b{;z@P7Cg_!|5N{5R}) za@6B@a9cPC4u=Q8DX;+^1J8m>;3~M@DN%k`xC1PK`@#wENO&r|5MB%Khi}1;;ZJa_ zQ#l{FFB}a^;Ust{oC2r9TG#~Vz+>P^@H}`6d=NeZUxOdQAK{v(MLjo$+rmC@Z#Whn z1S{c8cq}{%UJ7r7_rfRP-{5=j3-~{{&goIFE#Qu@KO6?9!&Z16Tnul6Z^BREk8tfX z;y9bb9pL~t0#1UJun8Uq&xMQOGWaO`82$(T7q&k$j^7Ec2RDXY;Wn@r+#8OEhNr+k z!E4}G@PDxLc~SlruqPY{N5T)_S1>t0ezyVa1^0v_;UriAXTm?iGvLMW26#7o9KHnK zfuF<5R# z$*={U0MCcF!Uy21@LSmaPaFq!hr7c+z*2Z5Tng`le}S*S58yYj{e>I{c87i8a99Q_ z;7qsxo&&Fdx4=Kc=in;%G5j8`by3u#2kZy;g~!0N;T7;!_%M6{z70QzKg0DF#c{TQ zC2$lx6xP87@B(-Zyc0eS{{~mXZ(xUu<9NS=+rfTt7%YR8uo<2JFM!v;JK^K-RroRd zFI@kUIR3Vs%Vg=?Zs(gWxE5AgqQh@C0~1yb3OZ zkHDAUYIy8raojWErSK+rKYRwh3O|J3!VZ^5Ih(>!@IY7%Ti^-se0UXH2H%9A!XM$< zSHy8PhyCGjSOzQLOt=7^1FwL$z=z;-a25O#{ttG!GLHXyxCcBCR>Kx}0z4ny3!j0n zz&GG~@FVy+{0XkTIF7#=+#dFWL*aOM1e^iq!PDR(cmuo#J_%RC)$nWB?y9KA25@WG z3+@fa!o%QEa4tL*UIed)Pr#M%bNFA_`D(5M+!gK(_lJkTX|NTZ0MCP0!du{j@EQ0v z`~?07cDyF)u@USJd%?kQKX@>l3R~du@LYHWycs?K{{mlyAHc6+yKA{FaBJ8L?hVJn z!(lC)56^^`!JFYj@Ok(q{1^N$?0J3Eqd(jq9tg`}9Xtk}4ljjwz~|v>a5Y@_hB(eH za1a~=C&4LjCY%pXftSPE;QjD9_!|5I{sh-rLVLqq;NEZyoD3`Asc<1&3~z?_!6)Hs z@B{dTv0ajU1HUtFnk31MQJ>C6$?GF;fxH!RPvqT@2Oa37idVmDMo#N267|v(Z~ys&w-c2CC1K4awqa5MjhvI__R^SS;6OTAis-HfVV52Jq96Ygr%@A~uk5abca6O8)(Ax8b~2&0ZS)2QFg zgBKcA{xbLwd}gO|c3@E-UCd*v+W-w?W*_v+$S)dI z?#IagK~C=0`)c2HVOO{t+!Kz5hrt>+3!VVagIB<%@ILqyTnXQUpBwKjb+P)qgjD8yh#)een3aFB}f{hZEr;@JKiV&W0z#GvM{`PIw=D9Ik}#!GFN7 z;D6!z_r`f_2YbOi;b_&MtKiM>UidhC3BC(|ft~M*<8B7GgxkTL;O?+L+!v09 zlVAlr4xR-sfEU9n;dO8+ydB;P{|q08&%hVqEAS2Y9{dP?2ETznz+d1R_s99K12=@5 z!7X7A*c%RjgWtHjS2Tz6z;ni>%d=Y*Ezk_Q&5a+Q8><{;a6X6ut z0FQxZ!OP%M_#k`(ehPnr>pU38{XN_T?gjUUhrt=}Xm|#^6fT9G9*S}|h1DQg%AUG0Ef)%h49t+Qg zm&2Rkvv3vs1pWv+KN`pF3U`Kk!u{Z(@F+MBo(?a8H^B$svv3vs1pWv+FX#AhXSgTa z4;~7Sg7e_%@Dg|vd;mTRSHVxM>!k9t>JEPFL)5FhRyIecn-WAE`|5Q zr{ODbHEjQvIDQY<8xDs1!Fo6so&+y|SHauhpW$=x@9-n|Z`k>nIR2(^Ti6?phljx$ zI2)b>FMwCUJ)ezoN5Tqt3_KlP2rq+I!$;st@GbZSTdPepD*o{xMg^7+VDATL3_3;AK> zXOUMTzl;0{@_&$%zeat#7$d@2rkGu@| zA>^l!Uq*ft`Jc#NBma!t>4m8O#zxhDE99M#OOS^k?}vOK@)YD+EK{ zTaoWWeggRgBtL_ z7bD+9ciu^wEzmUI2ZoeYxyPi?)y*Y9Z=4h8Yrjc67sNgvoalYYLyVFSMm`+51$hqg zWyp(>A3}Z<`Ay_^krS0^<##mdUw7ml$U~5aBTqrDLY{*>A9)e-WynjAZ$|d#O6YhG znXL0(!RPi|EIWUDSv@+!E^q_5IqU{^g}vcGxEI_Hmck=oIh+n_;nDC|crrX4UJNgX z*TEa%?eK0WGsVwG)236y$N4w73cd|LgI~e#;eX*e)=v7jKHLoc9&QW$`5^jxH{?Fh zuc!V_ujeG*KNwDjwXg;Hb=KdfBA*E_h4vgbtJe*1DSQw<0{uB6`uk<%_uz-{bNDrE zr#@okt^wDD8^SH%me8LsqVM-X_UDX99*n#{91o9#6|e@@!TE3jJO!QsFM(G;e-4R` zcN6j*@E-Uid_Jq5_{%{XC8jgkj zyf&40F!B^w1zX@8cq}{to)0gCm&2>zGI$q!5IzE5fG@*U@NM`Z{1|=-zlA@+U*MX| zBc0)fa1+=Kc85E{U0`200PYQk!qIRnEQ9_$8MWh)$Q7^#*1;BN&$qMdcnUlNUH~tG zH^8OvPIxbT1U?Q|!q?$Da5elI{s;aKwp){N12=}hhg-v5urK@r+!r1IC&MFPIc$V2 z(4OOG?XUoz0?&XKz>DA&@M?G?yanD3?}v{Wt98`u->3ipEhz>#o2cmSLXtKf9l2wUI@@DzA1TnMj$H^AHAo$zt^G<*TR4Bvwv z!hgdbV5d&e4qf2JaC6ul_JAdD5Znh2gA<`YUr5*I2;_3u2wR{(kJ0)I@~QAlcmcc! zUJq}Ax5K-kKTlER{RR2&@GbZm{0iCwL9HLz^B0Yq!*0-?$7t`Dz|n9lEQ1HZ8L$B! z3r~Oxp+EOX<=%k26g~hShEKs~;VSqx{0IC5{s@1D>voR%ZwR-5Tf*I7A2et=AuX63>{Sc~q zx}5q4ZT*7oeBJ}5{y_=yAUGI~hGXFbI0;UHRd6~?{f0Tn^Wg$`B0Lu^gp1&1a0$E_ zE`xW$N8uCjFYtNzI(!qp3qOEg!f)aC@V~H=#+tQn7iiDzHF;y$9j1O^Pm^_hc7^`@ zUR|dWleu0h`Zr%45`8K2>W~!wpo2ZsF7xV;NEv5d9gvuMWw& z8Ogq{4x4#(NH)kw_W6cwWGy^rULEY=MwwTKL=J7{)gjp|BUyP{w2`~Ekrjx@ygDS^ zGLrp%t2T1?HuAP@KVtGD!cQq|beP@VPxZI$rI(yv;N6 zXnkPv&H7DR-m-i*jPE~@kq_1POh z)h;<+#^cKyQVR{jSW`9kFE`P#F5;}zvE$;ei3lU=`1{*Zh(kMB>)$QHja z`S48p*t2%y72jW$k(cWOlQ$Nv{wqX#rkLv^j(28$*u?J_XJm_en4JFJ^wM3D?G&uM z;{MdZ^^`t}=f`SF4%5))L9q#P)fOp01#IqmbFk`L40gORQM3a?F)z4f`h z{-S@@UKV$;ziW|;zyG`B5WXMB|6MW-*@jfRq^n;a{mCn2YwLJ*Pb^-OzD)nv^I|X3 z8{6rh)%PsPN?k~HLAK|{ewdMOlx%Ze`uV+*_sYl?x0#xe|0emojQpNti)p66|3dOd z8QJ1B8|h#A`8v`i)<&tkh2-fOc}K|?WMqrmJe-k-N&Yw^A0T;S{Y%TUIL$i$9%^0_*+Z9G9&LM`Pq!Tm*jtELo6ILXgvk`8zkQx+PcHP(QV1TGFE`eY3K>si~&ADc4k9(_Ec@x22|`vQFPm zztvp$X%w8RXsRxsk*jQ}O}}ELw^TRP)igBc8XKC5e#-mlSF388Rge1W%KVoqYa5!Y z(~lb(tLxLhn_J48T3Q=Z(d%WEu_N@-uj;FN^-VvlYSC%5G^b+v-BhlrugM>;dXE0C zsmisKSJYM~x!ly&`pR6cSD!ul>`{^x`{{WonNR!n-Xkma>pLJT_U+%dNE}oo_Ul(v za^HSMpZ4unTvXqI*`oUO?kBOays5k{*Q~Rws;+3Arg!QZs^afK{jFkov1M*!^`QQP zc&oOivbw%mZ`dL1JF}{rnrj;B2lcm;iyt*tHq|t$#q?%L+F(`Hv-Hcn)KsJ2=?77b zs6zaozNV7Y-=f6krpojvcG`B3^4gm6W^a>%)TijP-dRacLdpDYV0toM%0O$Kd?^Fd z^NP>XlM1Qm=mV`83%|1~P>_o1GO(yF1B&W0pr|ebis~|;s4fGF>N23HE(40{qUR)K z>N23HE(40{lE2b^e))?WQc+#<*E>Eds*A32=6L;!>f+rv-!A=&>e9ccE+s|nQc~0| zB}H{9DQcIJqPmn6)up7UE+s|nQc_fxlA^lwE2>MsqPp}es*4Y`{Q31Os*4ZO!e>Qw z@ey12tf(&iit5t0s4jhr>f$3iUy5sxf>czOzD4cQx2P_CX_wa8YH0u|%&KNCsD@o# z`Lvo!E2?FBO|$iIeM?e#b$LZiuC;!4O?_3avavDO*wj0T(QL}QqM@NSX>G2^HC0cm zX_m^)RmG66tgSAuZ*5EqnlZJhx;klTnVVPl73Hl}nm}5r6VtKj_oO~3!E{zleX6kR z5TRO7zi~{{>S!E$qq(}Nro1+nnJWC<)`~hEp|zsGQ-I)`Zg1)KHtN zYo5kAS%H2|jXHSC46m`DXTG*klk{{cv9&&5=8T%!T0fSZY;}EQLsfOIaIU}EpnbeD eRKBsPp`tqbM*dLQGpx?Po6F6pE3ehzlm7#)QDHa$ diff --git a/sw/ext/ardrone2_drivers/ftdi-sio.ko b/sw/ext/ardrone2_drivers/ftdi-sio.ko deleted file mode 100644 index 1553306fb92e99eb2eb6ae3b60bbb0ca63e4c21d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 280807 zcmeFadw5jU)d#%K%$a18Ob$aPfnf-TlM5jb2$N)TC1~z|fP|ZXHwa09NG@Y8h<$Av z1QjjRSkR)?8mn(>m1^K{im>OHbyb_@finIxk8*Fn}t{&E2)_O zKC9>-@&<2k)-nQ?Lz&?N%-$>@W|y#al&ioS@uzAqB3dky-iK_4|%A4cAxNImS~ zWb1}v84GM@dxvREVdGGQdHaV9@DrWH2FXSk3;G>5rfl>%2d^<(^+mGt4o0#Kvh(T@ z4{UbScm;M|JrajLDvbV-qsB9!`y$&}FYk}RhGF7IpKhy9>Wl1m8Dt;9c!C&L=J6H7 ztO9&AF1B_=spxkqkl%=MV@3b{`)J(O{HnmOgDf@JKeP*D-erw>JG;Regx2L(5L zGS5c}>_L6d-2X24Y{YdYZOFzFjsBr8E_!<8!r(I_B-6osBjMgB-QkKSPf~yAmVJO1 z>2Wb$XDZFL(F!|;Hupu!F&8BJ>^S?KhCZjE&uOmDYn*4$vL6fA54$m+&qlR5v-?T+ zvuN`;+B}XnXDZG9lY74!SzZC3VjF0jZ$6Ry26V3(R#@*K^?SIYX^{1vKh7n=uSS$$ z_3)D5O_3Uuo#3gdxGCcP597x0;z=fBmyE!t<1?f5qxG8&{bFFRWavnIG^e(nXgg}B z%Tac~xr*_!eJ^!YU&J22nm6Wa6lX~G$B_Lou03cd6VJb3T*?jGSj3;E=;$AFu5sUPt&_G3NxcEm7z!^*sVpO^WD4c6~-u->5xV7*4a zuNOXq{+#e}jyqA8it*4pOmiv`F(KO5x57^3Up;u8g>REz57zG;Ci_yq`=jQ8ZSEhk z*XMPx*LAShsK1BL_k)_vcSK_UyE%V|`a~amyeARMQmJpOaX;pVbcsRzS!<2j>tYY| z{v5_|#)>nk4Sf;Bm!ZM%jl;3v=e7&pfjL{t*BJ92jM(-cSap0z*?5DG)ni^Vj>8xF zhhVo6n$MY-Pnt`bXAj=@Whf(FysMz?`GB83G}=eSfk-*@J!zmX=uGDHNH<>KO5sahP^V_8=<_wlX?A6YkhCTnRfk1uW|iI7^ zyf^Zy53h`|br{-wd*pGnqd1BY^#M^U9{t<>unp@Jj)oP3Qcq+#G+I!088;38quvm7<&_B+d`*FQRA4VIJ zLu-io^91j~Iyo32AHrJ4+?u%y>#rYX1O2{)-u}s7!T$6$$bKU9`cPco_CY7xIOOc> zzi%)f<3d||-+k4Au_r;V^s(_PY$J{Pg`>pVN4y(H{s&`u9=xotf8+u1lO8)E-)r21 zIeb0h4qrd$uK(?OXX;(Ulv5$!iJxP<9#OpgBhKKgL4(~m>wke9^^J(5K84S5MU;M+zW5F3Gi3Fr)?-}--+*0xluyMckK+x3*KPB{UdVm<`l2=} z+HfC=+Pg?TLz`D8o8xg>^4%8i(Q&*dlzSr&TD%VMI{G#a7edCH$X6WRn}+S&`Yr4g zR7U6tFt(28H|$vdNb+XHKFpV=g72B9;-MpA1&^;8uqDwk@C}FYhUxdn&!<9$1NzUb ze+m2COOcboySQx1Ej`E^yx3;s?r(`lsF_Tt!)DZzCUi>OIA{e%NE|fep+) zbnk&-ip@&UvQNd{VI_Ria2#7Z^fvr12Kps$z9+(cXW&bN&fa~4DIiOsJ@C`YC7 z%IZvUhH}<Ia?c!LRl{Kg5hX zBaX0t7<-_il=u5o<{x&H@9{YXl7|(%r?LYPCAh~&xt)3p81_M4PZ;vNt|0bF#H@jW z*GKa=|1n%^s0VO8VCHTU_s0IAQQyK^dJFU8KXy+9>*66hjxB(Gv-BD?1b^iMr187_VTwNyDkI z1Nj_$Y%=1Fk75kNoI5aIJjX_y8YsYZ3UX`@%66V@=P?uJ2)0B#dWia`zU@7Z&I^ck z!IrB@rzm~wT#fu3`{76o`u;1f*FM9zX#K%YheBlE3gke@NA0;lbv#|0Q|@P2wxqmE zMci~5{X?`~immIuOiVc0agMcK1_yQzr@~GN;CDhU@;iR5K{`^NVD~}!3UrPSBksP1 zJ@_r``EO;QzQWvpDG$b85_lr2&HLa#3ckm!Jv&1Fvw6}`^!4i!=?+io_msmHf#vf72McGvNCmyXPYPP8XIvG=thH{yY} z5B>IDHAs7`s}J*vIOEw2zrb8-Xyd}Zy!twRJ3t>@8M%Q5*25YU{4wg z>$PkH{SKp^Y{Bhd#a-HyJ;pse4!ga-eNXA#$IobJpFNAcc(29Ba1KCzeiXR@%^A<1 zy_7%S7$G|-$e)+@-N^Ij*6@wU4{yX8fuEqypm8Je{TsQCtQRre(#>6A#fshokx#MK zY~B1;pVS}O1GYZJ#$THvmseq*n&1t%jxoy>D9c{2+Ol_{U)u-$&?}5}P1km9zoyW)c~&Ct`xJ9h=~~Ll6H2T&LFXOoP~M5xA-uka7bQ*6c>~4bSS*M| zc=0>|Hl+QRbfb7>kA-3gttq-zjgI?=5d(>rVkMo!M4wZUY>HP^(1ZTyEMc&s7wfHm zs4r};8}b9nr)X~{`O$d^$t7NHC!5dG!#-cbKE?Z2$!?HCc{H`5vr*n2xD#hjD(a9P z-9mMA=1X-nXEYWrA8Xe>M<88E?-kH{3tli8!(8$|8Uw{zM;LahuQ1O%;g|6S_L|N8 zID0kqEobH)nEa_3N6_zmDjR%^`k;M|_BRK{g4j3YL_5-9Fqlkh$&^Jg5`EZv(Ba_u za{-;=_hByRx_U3hu-CE!^B#)y)FUsc$MrjOqJ59X{9j$a8+85Ne;@XQhm5FxVZV6V ztL*bOjEA2a(HR99=W_TE*{ugQ>qXg%angQAWAhud=fQ6AN&NbObV{{s?||*SkU^LS zSh<1g0PK5ccj^e_Jc`%YH80LNVY_Sf(Z_D*yvupt{Uh`2zOk3|u^TAP25cWmfcH;ek$B zZtO{!SASFFLCB+hh-}YwfX)vhF7*Q++-#nIv;O{(Sm@s0kC*{Hh|hj!eYZzmq&>Iy zPMm@FMrtp_bz6Tg?YTpbg%1xId50rv|0|LG#AEH9Fn9dj*gKII4_$|S`4IMH)^Fwt z3ii<1*zX+)>qk)UBs;`<*5lj~`EzhD&sTAt0D5m^Gi18)?hf9`WjlhenD#RIo$+W# z>lOK|bD-c^1-=&V0PQ>m`k7}HnolQaxKcnRKhAh|$c26|FLR@>`6-t@f&KkVI?igX zJ(c!H2Y4}#x$gj1EPawm7h^AMg!}^fqwfOPwJZj_PL#2hGDz?3%-pk7oKrkV`*j7z z(+A(p+cOw84o3!XPlSA>&+2c~)|f|k7y_Zm!xEdY1=qxyO7`=tbwE6jNWcVyb=ipMpB`tbaB6R{Va{9|5m3@A|>D;2%gc z;|%qC7&O-fXQA-z0LifTA+)`Pc<5dh@xaG_Yn~ z=@J`c(3jR-uj6>$pWXxOu!8vGEZxJ`tP^FWbk8%GzZWPj(LC-c863JFFS;Iv_*1m5 zF^^6s#^R>E0lM1#lvw@Hy;17R8N7b*Z+WjooW=b^#}u5WSu&NN3fc9b`<+|{>mRXY z(HPGxrd(q8upfH?`4jnzve{f$eTX}B-Ou_6w_-o#i4}v+SD-KPnsYO@UsJ3a_0I}w z$KvU{lKf^lV&HPbKx%V`XYC05AmE2j1%nFWhGQ^@@gk=Sc={<;Upg`gZQY2^@vtkk zQOC)~v?2T*h{QwoS*%^UJ~^Fk`3v@#J60gBLe`6jJ&JJ=_Ttqej*ssB>gQnFY$UH| z@Cq7ZuU#n9>yE^=Bhw)p!e3aXt;N1aF_pb=$E3A%eG&L7+TQ^j@A1pPi;Ls{&ah6= zm?m4i%TPu;T<@?`Lnxy@egpJy;w%kumE(^3{*eu+$F<1FC3tt?eJ$Q&@V*-Fv3Re? zyBqJgM|ld@86(T_{wd;sZR1^#`!Uu&+4l_A|5+=3bb^m)2l^x3X|C46hSPxCZOP}3 zga0Vn9|bR;m&E>&W#Gfv$*BRWeFpg`-RCh5Mw0T_$Ya5;4BfG4&#*VRXPA7Iazc#v z;6CVuoKB&>)+(Rr=YvEc@?;VGJrcX9m_Jq8ctok0vZgSB9fA!PNRN8^Rvo)3=MjB?wP zpig2A#ovd$0Bw(=?LZ#(fqL2}=wk4G3Jq% zk+(VV{u{iLZ@`~N-n7mz82&aQs8FQ(48h`Nl-bh?dlK)*elef@1@FBplUV(fA2K!_ zFZ?BA6Qlf3=|%2N>wN&Zcku8#3Uo+?o}>q>H`n=EF&cl^1NU2az$|3uu|6VQ;tl7?_mvlrj0m` z;Q5Fn{l1_vZP?j=%a8%wKwM}-ALJK7lqv3b&GVQ5=^WF4%Lt8QgY(`LiUo*id=14~ zIPq6Nr)=m%b4qKT+PSUzY_!AH5&t*Lojup~S(q2?sLjBAzZjxDi+Qof(th7hXKiEW zq2!aZt^JyO%=RzxDe@=oONjaC=e+xchbixZ4*&^kK zqQgQB3$hxoZoKZn>v_EXg;y?uLK9xM;l-cZ*^Hb8b4d5^l?sY!eebZa8OJiopRg8b z%(NfTxRWsl$(Vy=%mE+wxaVxhFX+rl_PHAJ!P9?-?|Bg?F;5ip>3%<5pYpSE(Es_Y z{1QGVl+V)oSb}FA4$>MKcdkXc(LE%(mn3_pOZw40qqMV-hnybUMS%Q`#!hw7&ktam z;Co6o=7r8z$YzIN*Fm;>*b&BfHk<9DpRaPmzU9VOhn>c6gV3*l+qwel68)@Y2ZrgI zx;$#l&^l;4Vfa=|=m5 zo#T2z50&>j;l}X>%KL)%x+n%J@oPrjUbx3W{^>OojAspEK)(<7l3X9d7yq4XZ1VwI zHs#M)HUSTGrTgzrwwjNN#zXUsI636_7sW`^)(p0#GCj9+h}I@uV<3lM?pSuF7IWW= zyx_jRNDb!SiTQNYV{L_R!F7%41JUQ&Y_pl`-;K593gWsA>x=FqQr|N}F8KDkp;;K) zBIJxzu0{C*oF`Jb4m#U1>1>F64%bxJXUF`*AG|$6K9`L6=SG>%06ch4#k>8SpXrB( z&hta^LGp3c3t3S82X{JMmt`TFAktB-4`7|Uu26T;CaG9 z&#u0jKkA3#6jTe;fTlBO`}thLp?1I?H~Kn7P^K& z3=ACUU5?46`s*;+4?|uFoO|G5cW*L+z`&8%-jDH4{p?2&_;&1fdp!s;1CP3U%W>f} zFz`_CJM<3vBmxq(I|k<>JQ)|Q1CPe^ZpQ^V(a+TIgY2C4@v7xnfOGD!hvvGGzM`PQz=5CW}+}_aHwW*~Y zoLjdxcbedq&gKR*>uzPHl-7ps=Jv*GH+8qP*(_#7XGcey*`%vyOIu6#CNyl?)YG}e z1UV&80YhnQ?&{hUhEld7J?*3V_k^3!;ik66?#@&6}EcHn(?gqJf(-MjJ+1xT(3jxwEaM zy?Imjwc%!(H2htQ_49eWZo=zUyuOOpy?A{KFFw@s?bHYi!-!UZIUTCviiw5!H}TnS zYT4P+)q#TxtAc|V=qBEMN0+H#N4UA&EMe|2E1avPy~VOe^DdOy;ZNuHkKr`+Gk4&YI@VmWEcNx}zNy!R&MyHJvRevWA{+3}MmY&gN~#vd)f%?emv3bauBj zv>WByfK}`uEVr?v?SgqmRZDBDvHIF3n5TS8C%sp6ZELYAm-TFEFjj7%x*aH1v^8`# zx3q2PZ0Tvs?daTg0qg2)M2B$K_C=v!epPKrNibAeT31t@S6UFtFDR+3V-2k>4PA?R zy0(<eYl`!l<~B9XZR)}+Jh!EBZVO5+;khE#kR)qqZE5g7v*uM6mxhaiK^XUm30!Vd7;AMaA97a3~OOkB{^Y%vdzpt?ZT2Wl#dWpxFsv|THUW&D*E z45Z4gEwIWAtGc*`e4tR$uGQ6{N_kefy+EWw(WU&4naYplA;IvHc}n1yI0 zX@Qy=ndoAMw~)+&30CJ9(QL^&VRdP#tOei)vcsyYERmQ3zG7>tWp-|xRaSx8N|}U& zORcMunSx+V0U}|6)D+Z&io*H9d>Ol1tg^$ZsVk6OhG3PBE_DSmy7K5!S0EjT>g0oF zUA~07)YR72(iBJx%Vw3()n=8Qg4*g5*_Z`ZiD8-hR&A|JQp%$X%pe(Ez*!^DS}o5i zzsJ_f?gh|Q+OD;=(snJB**5ZUwG>94C*dw;AS#f$gy0LNphR}IY6?nZXA7*dvjtY! z*#fKVY=KpFw!kVoTXhB1vVjP!(kr%5D!`ZEDz2(h$_I$GvRZ1BH(5h6#xhw8WOikxtU+Y3LQq4T8s6;}6U|ng5@>dzpvRGxNptJy|ImJ@O;;cnd ztQ6quD&@1{(i)jzajB&>GI79Sm5BoutBh+~tTJ}BSY;-bvxY*l`&L~jB)e~cRd(M3 zt4tuWbd}w=YJ>7=PEbD03Cib$LFpA+8?2Lwgk%A*$~qxfWt|YLvQ7wAStkUmv=au4 zWb>@LV3D-H28*QqHCQC=ufZZ|e+?GN`fFWPq3qQLSY`89uu9vts!-alRfWCcwj?NT*PyJsK&rf5 zgYtHjzqL>jl((z&y*La@)~fFaYD(iW@qD#(*MDYc}^Of1hbN(yC;mH7!t zRjqWIlP{mW1!eASEjU^vnYvld4M&4g#Zm`+9%KK}Lyua4S`)iH7zslTV zw1!nJ@2}PJ{#q^XuhsJYS}pId)$;yYEgxTH4y$du%KK}zyuVh<$Jc6kf324H*J^ox zm3cPDHkN!oP$loLRr3B?CGW3Q^8Q*S@2^$z{#qsPuT}E#wMyP!tK|K)O5R_qV_om9|uQf0cQn(v~V8UyJ1ZwMgDyi{$-P<}=dvu;l$!<_QX0s=U9- zd}zRuD)XeO%_{G&GEb`7QswxUuOa#P8j|V_oYPM8)f0cPY%a$tdule%vHD5ly=F9tQzI;BAFYmAU z^6@oa-d|7JAnNJAYtn&VvFCSm?<^5IW!8==5d4H98M9!8f@2`3C{+cK6uX*zR znkVnCdGh|6C-1K^AN{uMD)Z5An^iu(%6#H&v&#Fc%m;F8sq+3R^MM>&s(gHvd8E^pD(|mB`S>dHIeA+Fd4HApssdZ8 zyuZqPq~4Y);jiYG3RFpbset+6AsM@xQY&TbYO_k%)n=7Acd=O|>}s=0oV(bp(sr$t zNp*uY^zkXlZ@#4ON~o6lm=B+=YMDS}4y#%w5ZSB}fyic+*f?!gi9lqtN^G1qt3)8O zStTx{P1c~)Gf(-!(r_NWckw@e93{_UmG#%EI+>>wxvpT9H5OQ9jRjU|V^vCh0WJA! zb*0Qbc|I(Bw}|YD1*`Omt*VnX7QTX4Vqz^_Wui7`Eh&(>x4~JfjLOw3b`~3~y!e7yU1i3su6WkOzZ$%20ltWP zfhlr<`OWSv9l4FHyaIgEYwzf6Y2Rj;Oa^^_z0uhWYA3#~d@H`M{Gzp$i{qnO z)V1s){+9Ng_^R(FyXyJ3=&xz{T(i;9j@Hm9+!Ag^D_bFm@9w5%qOW=HFlOP0 zg~oJ>;<=`!d%Mvv`i=1DvIl)^MT02W^G&U}kkJn38(T;X8crCt!1v%A_)h-@Ao#L) ze8c&CgTAyLDvfH{-qHTK=FSd-f4RRwKN?_kbvJbPbYVn|&G@GECYY8K9qnW7(v{UK z7T2x?R$v-cxolRBm)&f|s&&SS=K=NnraTIkE|&0k>P)69JUO3X9x<^6D?^Ate~+t!@# zKbV^PDetGXxqTb_0SY(GGiP&=!Di*=?=tXnU)Hp=HMGKO+n|p5+YX}@D=(>Cy?XV! zi%pG2;i}cOmCHtFcoeR$T)lMd#&NuLt1DM5y?C*W_O#EV|?NY{zGiY?r9o6$CFtbIiwchn2U z=7WbDQ9Ls(%zr4wpkHcf+0sKnoA$r)%dWfo+D-K9DO(zPnl^P(Ozv!^Wz$8!H$v7q zZ*9*v8hh}gFKvePJ1b-Z_r>H*RkUpFiv}vP2_I%$V9_ z8#q?in5Wo1jd8;&jTq~{W3?x*dQH)&qGMRG04o7DINV#vBDRd}vBXQ!XiH0X*8)sUm>2M?G%elNMoUMds5okG$rI!0s5)psLCV?;F{@lF zYbHm>0xo-qV5vr6uSRSqv4$0=qm`H_5RG8f1>CIXH?qxd*bXz6Q5d^A+IJ!P8ZBE} z8@4T)6%6hAkG-JD0^VkvZlm3-HNzuT{#FAqu<07?Ymx)uo8WlfQNfLEP2`QHlA~xt z=eF~mAL|6W3?)P+Gw8+%coD_5X|_bUF5LbXY+UQX|z zm*5@WyMgzppMkPslJ)ymY!!Zk>;e2PS@d5cu;@ShEE(G|4x0z8Q_z+~J&NCmqQ74L z-~9Ju3ybc{3BgW=|L39@Q6%g^0oHr(L_Y8FiP&TTmL$M@0xVg8r3kPo0&J=PJO1a1 z`fdJnA{G|3y;^|PKR>Z;=bnj}vUwsFBfviS=R`iQfN!z@>wiJe_LGU&iJwixekZ`* z6kxxffW;*_yyNA?CB;m@oa*yu#`8H697(4MzwdUg~> zb4u780XA2F zWddxW04o<@iv-vO0_;KoRw2MD1z42;s}^820<2bm)d{f00&Ix@TPnaV5@5>&*m423 zLV#T?z*Y*ddI7ddfUOo_YoaiFEvyw_>jc;(0&Kki+aSO;Mq&1PyHtQ(CcrKiU{?sR zD+Sml0k&CyH3+aR0<2MhH3_h00k&0uZ4+SI1z3v!yGnrV5MZqWtWAKm3$P9WM!(}6 z{YUZnY5~?Mz`6ujw*c!AU^@laH3Dpx0J~OzeNKS=j{v()fPG$oeL;YIQGoRdu-yXe zdI7dafbA7vHwdsB1=vjjY@YzTS%BRlz`i8F_6x8B0_@8I>{bERC%|qKU|$hn2L;$6 z0d~6pyF-9|Re&89V0Q|zy9C(R1lZjI>>dI3bpdv-0P7cE_X)6X2(bGF*aHIWe+Ae# z1=zO)*n+XCz%0rs!}J0ifoBfuUJV2=v00Ri@10rous_Lu-WD!{%kzp0rr#tds=`!Bfy>&U_TdNzYt*039#n{*e?ax z3j*v{0_;Tr_L2bmwE+8#06Q+gUKU`#6=1IjuvZ1xYXa;=-z=j3bhyZ&>fJFq@y8`Sz0d`V=y)VE{39vs3u+swU0|EA- z0Q-{wJ0rk85@3H8V1E%{9}BR*3b4Nku)hnivjXfN0_+n3_D=!!sQ~+z0Q*dUotuC; z)nlUbSi$-D;2)#2Z1aA=`m^J))gC2nBIXcaP64J0Fr#mxyvgYku`~geB*4-Im`{LZ z2(ZbSf_?>9o&c*9U`YZjU4Z2auqpxO6JQwvtU!QO3$V%Ag7FHlJONfIz*Y&c1_5@p z0NX9Vk_1?~0LvF(RRV0a0NWzKItAGE0?a4CG6YzG0IL>YYXn%M0P7N9dnRBn#p5vZ zygw%^O-NJEgZO=oUD5XvaFdbl1=dHceYb^$C)_7-s#goJP65^>z}zP%>Jlfw;sscO z0P_g2L;_6J0B$bZJuC*3%n;M>;d5W*Z8)VxRoOlF^2$i3b4rnEJ=V(5nxjVm|uWR z6JWChSe5{rEx-x{SV({^6=3xO%<<##_H(L6WFmI#FB7q+1lYb;Ci2}Zz-|#>UlL&Z z1=s-r_GJNf>jbRI=WtBaZ;4>MCqJCX_r3r-CBXhDz)lOW4+PkU0_;x$Y~SgL`rSMM z`|uA~i0Az|*@u5{2r%aa%&BJo-+4`W9104sd;yjxzzPId;RLKM(J;pMTbGzN0V_+K zI5zn1x$$kCYTv1e7<+3XrUPKjO$em=JK$^KPid?w~p z&;EEKcH)VN*zW|`^G}ZF+v_q0#xN?8e(4{K$KXS8<1zTlpC)3fCSbpuu56yjcjtsW z@sG~931=Q3rB3vznz(Qy8v~Jsfx1Hr}!9irLm>H1*nW6 zo~1xyvw$$>p2D13S;9h&#aS)gjKu?Y+jv5XGTTF9u-{OlM4yt7K$V1P*z7F{_zVS` zRLEJpDQvcfcqdbVu_SO=@`%glQ=HnEjAS2Vl!Gm0YLw(DiComwu?`sX6GjrIkxu5| z0$iBOR%rTEl08bMa&lDN8KcZD(q6ZOyG*GwEj2CD7^_W4NKEh~P|s-=4>wu*=s>u* z3?Ix(iZGT*W8wrh=~=2hUe1=4jk?rC#%7P=+?LriO^nTfQ1_U1=8j5&*c?kG^ggE2 zJU+eXXa1P}W3{qY7!9qYOPAnS(l)Ydo0eic+9>TTQbI!3SU?{*4QZ0GLmX?UCDoZN*YcK-xGt&#uw6oUD!gj_IEnEziVaa}gLz|= z+8{5D?t<7aGsnT$S#-YbGMHT z(nLGP*vPQqv3lz8>M`;{Zg_THWKL3eTpkO^PCFpu#+4b6U3Nf@F#~dJbU=2G1?0Hs zfE*tkfD^_d0);1!8GsR^qa&g@g<#X$EuW3oG)iY z=jez&b+kX;3US(;CM#O=T8hcMHej`dpOebd?foUy++Pr*&A>@cqDKdynWJ*J4t9J# zFBqnc?F{L5T+Fbyjm+o`X4cpc7|R-)XmjRglRsofPcV7OoG~`?hq+_*MCOduTK;hH zAU0+QqRn_2{wwNiIPpx5@PC8wQu=eKPBr!v3Th7iRpI5Le+sTNVqf2com*WAGIlNg zITiPh@a|rm!dQZDD@S7XtpM`7DL|5UnLG{13fJAU z7sz7}mN4xRAaSY-pXg=opI!kZK>fS_dl08+pX8vab1Y2*GEfF2^9WTwjw#S) z(UVZ_TM@dne0p%my+A{8VG|Xvq@F4|sF*Sd#fv^i#e*1~c1sSal1Ifa@nXw*6d$~e z(AP2Z+GBhKF&MLUlox-2F>5~}^SXl}6rZ>iS|zI5PoKcM<}1a&pHb0~fn1JT>7qhl z$Nm=>H_}@uaL;s^o_gA*9cKNfHXRGA(s`CwF)gg2JXvwi!oVio;wJNY<5MojyLK8L z89#;eN3YsPQIx9vEsAn$|BRwMEYXOc_9GJTFU($ifQk^1gfIPI@zZIDjto_EQ(dY_ zxwW7l)C`mIXwSke;`IRM^lG=jO7SyIDSjwVT+lK7&(y^aXQ48Kp2Hv=KZQ-=GpECA zsf*x6pt4OdZszMqhH)WKvyq#Po z(_XFxHJ>a;JuI37D%YgkTxk3P(_S7fG(KojUY6Vo6Dct&iA*u#lOM+WlLVoI zAcIf67k(B$=Vw&>0Mikl$M50#7GmnMCrGRHT6>ECIDH9TWztXqRC%PQIjslX&cst3j1~D3h%C&Qapww3GkG zuu0`5HmWf9YY?sKG|j%}X5(Z-HO`vS!EM;nzNhBwAwK8?KN%)hthMCHz#gUPk)CGc1iX+2F3O6!! zuF00EW#Rly%^_tRcvL|pm|?!H(FFoQ#!foa{1IS$F{%ZouQKfv_ER-v`*qM;~*LP+dbFmqBqpjhL`hIQKA3di29BnWs`b%*3xTjPsV34Z*98#LNr`4w* z0>jiPI>kN1CmZ9`KfV&=vli*qcU}nc7piHYWW5>A9`|dD^y}}$MUkoc9~MTDhEA(H z?l+dGOnqZH$m41Q)&-_%W>+(dds$r!RUH|@nVsD%?ziezXpHeGx*wZU+>p8pDmyct zS9D_r=y$m&XU2<)elgrS?mhKOh^5Yq@{FQifh=N_{#el|_{4p}hvm#TtLQ%=RsU(xpDKDaHnLH=*P-{2I-gqg zdmVZgVp7~^mU{afhK`Qn&T(2*W;!$WI}D`lIGW`ysVX{$LZpSmf@W}NZw#Oq3rZzu zX1Jw^#kpPdY@suw&!HD%%yDrReaNBb!TIA-Tr}~{jKdE7^KhKFDHeUVL%$gg7#DDv zrs;R+OEK?p(=GZzhu)kHI@RJIaOe$W+6=4ys6$^vW6iYaCmb`kba%11xvt}Us-AV| zZy@W7o9}v^)6YBf-&BFlwfIjv^q|Q0 zS4Po?o%%oFBXPwpT7}MxyPf(pJz*HVrcd>QDKE?Th|kE&l+9Yy!6 z`gdqNt6iVt_I*Irm(%=QV(I^&svj-}z0vgmUrI;RnOia4m$?!#YOFj}??XRvSGcBe z`nakufSkBZt|NRpUsd&fgqgSo*Gyi20^(_STU@g^{g$fl%mUryI)Y}-j6qf3OzvgV zCsn;_Bj{$U{*0=}(DZF}ZN>axX{!4B1)#TE>h5#tkCVH#xQgM`SS~JoekJIuTnl-B zeJ=gU<)C-CDEK)u4!QIPX!*3dDtY~3mkw`Zac!;@oW9$o{~Cq3PS+G3Ir?4tmf4_t zT$G6+5WDo{Qn`T>`ICAr(Ru7|N_J2M`1=|88?@p;#2E)VoVG>qGA)gN)`owVF; zaHVnipua)O^Cs6>&i{l!^VBz^#S%!XU01&eH-cf3s)Vl2Yt>B`UPvbpLFSeqxt@oYc;Pwt!Cf&${#VH%1>I_a1S*G@tnQ#^`P2zNany z`eO7aX}Nx2(T8GmHyGpo93sY)d{oVS1nns^+7f0-IfN6RN}bUX<2oqJw-fpqNx2lI%?_+| z8kZ*6kdyLgJd}ptPzfsEq}L>)0enBEQW;hzm1}y#Ui%FKj0i6p=vn%y)p&wtGV;kosaU>x|rM4L? zd7673LQwLwHj|v`UcUfj+I1i^zf0?|xLrwPDao{Cw8*8nNJzOFMX1T#IyTxA;}A%2 zWWF@YF{{_+ScUkJ68r&3cQIUf$^r5$_fZ7dsi_|V^?h?KdYft#OonvIZKkGyjT@nw zW;KH}AWJ@oI6XC!*eKa+a)FvfW+6+ue~1xGopAvwW7Hb_pT@5s8&UG`eAP>6=i4E&uhSnGm0}{_3(e>7f|MJ0DQP(!wi3R zEnI}#!9U0J8m8^I9CtBt%=}OF(={h7;D6DecaQ%Je@{+o?d)OxRi?^xElLWx_hWOK z_89z{x%XjKryV7kzI&!IHZM?m3w70%h6}MWD$=+~SYV;qF*0+Kb{DG51c%Lj7_+Yi zRxZMDvaUb`U|B~Ij+CrVR?z<)Kpa^MA>5fYy9AtByX(+4>mX(>CTng5-9pO6ZspFJ zK|v#nuBGC$?u6qeWc^cvO|sS_cqC@6gr93!(=q##vT$pPd9!E^Cug0-PMnn0j#j>` z=b%+`){Edt$qHkuosxAUG?~g~=VD>1f$Q5z#WxB`#pO;??l|1lkyWsUl*>UgHS6Nl zP>#*M2%Ku*>j$YpIG!3j#K*KAV|8TRcLf?SUp!2b8Td9O0opdqc;F!`OlUI@tpX35 zl&Vpd6*yv2ZtVmF1sneR4R(EE= zqg;SGeOng9q$v5&4VC&MaHGH!i*)NBZv;7=bK*+JbkK{@%$l?G8zIvjs8@E7sBfxZ zUZvQMJ!9`O#?Cqdy7C&b3jHcfP9R;O^BU@C8O#)zXLaP!w^B#NoYRq!tkZ%Clq=?n zDbdNN0+mVxavT{Y`V%WbE>Zppl4ms!p%7Tfxv?#)Gs#;6tCfH9dSp3QkQvu1WD9JQ zs($Bu(3dFWiO!7ED!=LpthZ>S8Hun);8G<4$q}|GRlg?=bPHeg$kJT;IxOTsheGQf z7Z@(xu?qA7Wjg1_HkuU#{bfrYZKJSy;8u&qHku2=1P&>G;{4b)yRiQS?y%~yZ7xIF z5cq~gpLXf*7lOXuqOpzsl??r$vXuA#F%G_H;>kEx+)x|fz+@dx$78+HP*s{Z8k047 z>In>kbmsIFa8az9u?$POBqq@8AocX)>F8>!qXVmeW^ESw3~Y0J5hU`@1l_nRqB}Acw<(TINElg*(>QXOjqt#m;Z3bAh0|%YWK-*`70VAfQWu+t9B#AmQnNAgi65YuXU5DhHT%nAIEryUmuqS_ zBh6f^rgk&ZO_9ify4S)gdLmt%Yrm|3F%$2>}N?D`}_JB6-m0%p~pf+t-_N$Vh2_vPQ%$oc8Ch?4~-8_Tp;P z{q+FnT%x^F0_txwIJHaD9H9Pg&c$`wQ`qj(&JxAX;_fX5`H#=%5xG~^jKK&Fe zof-QSjXrFZ_OIAIMDAC#-yqhfeOATW_9-)Wgjt%RtotI>9>RIYI@CI>aCBJFx7L7m zS@hkC{us%QQB2|eiv9yElC)UGl>UIC9}0m^u<9RF^tnhe(mYoE5u8t8i%3hfveo`^MW0FiCt2;EQ1tt$|0!1eF-89iCO>VeRsXD_=O9|8`7L=k z-$}$)oHpH}alZ55deEuLLT(M5?>q;0NSmq9$v!{d@#la}SIASH87CB7y$JLyi+)Sd zkC1(`EqQ~A{=)Pq`W;1Yqw(fg^(PhmG#qS{K8*t(thcmW<;7l-j{~D@8gJ0z$Dzv& z2={3hDwSM69J*|T-;L5ZbU9TGy29eep-VebkWu;phkhH9uCz*pKG2V#hC>r~6n(^@ zUqaqkqpaZaaVWDM7XfLDm5rRnq0H~G#L|{o<9*zr@58!ETWQIA!lCz*k2djr8HWxI z-IoG-n_>n{9MUW$&%8=;JE{K{9Wy(dx3aVjgyhqK*1( z6z`AXc%_1K5ai3i+`D6&PoS)Q6Cp2lt2q#+y@^#4yUkP`VQ_{EjOmSk0b^2QLztyE znMdG2-@^Q-a}mB-$U!|BO@-Ldv{`Vw3_41|h?uqti!`H!Drk;Ul0jW%Qf}z^8R_yW zQc5+W{Sw|7f-=G;1FC+11>|OG2dL^!SU+>pAeY3np;e%~CZ%e09+^4Wq;P9$B_dIB zW-`%cvy}6iO*yaGRI8cRi};dBiyo?av|qzonbSMRfOMJ+^OtML}~;`SGvfd*5!8RuX_^4vHQVlw8`OF{cr(ssepe^SZVuB`pe&w$O`x~Yd{9ddqs zt7*pP40L+C^HwyXdn3mYHnR>p4>b|#)qjFvW!>pCt(vU=_!5wJIVq>63z*#qYgu2T z^cbXHpHv6(Zs%T1GVWgKZ(I!W9_Ktx8v370L4Mu&>t?FW)-$Q?y-qp=My%265OcEn zokd)$3jK*Pkl%2cw|6(|_oBnBZ#ii+j*RX40rG^0o#ynl>M<9B{EpM~nr_&QY?0{o zf2|m^&a*%N-6k*Y4U<{!F$KA`5P9?0r(}>=WPgPSjcffk60LoRk^66=`zI7QmSZgb zePmb)9O<(`-E2~BEgn0s|9~Y#YXFb`)=Mxt%1wWcW$EuTIg_=ku=)7ELSY8x;+um1 z8>zhWOzlm$mH#1A&5(whip>8o-H)R{oP*rJ|HuYTRcLw%sPCFGYqTzedjDfIvyO}< z+A>tPqNM~c^f*FyBkKe6S%R|Pbcf`|V;3VAG$jGns{{|hv7 z?FJh5ugsw_?b-@ZFD~S3NY(D6VZUV7xwSQ<)UQ9_DtffDF`!zxGZO-lV886oXS((L!92UlnZv0nUdn`W-ix{5$WF2yn<0b<)(OUVDc6d*7tiYO4_~{eLv64O;2qG3s({Cpmysw^{4U9iy7GTdD4}*>1bG zp1jYZTD5P&%;G&1T8J!#0A^5QGB} z@VP%)jt8S-Nxp9ZoZFLqeK#t#E8uF`du&zdz$$yMog_H0u(EG3mlBP05gPb@hB;NU z_uWp7pTo3d-%N54LXmgO@zFi7q^_22Y)*1Mx+2(JiEub4g&Mf4p~T$DbpOcxG3w_g zy#zEy{UOx_HUdbd=b7Aphu6+cd7sz4g8#laq^-$wt_x+O(>r0hIiG(TFvaap5envf zfriE7b}Xnb{(;xIwO0@(=k$_FJowjP*vWJDTnr&eT@7r`-anZ#SZXsOkD3!p-*+)} z2fE5}Q>2+1cLj=Z6l?K3SrFxTYMbcJ$-58l8U>4-e0nO46sd*jati3#GjfVVZ%*+U zV!G`@z$JYa6P<75l#+1Lwj5rZQ$}obT%V0VowJa1AnF|~pqz4(6X&8>Z0sDWva3j& zL{CmdKJ+qGs60=FDoX`ZUbQ6;4@BiG-aXo6$$3qd+D$INGR(Qi?9{D2xfs;48@TEo z?NRiev)rV-WQ6)}lDNkb0Ixy`S~Kl37&2$wEu4Z8+&LS6MNH3B0KU|GLW?DB+SIbn_@16JiO&m|OAA*(YY<4?^J5KkjE3BrS{NpJELnE)k=Ts(N!bQk~|+NOCW=!_Yb`h1|=?)oGdh1Xj-4SJ)GD>Jm^_npX@SZ6?y3+$Oqn$FmYBmD_A~?bq&40kyRW-h$Lsix{A` zo1@82!Y{b7+>USZx}a8$0FxUw>q@lWVgct~ZBiB5qz#}tp*^H5(T*$!)%Er=qLyo3 zIDc;Us*8!L*FM5j<@Uf#pw?&Y$5`!5WS$>HuKF;V8I2%hWL|2_p}#WNN0_>4$$!UJ6llkWnP!c zRN7~W;EM~#!!&}g+cakOXbCo$1+~us()MFu3l^K2;T{f@S+ImE&tI)83f`YKKXw+A!QA*lJHb?Nz}x(=9x>Nt+jNPl2?&0Lk$cVI6z( z>*;AJZ5W*S)@?tg%~=C#wK<`1-D@xj$@v?)h_QJYsy3P(FzqR7b}2p8K(6b%2D^c~ zAm?skOhQmBm}hJGBLmcYOG`w(P~KC-^u#L0LWTb@hmzFQ+&D_9EcHG(i#wD%0>-KR zSo5I;^s&#h?wu@DOkFVd5F$)yAxZLWU4fjT&{GLJX)P7_uu!6@KI0F`7HVeKZY>M$ zQ|Mg*Hab!$gs&D(HtW3FmtdPh-$q`SjBJ9q>_mbDCojB=`^*}YXV;~|GYdc3g>u%+ zbxNTqC@JUHdD)NNl~nL$;?pWc4^hATc6ialrUPP+BlaV2TMDhO1NDg6c(e8gjHKw%NAMpP zx7v3R&x!`j5x3F^(Z;I~Z;bjf%Dg9fIE61Sh0VPmVU3j}_>yT^m8Q-^%;raTrIcku zB;$8aN_9H)r}2j{#?qN1+#2xkc95RZ^v2O<8FsTzR4`^PMK9y_)SL)ByR4c*6&^l>6XoQ+Q-Z8F}HEI_6auZvajC~BJ0jWFC^Lb z{u*>!wu7v!%|Y*Ft-HC6nMR{6YrBb4s+NGO!LoLH{$td6z>`0KMC>FjC?_b?j*kbT zdr*#1H=u*SDP#@%++|n44oJHI0lch}isYCdViPOtBG0F5*Q6~yTUlB6yQt*1i;g6r zw#Tg9JDI6uK&s@9Khw;5{|wD7$hoK_S&qrqGdH&2FffdPnNCUE_1vk=-i5#5XiaoLE1)l0`nz;OVJAtws~$!NFipS^qpc z_{TJ$S!RPW5v+ryPR%}UDAVNy9Z^bZ&NYJagD$WzsksjbDhOyJQuCe@R1&;h19T`G zL>0K90BErhMOkpzIH1FL9u0f!!6Qka!_BU9qdZ$c$AnLx|T zqo%n*?L?sEv@yJlaK&t(qYQ0vP!8*xI+}gr7B30%F-%e`woA=c2A5+LrdAqBtO|~1 zJ&!SHbx_0>9Y>kT-rQ4g4^k(;i-g>ab8_#gcbw}|4^SFGS4=0V2e-(Wa)NBk>8Xc| zK>Zw?O z9KON`p`sXbdNKIp^0NUUkf>&1pZXv6PePQL0@>NZhS-}B&Qk2~bj+g&i|<<&^rnX>fLMZ8wlCN(5KHzNGG*E1B?6ARoBM&vHbGHH|n29nb}p4#hrIPasnB zcw6ilr@)ydS_Bpd1F6Y1?yqwN_v{TdpU6mi( zrK-?@`gk-h_La<7Fdq6%baCu!xgo~9j~WU1jcgjC$@*Q`wAgONiv=)3`ZZ`y24?FL zC`;^H%bd`w;lX5Jo>MdqV?R6ggW@rM&D(adA8k&K-U1^P`?rO@?ui0oKPmGJJF4q3 zI%7Xu7gKL*b|R%*{QWy@*0SWo+GE#VyW!c5$OQn5kq&QVA!eNt|BN*w(>%wTM= zg}%N8dK()eC$1>B!=MVWVRGOKHd*hO1~}5?Q)E8%QqbX8%9dNAd%)hr##vaZuVDw( z*tC6gZWM5WrJBcsv5BrxwQ~JpJ*f5e0bqrm4yBAWxm?q@#VPGVt74N~vm9QoPwfLZ z#WkyjRoxE5{h?NA9Bqrfhn1WwGRE;hWiDYHBEs^Dab86(VJvjbB@CQD84D@K7D?u~ zm7w$(O8#)EC{DerZuo*OZVk9qa5S-Ju1vqJl#arlxiTG>#yBtX1$ru$#<*ZKoia@0 zJ<42CImV{P1*2Aq?O2O(!ALHp94C8MaQ<9#DJ6~9xVmE&_|teT&UawFox!*yB$rZF z+4MNCB9~Iq80S@HaxA1V&Z{i!x(~*Am1by3?0B0V=T)@c2jAxEqbBWxab9Hudn3({ z^D1-U_r%hN{%~I9d3JmnA_V{)vm@+)KP9a$_@er*;@ ze()*`P~|uOK88vb%~`g5g;TkE!SO_Kxp7^QoSoM zYgPV%8aPTtyyCl5@2_FV(=lO*xqsYWF(HXLz3#6VUt$`kBIZw%k0&wHDHI#yGDe@u z7)O!GE52Ll1!zEJ`f(PHlA)uVN>7=ggrj6HF;8E$KaBj3sBT>LREE@dClcc*+0+i8 zhsDO@WG;?^!NaJG*ck#t=?8c*l~Ic^bcR7Dl`%z!5`KlNM_{N_wzEg2p!(yXnw41= zL-ikp>Q=_>Q7NeYm85r4G)g?0RgeYMtL!Z8F~V~TeD-fTiqdoY@>EGCisEw%=COy; zT$G<%aC6Q+Q52wCFsler2iWW>LAPK9TbyU36r=RIgAmn4ZInuFLL)l^ca_-+_a$9@ zOB3*cR!A6c*_dQ1^VLgGB?#5kn=nsT9%Rply^BkE>=bSJ@eJ|gS-{;a{>0T+R{|GU zjAw|?vX+JF1IcfftFI^kE>e%3!2EZG^)>mx#a3v$!+I{8P-5{9VVy$7E4$nLeh%wi z(}9z={(HjuY>uBEmVa+pe~5uzS*kdoV9z7^L3Vmii#J4c5mr)_y)3>bqVI>3R@vL) zZ4up!>ASLzt=}gR9h(B&H{G6yzK`@J$#P< zjf>BX&sJCzu`(T;1U*fxQyGJwWg z7c}T2eTdq`mdkZu9tB#($?j<19Oo%8Ufv1|OZ5_%{n$zi%k)yt#K%}zp?`y&j~!=W zN8FN0x!o}v^@XgXXw|KeE83gLB z{#-QHEncZ-7X#jI;VSe4FK#EuMEwU-(Nmhv>D~TQ6c3kBu}xM0jxL!A_;)MWsJ^^C z;5}9zam^K9>|WUwqJ!BRwkvkOC+Jj$t3>>NXYp|YPE{PeHxTL3qa}ma+K#W$rt^(uItk!sUG<`6=w{Y;;T>{l& zV`~tT%UhnMW9IOdXK*1}GiGjbjc9_*%VXwoUdHH_8GX!rjA@`~@OA+>4?)pDaXCUd zW&yK6t8)&+=oqt*6F3^3v*56!oiT?_7QXZX zOnD_}#uVh2STJI)*RkA>ru==QhD1i}x$M3gO^A_znGvkPRy6qHMf)vz7T|y@QDna(x%xh!Gpu~SrCd=v2c3h$YE|-8Iq|6T zvC>PvW*_D{`kIM=|FkQIsD>qWlCN8st-G`WzF}dW{t(KTd{cZ|2vASK)RKJ5E`D%K zbU5JKc1=>MpK1eq$37ylkdA`U{~m`;F%;p zaLwjRN*@9RO73uZksOYo{sO*0@)HXi^*5}>rxs4vbzJ~Ia}SY%=4v{6$ zeCP7CCVfwRItohu;NB3YUzz?vtU4GDQ18sbBpN%@B@hR^gk z#T50ZnO-q`rtc2|Zs%=*$i-*s4??now@oUJHOhxwfwL{%44(@UN#@8gOs{w=EfDoL z_opmuQ1m;S54r?hAsVL1#3!-+4O(#e-EGLFfM{ zC_A_w`rL1A6!QX1LvRAjSicKO1#t`Ja}*R=il2j?fuuL9WJ!p9rN_e?NOqTt*_@#^ z1%SzrQPrr<;~?lE*QmJ}ay6#MWNBy>noJY?BTQPdr-dDL2h8lrULm8%dAe73z}}(X z4kL4cJ{RU8*(WsY2*MKmTp3{BP_@8P-4E)X>=$Yjhy%h!fc-=B1eWQiB7kMK8s&OE zyLfmO>>J^>;FPUlB0zxn+v5J z*OeBpQTjtF&KN05M$kgit3uo7QjsoIdY}(nZLi>C1ihXMJT7!53YQVYS7#(^Y<}3R zID@sR4J||$VFjY}^>7iB6Kwu)zAv5tJTYYU$acH>V3^6|q|kYi-_Ne@O3Tuae&vCu zhfp$&p)*CX@y3e~G$=XMzEJ{iyqL%It@f1$c!R|$v=DPc=5h+&VDTV^a`I4%ALpYQ zK3tZUvn+z9$pqZP&Yi0f5od?R83OC+_%E?6B{K!N%@liMhK(Vx@vKSMzc9nVabfZi zR?GGG44orI=t%V{!dZ%=B^~pH#BjuzJQkzAVEh%)U1Sl&;bTZ_W!iNN5Su#=3fnk# z6i?FU9JX|sGj_DG=T6Rog~vK$Q+5Q&gX6JS(@;m^K{1Ta*fCHPplo?SG2F364n`<(DaQY;mR6nqB zGEPi^D}lM4$#M_tfGn!Bk6;!&JW}1!Y-gBbG1WQg40$oJI@j!#tkNUMPT=N7}TC zh-U0*Wx6S@|H(o7j50lwt=prF^Qk{*iO1>;7YT+f| zemrL2+M2`TlOdI@7#lT5q@{8mG_qz%S}K=8&^1S<|u>8g2Pc-&Cv!`1m~dQH7krXQ%>&B=#;#gQ<^5DD(Azl)SPM1z;9<1da)VSb zc^1&%^+I!lGvR2|9&9r4gW4RRA?e}@V3KMp49X6cKz_AD4ay5*P_f!!1{DO&D74l- z1uP9lLPoXrDPUQ!U@Fka8>PI8pg)>gJKCTT!CdHAZOYUo6`X|z)m9obCTQ&kG{$gN z1<#-}YsZ@MYJ*XefvOB@3@#(8HfVaV6`EB$&ZL_gd<}8d)|fmO1PhsG?I}{1Lxbf+ z<9EB1(qbn!rv<%Gd+rMqU>=)(p2-pib}{a1&o?L<@WfZ`TH6awbQ#P;?FAHj?mtji zW9>yJHY0}?b-31Z2HMQ&0Lhm&e=wd_j@vd&5OIR$IBM-wW)?R8*LGT@{eC=hX ztcu`2Y|Q0p;q|4s{$@}rxF!m;!Jw+(dMt%%uQ27+25&-dYOgeC0!;2{s9@2@9r0wZ zCaNZ*qPh!JH>T_%H=RpGYiHje5Y=yhzb4DVY<(uFW^;~rYSxwmwwG-ldLETj*}y(p zs?aG8tq!si$V)UkF`#R*6`dhmAkt5exuZ1(wfda~z#Kci8+9CAS(7UpQaID82eTRp zb)IxzoAyxgnoepl{&S1xI??B513$!*z|jxG2tNE07;|4i?NT+*{sb;F%%7Vj3Gk9k z)S>2igQ9^9^KAxY2ZiW`nimYp3uMs0Xi$L}^e-7yY6kswgUZaHe|eIqRD~JzuNX7} zN3YPu6*X`3m8Ah+y;$?kHUv3B&t-A%Zjy%i!QYyI-Z$pk4*Cyz3k`?h5}Y>b4O9_nJu)cS6$ZE8x@tq8N8-xL7$R8I)>bt5a*OMN6T zs@r4gsp+je$dSJJs*!+wlopt+uZF>`>1(M8{Vi-|O+PhSsCoKgEKqCu+iK_QB~-jJ z)hg5iU4oHYGe9j7Sfa;MjR#uhQvETjG04I``ga(FnsN)v^mpj{n!#3j<@#2RpCPu+ z75V}wT+L8h$q_mNm$+uQIztLd=?O5YHKWwE0;{aVD2zBgv$QZNDI-h@Mo19m-I-X* z$0VStrBgkVq3~sKM)b&q718~3>W42S1usM5MhcPnjtX+5>o zP{1m+QJ}B;vCFG7YVBZ_tr@4D7HV97+y$`4!fgFEe4v_I^{r47dK~+ByoGuC?lQm$ zcugn^%Gb#@z=^7#zyjT!<<_Yg0!#EuG$fNOdA%|392) z{OK9`n%H8q}+p|hoNDT{H)gbq~Lr>7J4U!ht0v;vFon$_wfM9Gz`nv*h)=hfKqs5#kA zTfSb!@qLPg`MR(W@Kj}Q=*bKAYEF}U_}F{wAW%4%<(yZ zNK8A#oP9`5W7^jC=vIrvel9?Sr%3wy$-eF|pfWykOZIcwZ3B1^I@#Z)`E~|oCwsYk zo3CDUAYyyF_9D8RA4vAG(C;?y=tWq?yLsS*Um*t|k^}5h{@r5 zJ{BIyA?~$MUA>tlR=ArHrm{Z(H!(TX<@IvT2~QjhIL!T4U{ue8Q#6#|g~SoltbL*1c0;zJ3qgmYn2rE~hgw5BrYEdbb)` za2sP)46wodRH&u;&3=H5Zq^)9`{>dcfRo+90?YJCtYnMZBCuQ!DF&QoYgM67>;yR7 zJw~V_^d^Wo+3Kznn6j$&0NQ8X;l&V?>QVfc7zRuGUE^zC4b85vx;@VWKqmVd4Twn9L8) z7sYd6f{=#Oi^-TG|G(3)De3+8lO)Y_WXgUqwI@P$_hzzVrx;;zB@5DaA@P(kJIELz zIc`PGk4qKl)qwNMOeX9*lRrr&4J#h!Ta>`r5p+{~cB|o(np(*Z&(PViraEg`oGoc) zhR&Y;D?PG45fNd3BYqE6;c!P}4gh$>ce9t2bNE%mZ9wH@>kfrP7`&Lz|n|>jwj#XVaGJ6->L< zGFRx;5JmDrsS?f5Z0hhub_2Rfzs*XnbKgaUxtBe11mMM%TBqA#t(CmQ=G>^S!3>MN% zG0_X=9N~`5Fr4$@qiAJOIRmfjP={5Euoz=Zxf3izF6&eL01(D$L6gqp99902%3=mmiV`i+AC{~h{DV2R#C zQ}|QJU(RZj>KQa=KZgng_R;l_Q}REdfdb3)H~E0Sgp4m+t`&RtR|_lj+ib#~&?I3V zq4}QCG}zPzlClRSfv+X#g_a%^n$=z-Iwj%8~RFMoqmC7{}=L)V%kQ1 zLKEO0p#p);dOZBGVtr@dD~=L(GL;qdE|uZA`W%+^!mfUjAIlW-jY z{~3BksCoL^0PywDe+1_160CfZZ-lxY$$|>>(20O=hK30&(f=I<_?CsG`mB1uw?i#L z?W3>d4EauIxj;M;W)t2GoiDIl^O{2PJxi_7O)TjB(49gZp_gEIBtHl}Com?mqt0y)_(^D@P@DDD0{}m@X{YN) znf9~LF+y$A*VO@j9=cW_uIh10+!=aG-~x2dmFSF!a|pWUR=5XqlLbDXDCr_rw@|_y zAA2z(l1278vaf%u1T3~Nt}hP(miU_wrA!mrO96J5eQ9nMv;}}k3%lqKXbgK~9>V{d z)KcFZCoIsjIo@kOZ+m%J-Hxx_P#ay0KuCXe)rvWEb}&D{9+5+DY_qlg5)vsY81`)?<9|vXJ_md?pi00lSgMXTc?c%TxDTYUpWcz zL<{kPKG?tHY74XVHyr>^vM)l(bNWY<>pk}1fZcsTxLBU&4cK0W@Fku+`W^Hpr$Eo= zE2oS25F?rl`FoH;KfzwY0&bDCUaw@gMEnB<^2Mkm#Hm*D1K~1NmLfwsrUSx7DJV`s zvYme`fL;mDKAGh|jxd|Ls~uoGovA*ZgS@@}p-`iy27#?X+|;0hWzN>0^apdcg$ey> zIbcVdbDsX3GR^V-Ct2lNUxUT&S7p}8xFIa_FH(B7@^ps&E9vsXK16HT^05CIqH`Y} zk4=~f?T10l5NX%mvlBm-n zNd#>i22TQPBn^xw4;F1UbJ>v05fENoOjh_ty`oP4?BpQ-86+4`NO_n09>cE`AUxO~ zhj7_Eym&l0)ISnor^tnyl$}%|jxo(w941}+XwT6n)BbrD`ubO@jxU__kXo7mLm@Mg zxrxL=!+sZJ6xj}SfNRTOA*59F;B4x_i(x+5ls9fBUkZ;$@zjHvA>^|?Z0e8KlotZN z9Dej@QlmPj9`M!hhNB2EmZ*uZh0P?BEhoT||CDTLr>0}^m3%#HT!=i)mnJ0N44*G! zxIpj0f-m`225yIJlka5U8ag)bW?<=D!1pq6FKx~HX^6JecIpcBPq1)F9o{6>DABLdICrzKR394v7KGmtY9GB51}s?^ z{*S;iy`vJa$d+5Ke~1AV+kz_e321GydpKWuW`w?KCScOSl&*^amWIa(wMzey1K2aX zTwtx{Tkey+!|MdrL4GNSEaDtaHJQlZvG4%G{!|8UhBuv9fQmx%7cpWcei9=FO2jIJ zany}5H+7bnlM$99Nmn8ucD9EWoxCcv6LESVy^D=PqQb4_fVtX2U!TcVUSnZY zpUawFD+$fsD4)~~%4tIEAC!v~QCR(w3P*(`NrQN$;kW`);9cEaff znRS|wsqDyz$;|~7`bCB=TRhwji1Q8~n5r{O^p*^hl(sL^;Tb0SQ07LAEYW(iUMv$i zT_j8_o350}3377cU!y^wKVULJ_^S+^A&|bue~G_ArO_vE3LCSb&t*2_WaT^tQRzk6 z@502hW%R^MS^Lrp5Nj8K89HC`gtAf@68*Bj@&{>VhD0CDHAI%tL@kISvB z*JtST*o=fM>D~;9-ka$~X^^FF&(P`4nXE}lPj$P6&P6i)J42TRtuSS}DLt{o!DO0F zhc6vFTw<9C9lbagSSBZ`f!x?IOzlK!z5{>I7%8aIZ-$_Ax!tsaI#BeG6VhQ z44um+Bk7FH(&r4G6(&Y=F|`kqJ%{jhCKIl%{yG+rJ~Ge_v8K6PZvB-W<@d^vxb*sq zB%=xR>I|K0v3=;9O#2pQ=vzP!3=`LA`!LB4Iok!MJ2FgMx&8kSFuW>s z4i+xu4BfW>dyujemvnzcr#D^NAvQ~K4v=zDP!eGy4KCzN3cDv>ks%#P(vujvhE9m2 z{Tlc?CBtH6Iq^YSPe|iP<@_Oi5v4^x+vM35gNq4@#kN$5bJ# zEQZsp>@XwtScJ0_U4(SZTH#}soCnjf*JNT}V62FaA!P9?{!3J(#J)X{VdK1Lwz1c7 z5K)WOmdPAw>7;S^k~o?AF!2mT=axV{FW{4Ms&bf z1j7vao5A%X{)CW&BRmJ-S<1wNc>N{#4bIj?{WhqWRD+x{pl$~F!R@f*6AKK&3qj!f zOe{1g9y~Z1sE9dZH54>V0V@7fP{&|)7EsAcf=YsQ@QNmOH>lLfy)K2y)kW@S;b%wj ztzG%3Bn$rttERfxM%36Xc7tl7b_V&ub`(&TWl-3ht$GGINQ-cnpZA2aC&i*Gk?B`( z0Vidxmu#G13F&4l4Od*I!B`UtLk^Zdkiw= zMpXT`i;pv6IynjS{TYJ%pc$>G|KUnO(SVx~^*=r+2p8Nt0{wftpzL5ce7^dhJ{FV+ zPDJO_|7=iRz`d0E|NJ4e{2+l|uK%^mDwbCeoYMxh$8eSeULDYX`wOi!$es%Hn?Zd7 zZll!y-Ym4TfZHbZ|2tk#d2lw`Q~&4Xg7C!vs7k$~Or|6B-h4o1VM;fJ0bL8LWPMxj zSy-#zj)Ur3Sf{(P(2%-Ua&FW`Y-QL|oAq|cygp*#bX^aj*GJVhVQ$kWz#FNLsT~66 z>XRvjcFKrvfgX(BtH;~wj;9(#>m+pF#Zm*{|51!|l?oKkE7OenJvxe{Zs3iaa6 zwYdCvF?2;YO)q61-xAFn?^u~%i$RG*i5^3Jzu)OS(#7M$i*Xnj}3{YoxpxPGZW z&_0N-(w}w*%$K)6aJQE)oUcE~!a6;N-E8g>ahvWTw!vH_!pofWeUzQKNyLK{LwW!f z+G@0Q<13x(i!7Y0e;Nd8u|0ONKtGIK%K8!u57p~dBUaGAX* zc9)VzZ}kT&UJjIR)P)N`A7U?#J-`d!97$%@W zEdCEtTqh|wvi6I9OrojP5)H=J5jJ^na2aMEuur>eJ2P|+H$z8&wW3iqNjbjK8FtIW za-5k2|3A-purSe0>Xu<*2qexExD)|ka^ZDMlM6#2(GuhJTL6jM zFhyZ;QHL;wm!xFZN695NJ!;zd=VV&i5 z<_${?Eh_g$8kQLp7bDxS(ipvLF|rNE7)zE2Xnq=wH3+Yag?Vf^?s62ySG95fx?$B8 zK?P!R8&3F_pb{~i4XcgmEEUt)aI!I-eZ+J&oN7#GS-`F9hSS0)GSBjW#<1ZGQ+^<*2~fLznC#+kH|SZ4H8(U#D_#!kh*IJp<(7BF^xd$2 zD#G&Mr{Q7-*?W8^MZ+aq& zta*7&?sM1!s;I1OSWQ;}?oQ=+^MVRtLjt zWKdbq9|~7lZ|YEvH=+)LFH-sVr7Yk#%wLsHo_LaJ@^6hmn=cmRi!)I9%uRx#!8Zk< zZ8eCma%FbBUK!^PnsNvJ%dJFxn=7AZemT5yU%8D#4AL|gvtPKwX3Z1Hl`oo>M1v4~ zm&%t+{i5b3^mc>d!Fy29%9qVMK(d3ovVmSnzY%03TluO%1?EEaYjlu#?3f>Bsr;w8 zGt(#N+Yab;(|c9H#~5;zZ_ut_HVi(4sjYm|pt|5T?AlbmWlHCEKBbhUC=zLC+9scd zh%7~Eq}#s%;jn)Xek1ISXj|DU_!1?l^)}-5?KW6Z54P*$wV@ z^lV)qr)0$zJb~Y_d>}V@B2m41x|EJKH&WaAk%@RjfJZC6u2R~ ziV#<%Y)QHtj%H)Ag}(lA2w;hYQO#F^HFj5~B5^%E1(;MyYMHIK6$AFL%nAKV7r;^r z^K{LDfIThD*PGzOHukcxKz}z1u(yRJ&Y+i|(~W)98OS>Nf4Q%;VNPi3^$@~h-J5!I2}2pSgGbfW=Q}~>6W~pK4GQD+hAW+>e*KXM z#vo@AQGaFuiROJM|7SbVOGhAs?ppxE{`2@X)galNuaatX@|()Sr{X*s z6)TT+ng;eau?P;j3PB885Ti{Mj1Q_{%9@56oppjkVc?sFSxbe|27@KSTys}p6y!CH zVg@-!&RgX)rED6RyqYR+0fAGQG-%9z4H|136dZ}s(o|*AVJgFzYpP~Fu@jE6u15}$ zVfYEllezZ(N^nj-iCyaUY7zvZ%7k<7M;bb|Qg@^30S1S1<-3I{dNwdTVOiUuzh0v&mz#Gr7no}8Z=6cNF+d}eZqieOqk zH>h1uRRqqR2E~I))T`wSlMYQHjoaZUy+g2;=u3letEeB)E`vJakW~cN%3C_BwP=x+ z7Ud{IbhI=n*FvRlC`HOn$~H>(gcIM=*;0Kyj`<#7VMtG%2$*LfzE`UOyI2^}|E74l zT8LLT^?^l=wH&Mp&ra83h$Y%uR9L8VS6GRbVHUdjW|lMDLVN}qiq$g0LSM7rTSi(K z((L$_Q5J?Zd%k6~g%SNebhRaAAu2T;V=~rKt8UFyYP==dN=>j(>CcLhw9Z1;w04q( zo^BitYP}VluMdPVZE3L7u>LRHik2xBMsyEWx!FS0;s*3yxTU-6oRbz!(%r9vdRVCR zDR5U>dRk~}(aS=7VS5y)y^k@lDp6t zH@OGn!AnNNU`q0yV#w)!C@g~C5_o%=;zB5rlk7Z>DIOci6tBZ(dC9dtQ`|BJDUx|9 zNHEDa`$m#CV$4RJ9{EimPi=SL8YJF;`NB!wd=Rr}?u#s(Xg#>5X0w2(f_WR$H~@@z ze*%8HC?=}IpE#}NS;1g`%v7}jami6#nc2q}3o1FGjP*&uVtdIU(t@+#QiPJp0@mk@ zQr72>u_z;XADR?P@&iEaoZQQiAb(m;FW5{wfLU;xc0AIjQ6d}H&*t6fc+W0=P+3Z82=f4Hko8jv`2fuzRWQ9EDZjt z8Cw^g2d=%4^NeSAo-Zv5{)PcLBBt z-|c|@X;4{kF7#!_>jvR_XwcaiZx~b&Y$NBJ28{?_hxaw(ErU|lJ3R&skMjr8J`w*F zwS#kYUF(U8Z1RSY*42u1baJ=lPV334=fwoRykfugRAqbtyas1BE?b;tw;21#zF_O= zs=qLobz8CUNT>Bo#qSkig92}iTH&;=QSYuLOliK+tMyzp>q5dReGL{7t>?=&9yc#< zf{ALqK$QzKZjG~`i`8JsdAj~L6sYwQ#iu!L@m$>#gRb=oHC(8R^~)G{tykI0X-o9^ z9RaUaH9}pftDz#T*Qqll=T-VoG`;l(WsZif(yzf@x85Xg9O9kw-wp=6*=Ds`KZz0F zdaG&=C6bpi%tVK^-lq1fBgPf-*Xw|9SI1sNj4R|k^VfQ(qCRnN6XK@MWl2Q31HJ~a zdvA;uf5seXZ}J=&vlmY0n7sre(M>)LS$WB-3fhpmD93E;By^rrv5bD41^?}ZflQyJ>AyQYc5~{8H`31tb^ zT0R~`)H7(Hj0bO(Jp3R8x25&qkZ46Tn2IK~4jCgT9u&YtwGJ(YbZJHSLgdzAqXZ>_ zt%X3tjh^Spvyj#i2Ib2ZN9#y4staUPw~n46=}Kf&x26ndX%5Z^w2ql0q&_*&{Ho;= zE<-CQ3*&mTxu$_^LfY%T39(^+Ex3xlhfzwj9<103&4ohi5M|}3xl(AYP}|pw0QJ+D z$y$f09|dM3gBOua?j*P}iPo#xZX^C{_7nfLw@Iz6_^;b0h>5e1z$`#HtVF}&41shA z{>vSPkx|}y0wriV;Y8aBc#Aa#=V~)H&6jIiPc}Y&G+53~IK^;cF9BNEdYTW-W+#Z) z&oJUk7_pz3?gTz&YCX${J>Q7^Y$NspBldF)XGtLAW(|i8Hg%*E&fBLG)?Oe4c0z5Y zf$VqFz>~|Rfjtpn+Riczi9-RYst|#phu_HIh)LX+hoObNV2NHWzo(Pf2g5nh0}}#> z=ODs#H-#-yOfSVQ$&e^{L!xxjny?A6xik&stxsGC(_lpXq!FMwmDl=|5w0H`Ld&-0 zS+H@|6zzZ7Xn#B?!6exFj9Faa1}Y8LvuS<*eIn3v|B`fh!AqD`TDScnC_jj&fL_>7 z-(T8K-|cKqJFKNC?YPy59&x2+{=m?75v|RD)`4*VYDjv=UsxRf^4vPdBZ0N znQmYRq|adv!v0GDSz6I>934%;>HS>iP441cHl=g{7VzHcV4gH#kjOtkfARgC#b58$MDoLFd>M%^_AxJvbg zn9xioQ9Vk;L)NgLjnrXzFBo2#fpFq5m`7-CC8)ViL5s7!A!i~S#M@!^sNkxB<~G>` zG&H@%y$mYm4cjCIz<`!7VUV(|v_huZL zsZJ}Gg{)3hfTVLs;55XoF>fBH8`>mk;e1nM!W4OkDTMANMbcwH3noSH(Dg{4{1D3@ zc-=^>k}F3bi{uqkke!oz5tat;dUrl}DTGnb7g3uSWa&5c2fD`~Klp|+ypQuNhwuwT z4?QNF@t_BWxA%xCJv(@exjec=YMto4ow+=gnV<7|KRgH#kDCZg&w0HY;Cg#cmb8c*wu50pw??(0IiwzL>`l~()~gMQZ{>mI_1j@S2Ns`YxSi;<9zxZmmo*k9cS=oP=FwCKeE`?kr~ zTrJ8t&_0=d6W{z{r!lc?u5@tx8xZE7;BIIp^~HY#G5pKKZb7ml&ZODiX!QXodU*+o zOsUJurPfYS&%s!5c;nQL%RyWTHTP=L{<}}6D@3CFsTu+PRxa`IzS=?3u_QF$;Jef(M#;HdWoTo#=tA|8f|e2eFOXtZ;E;n zwT3F_Cs}&4T6HC1ss0Wl+-tG!Zy$Xcm2H|$TdsLw&YNvvg}xAeoHxh95qiQv!1;>j zqTud32OS5$VVmncDVgh2qM$xynH_x#2hC>nD=J4JOoOxNZLu%oPG}xV_nuZO|?hVexgY zew}0WO?A1@@p9%6)4ydgUe;PcWAKi;#nAEoCJwy!?8{?s^K=;og7?1kwO4$Hr;mj> z@;1i=nzohBD{-6l-UqzGfMS5Rv!9eo%$h%1JMS6UJnX2`h%&=bZhrZsG0{)-kvsk=g z+}D-V(?8O$DGur0U4j3!Z?N4E(hE2Slw6BM`$PJ+slcvFgO9h>h4gSLfoJKDgbHHp zw2*78FFNhUNVS(;8 z7jUW9SJIZ~W*B^Lxwj21r?vT&#^)#z1n#31d`{gx+OvI+vrz@pF)w&4Yz$`n#RV60 zh^@3SnDQ6H3#9~DLY#9^oFR11Ap93ueg=aSNS0z_g#$685H{)9W|NM^rcV+#X6O`x zq1(06@(hUrNoROI!bPnZo7vtD?;8NkPl9(8mtkaL zs_nL75qv~{E1JrUwUxARPuZMmbsL6^x7j!M%IZuIW z(0|E)QR>XEp;O0-u7I%1yn91zijl~Dnd@Xlv<~-&c&LaYo<~i*e}wE=6C>)!LdK7Y z8sR=})5b+WPlR?zVcGiLgOKz|OHAk}`*5>`dHOn1w}ieB=6rdjhWCu67MNyi4Vh0L zm!RG`;PbCX<=;cV9Q8?DfH?%lkukWGgcj%i3S}G7R{ZmI@RWI&vaQ4@6h2pu_Ox|3 z$Pf5_^S0y|QMRbOd$_HKp~Yo`y{*)s>|h|uXtUpc#c`w*P%lHno7p-7^)@J9j>WX~ zK@B0df?y{sWm{j&EkH%VS~$>c{a7uxxH#wqSE{YQNmn8VXxhq5y3*iF*x$AR2K5SB zpeJnujn?!D4u>kY(LNy;oKnjHDmQH?5AKD9Y#R(u3A76HIMcu0&MsJ&-Hqn^uI`Db z^0(0wmNC`?IZ$xw( zj806KvqEm8IV&_hcyS_lnpR0gmIoa$NL;&0T^YflxA zu{(`T_3#Cg;9yN<=*}@|@#Toq;q3eNWc7aHb!RIs-*;Grhx2UKuw2f)RK`Uu_z*bDG510PobzvJK@L2E3_ zK^|3em!#K!!P!tB_eiP_yeSogne$Qu-%~-d6mXe=@2lWr7POpw4_8acveP|^-Zj7F z5*$O}98G0_V6plxgpF%>T-d(#PVuOhYGvc#xh`7Q;gb*Q1boWZ53GIW!3qZcgpdeVu{^T)NWZog@GZp{y zEs;Rk!7Y^PH3oGIuB0MdYfw%wyA9|%gK~{lUSBU2PRNH%+#Ag7gJYW`zD`(FKyoy=*8~Q6I4J0l(Gfeu$n2GhSOf7yo}`JQ3eC<6~2S zXmAQ=hELL)H}tdIPmPBrXV7xlBX)my zS7<9`kJ$auc#u|};qZcjYi=aS`SiW{z~)MVSB&%Nyei;& za#cWHq|Lhmt}k~5TKRIiG$$`z9{;60l-WTE5&GD7rIz zb(H>=iq*kld}w9kNZ@RXH!Hoe0Jx*YTe&6E9g5=5M*jR0znx#kpiK??bhM3U$bO7- zbfrDY!x3Rf6uFR);4Fl*6gw{+b5(|qZHTiF@ZFt>W%rqktxNe#hQ!`8r+RIwj}eij z*p2CY{+nTDZ~ny`-}kJ17D!o&J-82pJ+)pYG>TiYl&9jTUmYR_`?Dtce?wr%l<^Ii zRdV}5bjc9bE?%+{#>r2fnacplWi*DWpL`Y5VJLYG=C5$_z*)#8`4f~rntWyy9;-XKha7-YjB0rP?HI%K zMb!xFiUvbqHq=Pgkd}?}wi<0lUsUFFl{t(&x)QXp>ro4uqA(hwY7A#WJOee+puFJh zD$wf8jGG_uFs+)DK1@3kx~uAql_(89!z7(XJ;i9L2KE!boJ1?D8clg+!9S3lnqux! zl?S(CL@2wBTM?`n2*eL*A>D`|Q3N!@Ou?z(IS59zn!2QdMvPL$4NP!W1@8qwZ3fi_ z*F&6Y)<&V#;T=FZke`}YO_9+Isrkk%IATuJf@vT?WKfDGgyQ@`pR=oQ?-QWn3QX{! zMP^^%OhgP_dNeR)H0&HSEwqS{U_KB3MJ~cm2iBxwHB6;HTkS=UdG{c8INp%s^V^*8 z-!`C)vm2E6AH)wkAp+2!grUoEuyb~QUZ5OSg-LsMfBLAy+Q&1&1E4&!`_t2NDpq1X zjhvv!;^o`{J{Qwq7gJFU3nNVD>JMfcC($x+^M)9mUvi$Y#Dk} zna7uX8Nnc0)Q0~ed|*GKtO!Edq`b4pBYx8+j{jkUr!&4MxSf&5qc2IL4GGV| z#QXuS(QFFB>J@PNg2ca=sG|cs|}qU5T;h{oyNb3(Mzv5Qq+wG|>A~mSv-56=rPaXjx>b z5UVo!@QFxm-eoa*A=K9MLR`9xmQ{@}JWgsaINixgd7bY9X$Mpmh|Q8B+$plFHJTqZ zcbi4Pqj{wOVe*WYUT9G?bCrj|#gtg5;!0>|e&>T5~%^Tat2k#|S!w+*JXR|U@V@FmX1}$_( zzU^V?U9HR(*%!!p)XHUy5V`yYB|wcuBPUi5q1(K=8U`p=F5A)Gg{0Sm5i2suLnH3V9v-C)I+tw zp8!y^Nxl}DB8L4k`ux6`aP6_2eP(;)i9$Jj6$(eHcf-!9IUZA2@2W$1o+NbSqU*@r zXr~(M$sV)1C6oEseKI#;lTWor18nlCG5L%fI15=EW$X7xCX1u?$-;z9{Z@G7`G4xS za-aGgvrqlTKZgwl^tDp{lqbG!F)gRQ^-DLXF1*yT@cVF2(-}T^jZ|JvV*B zX|FV_QefMFzccXn3M;b;1_1<4G&dq{@`sZQL4`0}@Grt+#ZB*b16O%iG3g%sZNXpr zd(z3vCHbd_ljI~Ic>>rZAMbTS%mVXKJtkkS@X2ug&n!e73&IpfH^kTd3oeE_G)(I| zkXUByMPV+Cnt-JUCPWb!ohX72TgHFWf|ymN2xh+>fBgTKOcAT3h;@jo$BvacA1OAGwNN4(EQH3~2~ z)p%14R$&9E{qT4Bz3G;Ymuj>k&a`x*wDd?~@i^+_oj+@V>yJJbE{?#hfGvD&s;UqF zd>wjt{W6imEyxyfs6Yi8{*KC2fG-a~O%G3f8Q5vuf?oyM$boCJ%T(6MiLge~=F*Qj z8~uuO8}a9!gNyZHac`=H94$3Wmj zwg+)_G#%=i7;Q%u_-4?^sB2?1uBt^^a6giv1@(w&y%b8g8_Aed-5i?((#$k&yBS1< zF*}9c1v&N_uBm<5!p36!M%FLRaz5#L?W|egO|!I{*1QU^H;SLSlzE^e5e7>ZVYGK5 ztb9}PKu|A?D7L5$D$#)d-?|^I;v@?KC)s70R;-hw{c5^tR*X@bWL3*^iC*Mr1Axdg;Y5HTSIrEL%=u}e`;go2#^{( zBM!YP65EORA4t11vL3XVX}rJ0$nmq`+D~G0|B_gm#Y!xN%Iq&O)=DIn=R_!&@q7=e z(q=BA#8!tKX951-@jzM^wCKV*#7%gtQkZ#D_C{bMw*t|PhloXPg)z$QZD6DBMKR{( zu3u^_U$J;sKZ7h{`W`fh=@^JrGM zKA4uo%Mp%>D-dT|{;FuqUBuGz*FZzqap8tx)Xou-N^l*&P?O|HG~|y4A=jqA!!z?A*Co`e+^;1 zL@o)KWfawPM*_vRMCG}40!xcJBzXf&#!|FIDU(%*n{a1$VdN+|AK1ufT9l*ec4Cpy z^eDCC1>!T?gMUVJJ^1-a1fwmj(VwrQwk#4MeQt!bfnuO`)Pk=We`C6=-MM~kz*0oc@kg>UOGrhlb8b9e;Q`X!D!M$l(K(l{0Z4Y(Dx6Aj1% zVI6=v%D)ICX`G58LUeiwsF>Xxb&|jDyf8IALD$h=dC;gYo3R!tyW#JFN77yOps4R? z#F?&nSk!kiv2@KNqP|B1&)D1vnf*i5S2Y{uebgwgG5O3CRevm9^}Q%?8!PunWCBQ1 z^>xU|DDQNH7T{045LpiD%rxF#dC9TZaP6nO`%DOF7OTAXfIFkS#)r5QBVS!9TpO~-Oi^^9@|SMn>2s+WYT7YzkRZwXgb-#Hjy zpdoCaS82jnFys^feQI=2Z9!E=Ns*r##gl4%CQ3J26z(%oxY7J*wE8^4;zvoLpNrzL zDql#bTISb(MVe79S$(N5C0vPxw%R2L=hEqAiHdcwE^jC7PN?BgMI{&kW3wCoU;hM# zg9v4~2&GHA^l%s{0vkdsKF+9UZ{)NNSUUP%Bt%Dlg1FgSx35HId8o3gjV{MHX#Nv% zH-fqOCj=g1;7bHvVBiA;K4sul1b#+fUIh})&%y#WD+~EKt@l7xUPFef|o$G1pZ*ahcJ2|yZPA&Oh!O#%$q1= zI&0k{`V(u->Gd2C@j@WfD<6NkD0}`vNb?*M_e9_;(i^B*q_1M?LDA;pf&T!d`A7uH zA>HPA2uxz21%Wdd7>~fy2+Z5S_MQdw7SQ~Q5ZJ}QRS5jfz^w=z5n#1+9|9qdBV!7; zTs}lg%20?pDB4&H?5=NU9)bGTtvWQf9LQoCwvr>4bJD__mm$ zuJ6R(ZD79n$+Y>uP5iiRh%@H@4)NPQ0G_ch4+-xS$4pH%=KijIJ$z;Y-H)ReMW~k| z^Xu@Z?vGW1G&7AetrVe><0iwk23-G_QBSkkrv8o!rH%R&t^yuG7LPNVhhlTM3=ksB zjxqQTLZQ{gW($LD-i74dvhhKSr_u)hVvh#D4sjEC=^V^s&|8NCPw03s5?>;C4X~L8 zFY`FV-wRwX%eBirTBcV?7mwv{!v8JlT-|MuO@qE2t(j=Q8CizBd?b+p_XFzm2!OiG zTYxIbfSU+rrAsS;;2!(u%LKxf)*bJ1(GEhbW%S6D8(Zf9z63MD_ ze6Rk9$uZL&i(d@yX%^Vqo=sOFM`pnDScJ@iIWh}g4LnhFEH}cv))z>ZsWw;Uy9bG|vo`G_xEFExIPiBBTuUr- z-GSoVodhgRT!M$u|XAgu=jg%m4yjL{5l>O8x zGU;jCi?<*{V=?Xl^>O^E?vWLs&P?O|Ee1I@8?MKh2hH&7$U|)7zYq}HnC7wu!|4nL zn&A=zY;jR^ZUTR*SL8Dmm&W@SM~*zh)%zJ+Tm^HZDXv36ic53Z;tow0cb+MZ!*~fY zS;dShB1bSI4&!Uc$65HSWT49`3TAC-kAwp zC-`^bGll_AlFlxHb5pm6cClWRrx6&pcQ6C4LT+#3PtA`6TTuymCj5G#cqUgcK+ohZ z2I!e=Wq_W^I|$57Cl>GIJH()S>DTT=hK(*VT@)G2Ou6#zj%h=NVg&-uZ2Gmk!M2!e zhel2#8-3eJWTSVx6oEN(ZN;rUo6&S@uVi$_t-Tw_=*$|Z)}{DU$3<>MUNh5p|4t;w z2E+9OOQgz{EiIN8TsyvDb9y}W#dns6X^{7pP9y);$-S3N5XJP zQOPd0s9^|5QE3iaR5KY^)G7qG}XR9s+~lf zsrE%O4b%WjwaJKTPeQfDf^0{%`8G0jQTQT|r0NU7>`Zwd4crUrbQGa33D4ODJTo0J z|7W1H!Pn*>Rmhv476Tc!F~4U*bLi*tpKNK2f3y{`$KiP)sB4kuYxuhfIc$0!2AK~T zLFBEIt%#ezOOt9+?BnJ1UuUq+5Cear$W*nMhOZW>mV;W4 zyibz7|H(vjAWjx|6yT%{sK-Y9U50wpbw%~ni6K7hTnD1*T2en@n^uR?JBZHsJr#&J z*EEMsc?84uUL?6|Te>;tN^|%=P1Bt7q&YtjOLNW(u{mCTx;f`ba|(g0r8#S*Ii@ie zNMlBWW_Ca>l&7q-fX(E7QRwIEWCw?BT_=rO4WhJly}&C0MFSp31)%}Qq%~kCDla?7 z7lbYV$@H4|EPc?VY%Gq|<)M9dKboy_G9yvWY$w82kMB?69d1NIarhYUTTyJ~3u%!Y zE+W~9I3toHL?pign<@E-5Z%6Z2c<=DQ(m99$%>k zP@q|m?~$D(Gt7RIU8HK+VEEnVbCYU$X0lgyld1!z{+}GNt?oP#;XfoS!;%>)W?xm^ znX^SqL<-I3Q=Zh6k%&rRcqd;>mz&yWc#n~an{vm><115cmGoh?Jf|5K;&Ym6d7@Gi z;uDqX_k83!UIfflx%sfTGjcD~U#&5_XX^A!fot|@=y|50(zx?YZRQ!A+MX%kwtZT3hiTFC<>0(iL?JnmSuwdaR{x@0zBM^f z7uwKw{9E@5`d?K1TgmiX#2GdJUNU}=SRUv7AdmC-6(mtzCWPvqP1WTi+&D5#Q3rkq z)x8AcwH9%{M)|FLh|3AG7JuqLp&g_?gt!t=o9{rN4+2wUHDI~s3|Hbpl#_!l#0Ugt zrt|pAg)l1tB+AehaV6lIWq{2ra+P@hi@6qf?Nn3M~=?G}P;l(D_iN zkcW;&m06hwK;Mc#6%8M|9rd73QJgi( zU7Xy3_{`#DHXmr`VXoq%5|tmmn#F#Axa}2FP;$Er`Df z3}%e8z}r~hZ@x@S50ipC{{gO3kz_Mz-NHAsGS4IKUC`(8VbT0Ifd0#Zb|9dp%>M@e zbtwShR|JMK;6YhuGSC5m;~6**fei?VdASbR^TCc96Oy7|0RjJ7ImGXR3Fq}~RS+Hl zjcl$!-1h~@E=`zUg_!I@lv{Efe@~fp*eIPm^8`}f1ZB; z^W@yQ3VdcgwhPn(QZMnv3A_RnaRToq3pDv0EDdMIa zvI#3?Fg$`kHN$H@26#9KGt-gtFF?!;#LT|}fzuH<>@)6VzY1uQ55 z)w>f+Cu9m+B89z#xG7xjZf9-4q?UTkdB7ioFf$!FzZx-n5i`FDf%0M$R)PQvYb!$_ zF>J#3pWsFr*EHT@c!1uua?xp#;MC0}y<8(GOGnM~KT3 zFw}9V3%w`d`ba-&=RxO<*n)v$lq>C#I}vXH#W)vE{0yWW$i#0UjE69C4}?kx@c`0<`dIMdIs(T+s?3b`hq z?dKOtDiPPCX^wn)aXsVQm|M*i`v(~x5Q+Fa|7CFW4aQ}3&6kfFt@iGP>H_DZ#xZG) zC%}BMm={Bxwl*E{C4Q7{t!DgHtiWoi#P2{{E&x~$TmUpe3(ELQKpoq$E#~-#yal(p zYCZ~M=VKv^>4DVl@|QsyehoWHTLdvGCeUK9|0bsA4fX+~m-akrGKy(~o}$^u{-<2C zUtP2K4sLmyV77*4D(X|$tR=LPTX&ktWpx5NWh>3<=nu*Vxh7Z9#M0N&Ax^#f^^G2T zF$FDJ4*l-8-JZNZf~(U8Fg@?@mm9w)5Z67oUA`c55OLje56X?;X~yO8(?by*Q5tvX z(x0*IkmrZp5ZAX9kGRhZrRDddT(mqNHc88$gipI!i3cNIM5jp0U(F2VS#>Xrxq&#; zlM!D-JI;-p+j@CcO^Y;b)eYI7@vORc?e{BOGw0rZ7D{oSRm)S73CMyU&8uf4Ml&0B zqVolwG1{F&usF(s-i(+9i*at;xFb&)XmMOy{X17&6UUWJVXo*Kb~ck-vPW5w?5aTp zSb)?+di`b}c0&8_K{C&~Za+RG>-V={x*s2w^*g>3;`!r{_+c+?6A{<__=v3MsfcHM zL~kGU9;?A^Gdd4N{4x33v%U7voZQ@Ah=1UnfT1d#)(Z}tWJ^8bo%N2>X@$th z8v5BbWDjkf2xuSoj*PnxA5lS*?t!4jr2hoHckSl6HA84sfa6nSF!3B{`GS9Tdk7== zJtV5f;_%<3#<{X-W^3FUs5ar4*aHa;Bjv=t5Wa_iKfLvanp~WBDT>_W+~MS+?)nV8 zN!sPoEpgD^E^VUE#&=44^r^z$qiVC{puZEUw#v(f@|{q~{IVwcVpaG}n=j(%I_p}*^^@yy^5ptH z#^nRo@$%K2_Ys$g#DXx9y0{amADl>GtB;SWbI|FN(=fKK^rPyW-p!D|%8B}d+O}YA zl5qXr1j0C1JFyF5J%Ptx0>MTLF~HRPsvExb zo3$NbZU3`c!|sExs8T;xYiiUvXpgIy%4HLx$GKu{!Yi*vDyB%+scMjFWI5Pjlstmp zK6jN-ouWpbMm&%Vi{lVFLXi1A&`BOuFDjGIDdkaO2DI`7k#9&ab7yK#XL3G4TnB-F zS$k2Fv`RcURx_e-=Cd9Xg*@OJwE1%2C-kVI@ktzSL*Ms(q>Z@gCmn=%RV9{z4Ww+o&Q(m;FbqqGLC??3i zcqaV|s(S9jo}YCdZzCwZ9VfHw;qpCdBzpiC_KiLeKX&whr^PXdC{=tr>XP%dE~)r1 zs+c>RFKa-vG7dj1o!dN-k<$CHghbsR@uH4xjYMopq^@G|HDhs0_7vYpL8=pDEUU#> z-v1)ib#NiigD+BxYS(bf8dJ*6D3vPXm-$r>maD(tThm3i@`tsQ;QK)wijHb|>IYe3+ z0|K!4(6dZ(;5T<8^B`tetZ)On4F;Ld-qQi3Vid?-KJHJ43L$aE?N@_raR}?2@xl<0 z%j7~rx04K<&)nh)t&HW&_lu~Xq&WU8N#xrQ#VqEq<5i-S@p&Vd9gRAd$Zk!u-(0h< zu35m!xHk!AUq7gonVdxdBm47W-##asQU$fO6zNiP|(e6ysvdZQiuICV9Q2W8B?wl<;Rkyhz0M4 zn6dK$!Mb3KB3=2Y51oV!t&DDL*RP|R64|e^u%D4o@=tNi&bKnwatMACb(xs0qgevP z@+V_}Pdb$!!In4~l_xgY^nqUt&Ny+EVC_Q?Ni({0q@9eqRt(V)mVCQG%G^xGI<>Vj zlH+0aZPcS;hKXcF-T<-uR3`BEVeN3xO;gv(IM`W~UrCx_^kFZ=j9vo;Yafu4u3+7d zoWjnvGU{VlL9VTcY_yscsUV6^JzcY&Rz`din4O9mEN09ovK_=T*0nPhGj|1>3M;%M z{9jfucdfchTmN;fD*m4>P^BxeKt=6|{QtB|x&vl);0|PKKSL4kPFpd|H1aL@ZSSrR7W*{nO(tI-^O7nTF_)}G=x6eyd$MQ9f?1eV=HC~Env=tG& z4`E;vii>C%gU>KYr7`p01D4NO)85ebIoq2|Fo7!)eF zZz=K$E=Rte;CZvr7QuAn!Af2M)A(I8VH7(7&DtsYg4rN}(=d&`kRl!W2bwhcB90^M zZerQ=Y!y_}B3`S(5cHlmdT5G`@+u%(!PjQ6)G6pU6`aE{75rXG&19*;Bk;@@j9GwI z36^8vMFvAZ^m@dh|9O^9OE2nb8k05%wt1t@!~W&iIO5vyhoS^dnHi^6YXe z`e8c3kWd9koR&)b}$xdac9U3yap%e9o*1@U?ucu=1(iJQi9T2D^+DT>+Lo#az0QKhuxg#0f?`7NqGO|b zh$VhdB*c*%-An1A+%v>672QYiCLX(jgc{L!Al}MC^R?RG4SkC-5It0^@y5NkNpVHB z6+K*?5d9{6vV_iv9;w(C*fY!|@%f0~pgtD+Pko{Eg^1te=#TnB`&j-RPW-qp^b#k|olg9uFEj?@GkUA)E9IZ^ zVbeF%jEy7R0w+d#@I1qfM`M0URoQW@lhb)NzX3;|CEgHLTtpf#o`YMhi0E7o-3#^4 zLs5C2iIKY3s+J;}@2No4Zgnycn#P(GcsM4pb3#n0KYM19hbxEOYE4Y&Ue>(KvrO!7 zhzVV?81We%ai`V#n9vCxJ12H{Gk){?lg>?V*GxN)pOCy*D?5;aw~;NND2s0+MU4LLHYgbNo&hZXrQ#z0I1%uXvZ z6}5?JD0CFX5XIQ;@VHLQwnRTxkw=yS-}fxCfWLwI=+T(_H%ZJJ2x38tc|hy@0sgK* z%=Yof0INvgZVc?02X!nq@H>lq=w3;OcQcmeBKq(?M9*m#(?T6YL7~erlVVybr=-y4 zN<>>ZQE%vZEKxD7ov1%_4?K)%qqHM2p?_h0jcKbMmHg|3K1WN$oaYz^L+`S*c1|=D z8idnROnWEVEOZ>hGNywQO$c3u2_DnYiMGa%T`=oTswZ5GZ8;xuY_q0OXctbL*mL?y zZLPrj6A(LhObqMp4ZKKQ^CP13Tg`t(Q;)}fJyZv}XJe)uzX=z@Y)`Ipao^}=&MSGw zeV58BCA45)_!;-Z0I?hx$Y;7A-x1xkz$@sdxSw?CvjQJt7{;Au%*H-JfngZgaX(*$ z(zs7h;0P`c;(mJs`EY}hz;kde?)TjiU8w?@Xy>>;dP&+fs!36~6{pl1TzYeZlF-jM z4aRw#*b(RH*K1#3Pl?eX|PXPe452=(nm+&wRvV9Q`&G zs*gz;7whD=U4>e%M7)j@-=RWRQeW3ezf*;#V)=}#=cM0-{4ky38an#jD)cLQKCY3Y z-=jhwGkwU(Z?6jNMQ_G6b>jO}Xh1RI&D0yx8v9jfJQkI>=ISR*9BkpJLQ~kzEfpsc zHysMaGkqH;en^FyvTfTr`5jTAp%|AY{;3MBWxS)KKdM3>VNo;j<0{l2i&9*YT8ukY zEP^Uj#PU-d`x`u=z3kab)w|-~dQWI2CaH;U@PsnvBi`Gw-{cA1Pk-I`W>07f^Y5eH zm+sx_2`yuLxbbbCP#OE9pZY}d-|h*0%S)Qe)i)B~;R$tMd#5_}-RTLv%+WH`$#0h@ z6pc9_mm}wCyVY(_s2OHYT)xta=w45#Kl^i%;R*AT3 z^@Egm0RAyP#i`Fh4;C*@HlH^egE=-6m1`Y;QQKH&`o;I+kmoeogk>rIVs{#CnTpsY z9RHj~C(z{ams)X*)d|F+!Qy*gEU{q2${Z`c&mf6}0yD6h#b3s6t7E6vgjMM2_`aMM zUWL8?5)x{#ip2NR0NW=fBvfPU#rM|$yC)_jbX@>2Km%-;oRBa(58!eQuwilnD)K4T z5ucY;h>gNn^~Vkw$LidV%ww;pma?rt9A;VU&|4(twOXj(;RSWgSf^%8+>AYnjF?#K zX&t6#%QX8=8_k3&mbLTN2|fuqa0!;$It_TukH)iN*+MDtx3Gz1L5jcCx$X+oV+A(o zODBIIei34~u`96qRY0+}8*{Ky@CUejUgjL@$N4KJzKHD`xCU!OeDOGGT`R!a#+PJC z%o`Y7idbnUB;mHqK5qng{B|@sPGEf@H&sk0^?`OMWS_SSteby`0l3T`KY2S)pcO`M zd<8`gg1ay`;wxvN&Rhi>@_X0uRlA{-Rq#t(cE?w1?V`Gt%?6}W&Zf;R`wGP0K)fZp z>(59lwjmP4#8301f`K*Ykof86NL}^PA3vj~#Jqw19A7i9mY5%%!6IncjP2>xfVs3# z>=Y(DL)A)DOf~ilRWn9W?R;e8^In38&r1g*8?3}lMyqN8Gx4u3l1p|o>2*r5y$M0= zJEgc!sN3ON$Z~e6+mR-0t$A2!>N;EVc>}y`t;_8Vpo?h8*C^^HO+q5{PDB0}VcleA zf$7w$Q5}Z(8eRkRf892}0sFijK`!Hzh_NSlxF+!jB5X-8@KRy{K zvFldh(S5zff7FGSH=uFrHKj-|`!7W799_OQa4BX^J$aPCx$-0}n`>Q6U~)NPEp)6- z;3|x*dM)pk+6AQ}>b23jkkq1HTODf_*o{uA*Fnb;0&}or)Jyb>r>z6YIOo?(=7h%$ zaiA`i?RqKNvQyv|mfpEZJ?c^dSy%|_bGMt!}j6C}?x+^Rz0+ac0Om=8I)LfjaY$ao%@Q5i4*fF8k``YuCMaqEf#BPaO@jton_3%Yk;cA}us${SXt! z4#w1I9gMDntE9k{=+|H@MfT1C^jk1a$Gm}8aE1uR>zF^#j+S+FEGBU2EX3;SSe?L3 zw0W?ejs*kRX!Brw**B>9 zikEkRocU<4Hf@|*@>(*kt!`+qUW&%SN*ePbEA~D#LPA{UT}-$I{={|RS%kIXX(O)d zAt-pJ<7p$Vo5H!2Be^?I_1!}f3kJSG&&Ksgl2|D4G;)mV*;``GFmr#0BfPY1Cjam{ z)tq2JeO?x=t(be56@7M3GatjKDJ~H~BnRq{HWEOu4J=($pyxtvs_21BxT?AC#uIM2jgs!#Fl8sg*FxZZ1!hG(Mq6KGqEJ?7Ei zI<%}e?h{_021iYRKf#V@2o=0H3&wEcNhl&(N*(`6kv$TB0rYMzk8 zAn^kWME+8=0S_KkPr`|(fy{jD$Ar;i)o*}TGp)9dpa&Y3_z?lW0=%Q}cH@vk!-?tw zQA8vlXzN23(OsBUsdg`6y^D^rdAo^(bg2wBG8z(`3D)jGjM+vHd-z6=QV|&l+I@pM zg@!Ax2uRio^Wj!t_^}Y^{LX?cUS?%vZ3pMt=1md&XUWF#u3Q?>+bgk-I z?I&Q4HLm-OSOsbInrr24=;YPGYTu>`Rt+0~`0Ovo!|D{Q+IJ;w)KTcuhV~&1^$~i# zp+iXlr$owAsxWK|#09 zQ0CBjkkD%ly^6F=rqCQii%8p63%$V5>7?ha5E^G_Pdxo=-0pUvpJceD4Ipj*n9!Yu zjwJ2ys?b%2P9*L4iO`9LmXmh+S!fSK=a44Ghu97=hOQ({;#)*M`(I;SAGrN#Q6AYb?Ribg1*+ThlyKc!#XMlFSUTCzTLrA;bBlM#&uI)I| z^PdsA!_Y#~?r#fSZs;zS*5jDas|{UB+n%a1>(E-Aau(=ihlMUSv;k?~?}c7zXe-iwQBBwm$%b|&?cZFe*U%m~12!ITzR>qZ zx;|V!0rc`zq4yg)oVEkAgf2960_mWsLdP0fN;-IzQ0_0S$HOer)H{WG484Xl?Qx;+ zj&N=HQ|pa~ye@Q`p<76=;7dV1d%mGNNQeF^bhM#!D?rohHl=MxLl<-18Frpf%h2md zhhHr8?cuHux08+-A@m=HHo-#Qcx0i_xrRPT+fj3cjx_Wo($O~xZExtiq+{+C`o}Q0 zw9iP#J}Z>Jgr(c;d(w<|g>E%;63(cNul!o*Y(v-LG}(9@-zoCh!wsEJ+wqNso@eN_ zq*o;i{Vm-s?KaY@`wM-;(0fTU#|hnH=u0eZ!epT{4c$ZAtffNJ4Skbz;%!3P7 z`(dHK40V0zjr-EZIWGx)-O!<=xgQDLZ0NYDpm{$Coo?vWw9OBk!*;mB&=S&u7D8JY zI*YWhhtSiwB+#wy!Nq&yNkfFbYUo)!_ZBn#nXjOHS|Y%R&uS-G(+#;*eT_& zyZY=FhCW^nTK1&SABVU;?51t`8$w?(^mWq7UkKe~=u^0$Xk78T&}u`!plxOSb6MJ8 zLw_W#YA>|8p&_oR)t3rAmFD`;23J9ir;HN%lA+y5rxpp_Xy~h?)8-4UH1rVZ^mRf9 z8hVU$#(hH1G4vPGna>OTF4grRisNk7dqQ6{G(C#t(o*3l%a4+eye+hlw&?iWj|0Hz1p)ZkM6Pv(xC^7UP>55iD zFEg}0$M4Dugf=p?CF!c6LXQu0eOQM3!p5s}g+6QOI?`)r3cbnDEu?GK3N1495z@7H z3+-*_9@6Wc657Dfw@9ylOXydZyFPqOdc&7OpE2}X(i{I2dV`_&b41QX=@BUPI|{V zLURrMmGsW8LN7EldJ^d7K|lHM2JitVt{(ECX5 zZzD9z&|RbtTqLx+p`9m!ZXYHzVCZ4mKA11`$Yrh%$4MWWE%XsXeBELrl0M!@ z=rThWkUo(p^eRKwl0Mm2Xct2_k?zV68foYQq)(LzJ=ELv;aDl?(~E^ZXy`Ab&)h0> ziJ?(tpt~OwI?mA9JQqIuqRghlTnK?N0jq_d?&l)b*i1>7J-IY=;L79ZC8^ zbD@h2%_jZl`9d=ctss3dRcMl-7T1TpSwd|?o07gXRp`M>Tpv1+zPw84eTL5ASbybC zp$iOMMY`{Cp<@i)K>F(ILOU6HFX?Na2~~zZLHhcyLf^UA_2DJb{dL>29qu*sAn6OMaNZ)%`XgfoTN#Flk=xHflzmWcGsnGp~M$w0lZxec# zp&`;w9u_*o(6OYSz9e+0q1{P8<2xVtO01#Y$)KPAAoS-8Tp#9h{C*K=N88s7T|;`b zh0r?9=19O)&Hyq~HB6^oJg<4+nV-{(b%S%;9B2 z_tN%Md!aRkzDxSUr9!I={haj2Q9=h9`UB}tMMBRtbXz6p>G?vx@9z5WBE`o10xFa!s0zh!N!50#H)C9r(4IV^ntEqyU7`%$ut5ysCrkmqP zhYiF&b(i2h2H#5@q4-{k&%W8zxz7pKm;Df|bvbQ|Gp>FUO#L+6$ zk$HdJ)%D~@;(+3BHu&u44EC|NVibRBz-O;BI7l3;t`b~q@Qqc#ajHsiAA>g&$Ey{B z8yfsDaUFGs;A34}Po5*LtN5cDK6|&pZxGj0`vu=<@RT{g_0<=GCmH-1t%K?h!Iv7m zh1LyJgHFslXs}fcjPC&o{<5>{Njz~Q)mJe0y_Yf7;qEEGA$6tT>kWRCxUrfnxWM2S zh?}Tof-g4s0C7`QBeQ}*e z1~(^8Q1ud7`HKurB5tAD3$A1EThoABs@{S>OLjf^n7EZ1Blrn}za?(1N(EnQurCX^ zjan=?$Kc56z-`qA!50|(&|={8)Wd?~3~o#7cIsuppCq}SoS=1k^)JCY4Ze)l9TZ<0 z^VzEm9!A_z#RFh}9)oAh1n#8T3hrTWD~|6(b+O@i9g9~WgMQs;+zQI$8yQ&ujM;p9^xSRS=@JHxqo%fBz z=c^wC?=U!aE^v1hgC_Oa%MCu44pjdTywKpchzF@>1&=lOsv_XQ z>Y(66gC}r&r>buRdkiikPE!$BV0`wwxE#<$&LJM6&Jn!L;8ny|sBVJi8@z#ds7e() z+TeSM)73=59Swehc$k_l*fO|y3Gi^WM)2FXK+~SQPwNrtZo&Vk#WR3MDlWP{d#=G> z5|2`E3m$3kY2wl9xZw5%M{=f(Q8w0jY-WIKV_jrJ;<2iU;I|BJL!6;H3*Kt*eanEa zR09RiHuw@+k5id~hZ{VEc)Xe-m^T%=$nnHisa1l1!+nXy3swMMtu_mO!(e^~sBxxx zQt%do7ZFcTZwj7i@b$!5>Px}t2H!zEQCVGCd47(si+qqcTQw5=3+@y(-c6jNk_5kQ z@ax36s=wgP2LD9A^VE33(+&Qa*7>SZ@D&DoRs$EPYXrA4*voTqp}Jl0Y23SOPkPdN zlG-Vl`*LX9jMhc!b-{NS+>y9geJ*&a!50#jsNV&r89a!%R0X@SORJmY20MdTHI}x~2EfqZ2;CxzFsf~i08$5-$ zT0J88R0}tgKsN9cwNLO%2H!~Qsp=EK8x7t}JWc%~xYFQ~UPbZ$QUJ`t=x$DU?;sxr6;1>*DN4!w|B={DCw-Do}5WBO;GJ_u>UaZ;( z?q_gt5%3b#OK@X@TM;i+BLtr~*Y%_e@iH|@Fdx?Ip6^4vT+J7}-r#iNYt(wdB?ezm z0K7syAowza%V@n){ZnuwgXa*hQilZ}KgTU{74d3yO7OD=U(exltqSyD^0`2^rK zs-@r}gVz(URTl{EZSdMTz}KmC!3_+)pVrr_e8FEeb3J*A_y#pc@G}NK!c1;dHwwPN z;621QscnJ_4StJwoqAsIB?f;?yk5O8xW2*P65p)870fN7bT{;3`&9cs7WT!RM_->Kdee4)V~Vcj_&aWh52+Nvj~M(h@x$tJ!Pgl4E%6R@wP1b;Mz^=M82AxY zEx4P(@x+g+m4c%TK9~40b*JDD8=6d*_fGYMU~b*3^M01rkE=HXFEe;Q@e}H(;HwP& zi1wE65yv*KfwJ!&MvW7^#Nc+c z-mNMGk2AOj@v~~V;1q-3Abw7566`bh2=VjkF~RQ#T~G2$f%mA_1V3Q#pR|5KeI|I3 z!Bc4cPxYJN41*UFzo_c>V&(Z&Ki#k`mICip{MxF|whc}peo6Hae6YT2eJSzFYOLV< z48DT+6;&p9fx+vD_o*d<#~8eY_*HeA;7$goP6mEW?GVh}z_o+jd3JqWy(0LXdM=(s z>;39u!S@<`h;A6yZsyY|5mZJ>*h4?LXp5P7!NAarnfVxERpLN|Lr?ben z6`zRv>;nc5Tn_w>Di(Z?!DEQuRSN~rF*uL-pt?oy2!mg*1b$CFD7c-$D`@?`+AH|? zI<649g6}f;XW~!PI>9px{$eWdr|N#eLk%8Q4*Z#V zL2zq>Tl4z+b9G4Y&vC9NU5UR?-wS@t;LC`Qs_08u`8y5vO#}W?wGceb;G&tpU#Xsg zhZsDbWAK<7D!8S=Ma0JyH!1SjKgGJ9%pm?+%@(}R;N`?8)D41fH+VhqH|k!&Qw+YF z_@sJHaH_$N5`U}S6P#f13&h{4lY)PUaXmRe{Jo0oO$T2#_~UBeQ|es7H3px@VgG|V zUvQPd-HCrxX@UnC+@JU-l`Z&OgGUmdRx<>DA88L!yk#=* zuj(1W6$W2R>)+Hnf-g6CBk}L*Yr)M7j;R9vLwWnK^4~_go*d%%{!=v-{7-|A5nCR9 z(CM>pHTV}|6@nWYyoc6xJa-5_7U_Dj zho02+JT7>*!MAZ<*7NKae51jitOTy_`9km{gTEsVdj1f6sljR$a05?+zHF1A!F7lm zdO8XIGQ#zwIdLOTU%^isoJ1V*Tq*c^gD)m-?3paMz~D6ECZ1)2FE)4_aZ^u?;CcpM zF&DU*=TX65_*_purS&h)vg`AdEJ z?Al~Ca0^d+!F3F7Pu$YeTkvOI*SZ5&IZr8m#64xA80%%-=NB zMF#0fTh9i;7Z}`%_&m?Ug5wPScp-2*&&z^8vE59*C2sHem*AZSr!kWbp3{O?89a`- zqle#L!Sio}ClPn@v=!XL;OWGPo{I&?7`%))$um;$zdWud>xh#*MS>r##l^rWo&|ze z7(8s>Va1lluRhdARM2=~Q@E=Yiv7XHhN5AG`t6SVbTUvW6&y@rlUxf)0E zZBcAFX7O)OeZJ$NBJi*JH7*uKD)?yOP&pNaQ*tXRldCHyCRgTG6lN7$g{9fW)j7Gz z#f7ES)2KL;Sjh!tCArBJxh2_U$^FWvmKK*~SS3J*#%%F$!>00 z_(DvWoS2_misG`9Cl*$fl~?|q%CM@6tnA$6+$p)GRh5>>xV$*4DzU62tK1Ypg1yA5 zatbpm3(JzSSwUT=qyp66LRBE3NvaAea(_Vvk~{fplW(% zUU6Z$Hm@wsnwXiBo2O&dS=rgSm6bYSWp+Vsj^<}(ic+u>PhxR#_ij+5<*TNb=Q@eX z%PI?}WrhJ)lthJ9PJV?YxmwCAudK?dVg#<1SCp~%vI-q7F06FyE6WSf71>2PNuukBX4&P{wYJ%1CFRArRfT1xPJ-;}@*G_?l!h0Zs*9a6va`ywCKeVKR!w&- zCstMDI=b?T!m`ZTXh}&mY|u1$Y+vMqBCB-cp=$6*)5^m9(yU@_spUlUDU;BuFy9#s zI-)J51*!^k`kd@6bhehu3!P3!Z{M zq~GE1;BI1`4k!m__a z*m{_#dI{6HFkYNfSjl+|b#AfK40>plXH{f5qXEq;g8|)bh8>0wWX$v_h1t1PSrg4z zEVuyKVF4+un2et^udZ-LZ=v+PE~%)ttIM4tbUs>bWRzi+BsgdmEBw48Hl-|)!HVl8 zE;%}7c6CJs7CuCfv|uXcg%*o)D@t=YoRLd@o;yx3ew?{DsW1;+;EYPl2w38Z5a%b< z1Fy9m4ydH$#4gxzOhpWi$WQiq?0waPy~=(fItlVWtCJu<8J%Qbl2ku2DOv3DA{OPR zrfxnfo@%$>*rj7~ifgiP*O26Alahxx@%+@E>;ZYfPHBlhMek;wa2lE01J!Jp8uu6=z(Qo{~iI(C*cgCjOAO!a#0T_t&5Un!F9s+R-xeIH_x5O4_D{`T5B5(aBDh z&&5fWXpj^qQN-fpMEiv2om8~Rd!=lXZFL7jK2S=}x7DS+ib#rB`2HYN;qB?PxHlqc zC?fmah+RLA%I78iR78@iEB-N=8GR6!2l*~| zN7*fE)52u0wYD%YP?4PW6QWKHv&T?k)b$p&ZBdHsTTtAcXFT8^Xbn(CT zqi&Ljr|dtbz60as)2RF@l3l-i8h!gYa_~?@7Kq}v$fT6c?Yl~%Jg*&LFS6OTf6QWC z7P#`z_J>ms+S?<(V-22@8ayAz#(GL>@O)Sex=lhA*1J_WVycj0@1OldQgT;hdw5Qs zy=>0lF7_#vWUrb-|8BHd-dD2*cSNMdPD)Pw(OzS3Y}nz74#~BH#PJd%;HHWvVE9dJ z5*=Do!7NV3vWk$C{jCy{2c-eM7%Lqr&9yC_>H{J_Ao3gKZ2cYaNvU_(JLfL&w@j@` zwEt=4*_Ux@*nN^xQWBZumq>r#n+q?cm^rNX;I-4kgLJ{v2N(!I;J#krDPE(>L0gY{;z?2AjzJZlsF_gIk{u!E*(=6(LZl`naKkf zZnph~mzhKM_f1_Wxp4Y<_)jD!q@Pmk#)xMTsEEJUZC-4zkMOU7d$(4yaCS5 z#g)mwj2WE2$i|8_WiWG-B@6ygwr}S65$OvBzZ~Ya2bllr_q*g@ZXfYt73q}hE_Vy_ z6YbqIrIlp#+$y8zvomB?aI^436^_j8u_o*?Ysf;bGP|JG3syfqInniLN#SkYNc$V{VO?xqeoCjOI_F~y?&>nUedo)Io=)k43E#DSnyj?;v;}tj z6KJkqDiGVTxaw3QP@|eM0+oOBd%^u7-mV%$;NU~SR96Rh~zuh$xOR};*mB>a! zIwSV67cYxbcdYP z_C+V%oBX>O66@_rLT$U~A-I~OzQiE4J}jnPRd0}(qW zw(FqJ){6}qD#AWyaV1+Fp0qf{6Ss_TYEu=&C6krawkezQ&bP3kPA4 z{bq5ce@Z-fUc7lqO4}Q)YqfxLZ%g$8J@@{I&P(<8Nh#{2n>i^We+Y)eb=8BldTk&N zD@tlwYI0%c{Nyxb{CO2iz9k?F;b#)LH9$8Y+cP+k7DNs1*1l`!PGCQYYb&DA+5Ste zz%@eG{>f=W^OF-(k_Yks)GJc`t%f9~C8l-h&^4uVnjKuw&CX+PyQgryeK~4y=T4ow z$tdg!dY|NXAS&r+|NZ&MCfT0x1hsY`FQwBW7~DMN9VENXKR7uN3mU+eQ|Zz=Kil+# zhwXdAY|6)7xd>+(*nNa^7uIHJuYJ;9uFUk1@5uMJ$iHGhx_#7IkZ(US!_yt(yo^gW z{!pL9l+;DTaC%O%tCG@o4Vi}(-2PaxE4Ipc?_gvS>t!O29BC&cv8g@D-pE9h^l>Cy zhpt8v{TPv#nw$JgYA#wRKR5Yss{cAqw+3mc{2Su$mtSzOB)@2GdYT=*zqp9r#a|FJ^-NK;(#=v+s;pki2B!!Q>&h{wTng z<~%s-EQm-;PVd|yIdM^1=Y#n*Z;;F9Fvpwvali<9kvgY65G?9crRP-)~|Q%cuA ztILvZm5bWX%tbAJ@4;SQ>Q8{deSR*8Z%t+2-sewB;R$W0#P<5JP$2dw{Px>Vdj>xV zla+AIellu-9lH^#|r{5>q9x zOL$eF>~mxxw6l}!)^d7BP3;L!4CUCbJ2=@>56`sRTbn29s|LfkBX6CtC_ zo+ddBUxe04NkxZ!ExmqI%z`0lDMLJ=u#DcTuY#S-eGRUzJ#o;!i5oSKwU7Uv{V?rs zo^Sm>cv>b8)U3aGP#6A$3GSTvSP8dzVULw+?@ryPGym(yL@1&5F;QV@?E|BK_h87} ze1|=yF!$QHYyCG*EdFwk-~#XL7X`(S~0zHeTH z)f$X{F?iUW0{;ibwO*}Oc&@RRdzbl^Ml6Y3>|Yd>7B|pspI))}5h&P)w~w30r_g!P ze*OL~kAZOmU0?XK@CT7czqnv+MNt#CjNSMkf28PZ`@k)OKbbxfe*T*>db@cP;Cm_) z&dS3re=l@0#W>mp?#v5@WMpT*7K~jc2*N%)8XLBw}&oBL6^+57*Ay z62I!{{Ws+gj7v{I-u&b5c8&k*IG3@OAQl)a?eH6gViVSf1LL*=S*{I#r|6W}G^1b3 z?4{l%zQqxXBGcj~xOHWACvluT|H)ZbmopC6ao(6MVQ(#Cq}2YM2T@t+40?;mL1g~4 zc37=;l&j)eKMEE0UY$6;Xy6OFyx94&d!xT+WNu5n(l~$JaC^XCQ+7Y8>)}vzz*lk zf#N9~s6T^FVmy*T4-rS`a0=SxAflO0?GR1D z0S}Ig&{ZN;$1MuXE3CC90L{XI8Zgk>F>XQ3`Cc3zYif`oKOR?dMIaVbZx=L@!2vD0 zi8~=mKhRIz7_xMaRn@K5i_xy>NvKZYP}T?rf8zK{qtLZ<-4GJ;JcCAwVaW4$_^6@n zcpPEBU3P{ceVT^@m6wngD&ZrA`juxoxyV6MYwDOLY=CY8+NzT<*e9at zDMr1LV01GCI<3+Ex4b_^YW~Ck`kBG^IR4Vl%(52_R*7M6Ee9F$It#p~+fKAi#}U@g zL?Z+ZW55()mFow@1X6hlT5l>a5@;TdundW+aIn)D>J(R)yGBH9ALVU47Q3mn!!#@84Sdwp|VCZV8LOtViC}9qBUi)=$L3){S7kX zm{v>}VcADe33Em!_e$!qZrzBk$KhOOxOf}Tb{sOL5bneQCmHOcsdk<##E8O+k6YuF6hbTP~*Mo=tWnNjX^rEN|3mfYcJB z`x$IU>M&<&wZo|$8%OO}2HV8YEZ#9dDWXkhKqs(ByF+6jP_foB*dbaoN|;>%4vu(+ zOF8?@-=z8}#8g3=l2+|Bq7t3F#nduA4mo=yUf)!PilT2?!B zYFX{gY%QxzOZVsi>*D%H_6iOxT(wsd^y9b~&X(}BmV*rWL=atTu2^ZyUyDEw-T)QV zVSPlcEoc}6tu;;W2Z|AGIs>gWr{}PoS-@F2_e25~$jWSU5{Fle`Z64HHSE@wdF;W# zvB{8+FvF(=^`GJhn-WAv1(_v?=(wQa446q+m8sn)+7S%2*7W!RAeJCAjDpsiCSf$B zy^=6N%dHvmK`Lg?Znrj)wlx%C?lOH>LBkk~4^lgZ0aJUenVaUAzOS_%PFosa&Ft-F zU#lKL^#RFs zGVn^t84MiX1~SwRnKfYz8eyj-8qH4CS&sP>qAuHbUfX;BeIRT{rtH`7v!2UvKH7Qa zS#K9CcjLg?$AAg{az3KX**W^*wr;@MrORc1ErmZl5|WCJV8DcbDTOv?=g6icvn_vu z8R`G?_WcdXn@LZMWxyT?dj>|W9z!D;v=i;9bOhtI=*}J2kb{MmG~wK0==83cXJNLz zX`6xr=O+f2ia3m^CTQvwz+u784LPa6og{zfTc8Drk5(Y6_QaYpR83B+efI2Qn6^%?MbfGZ!g- z3`vR_Fomgs%flOhj3tEK)w*V3C;Vkjj^U%-Wq%!qH^6$m(GPImO^_M>}oK&XFr$F%F*481B_F&MW$l`YIe)3K>uxwzw`sbdA6RbgkJqo60X0RtL@b<%%LUI+FeNt4b% zCm-dO&gdE(^o}7vCk*$F`WhVYjsewPtNMsC!>iU{Sa_Z~&2TpjM(tmJwAd#cu>nh zhWvmO4P!3nX!`|@u>5P0X^L7joW?<95_bNr)sCQ+MTAxMHz52{vXp>8Ysa{iq1FcW zSd|iLwP{C|)C>pQW5C@a!V0Fg90%7bhSNly&S0I0W-Vg2yKr!PFy!aKknt2v|55)u zj<9B^MWz{Q(Qq0wld##f59pxIgTY54jyQ_oxTXw#)zmGQS@^Xt5(c&0njt@n#^v8Z z*H+4F2L+t$M13=93Y2NAZFo{4+$l=9umdJ6s^)J zj+F$aALu6&@MAfKGzovI>1O=z!X2GdmQQ}D z-!1yFuAbg*7i4-b2WW?&D_yI7Ku2)keBz@2>h>mN@gM889|i}coOA}d%fg;IQvWUv zah(D!!k#g?dLKXiYUQWJfu?7SLt3N=8ruzlPH(F2rbngR+<8sqR*>qGI5_(m=14{v z42p5^LV=;qG{a5xUu(S$Y5rrgunvcCU>Y*e`J2w6_6r=+C=|L$qnMdQeF_l0X4p&A z=?scRG?xF>5$@l_(wUW8J+iY(WVTh3bvgs>uPKGvT{xHt!-F_bGX_UQH0M~ZM-y;x z4Q0sh#DuS*^4%G*ur)LX(E^PaaR02ZM|-mnT_$M6HU!(XxDx@h4janFh)xrf&S0Jv z8SK)cTYIM4i-RsQv7Os_b(msv7#O|0l_9My4v-KZV;5tKx@r7 z`_E3N!xx=k^fshDt4g)nF|}GV3xC_B zZVc(0$LdzYkk0XR#*p55tnM`o>7K{xQNxh_d90o_4C$c9x}e5&lzGx&dW(_6U^fn8 z*K5l3p02~htpPD>!VX5;u{Nv%F+qE|Z>24ZjIe)AhGv{rQTL?{AN;k=( za}Bd*Qrfs#(8kT93VF=J0p}R(7jYzmBbqWer745f$Q##S3{r65dSPCh8cGFP!QiA8 zU6-_t>l6~ZK0$O{(l(a!w+tDu1;Z}({swJ=#b&WeXRuAgQM(ZA)*=I)jcKwQfS69! zm)52g+}tDZ#ooB{A`R~aQ`RVw-#3V8bsfHAr2lGX$luMMoECa^g*P-A=l2<3U0{d$ z^;#rh9WA$J$gd{ia&*62r1XAkD9}|5s1JL*z^poob{GS#HLF3bcDSnzzp-!UB(|-| zR)lL1cHut|`gF-Woq^8Wtbo*x!(m%9_lltPX2Edv5!ByR043{`>Y1w#IcTj_?uTvaoiJK|#e*SnUjTS(q8i zXJx{3b6J>Kf>YmcGna*#vBn1_x7iYYs^t(ve)l!}L`mBtI4}ko>^hI483@#VFWO-t zX#7YVHib_*S{YmvGamX8CGPZ|!4HwH}mm#0xjp*XH>82qgbVK*E+n=|aCL@oJKmWnR(?v(BvDCuzeYuB}up4GK8OfcmiK%FJr0Xw8*oEgDYEHqnl1))AK&IKtY$)^G$3b4YPoIh0Zgs7>g1KhltC_3+f0J7poEVP-lb?kh)uQVQweHhbGDZ1YiGSDQz|df@Swu6+*z}CxK7m1%7V)qA-GG00^Ql_=HBDk{Uv zWG*P*l!?^@asCZIVp*5q$jrn`PMO&H$l2E{OW%-!gz$0Fl)j%!Zr-yT5e{Qyr`5@l9id2lT(4{KDK0Jxwyg z88++z$_Yo6g)?YYb_R3cjBv0EH2B-gW;>;4BN>7@qGX-eFDj;_6dl(wm(CvEuF76O)M)bwi-e}=}6xK z5{iVxulqaY@LT^*D_lm=k%vHb8e%Llwi+s9%V#5k9euJ(s}LzgBr~%(7o9mBBHp(H z#A|U@p5xrLkjo3ESGxUn3*zq1NZ7MWI^Z%ACj^ zu)YMDf?^7?DsnO_t17CqtE^!@&1BOoYZ78-8QiE*Wm#U8n`XO%xX+gL79!ad)uq`5 zP!kM{K=YPlR_5lHU@IOt!f#IF)xyl|GVG2t4Y_1Z$>n85_|9Th0=|KflRL3G9~+HT zmRfyH6nRukw~9@iJ5O1g5p}i@bL#OW2;bYxEWl=ER;Uh6G_}$5O_aNF$*VsVSyMA> z-|n>L!Gfq_sxwws0En1foK;zg*)rX_7bq;rt4!jWA4J6I2W}LGT7Lqlp~*l`z$`PfmRp4|3kSMF*PWS|l|#-kcCJd zHU!Je!cK11Er{_gR7sRsSe091U0ffPt*Fjqi&>?Jh<+-1v!W!cqNq|nw=K`D$YeKi zo3l#!?DY(iTV-*ZW=UC*i&iVd7{GwAu5c+zu!@|B^+Q8#i@mq3^BQScif;i$dA{@= zHap9*ZiP~IO|$U2v6iH{ax1J004mUp?p|6}Ie_yLtF@w5MiXph%Ivuan4tk=Vn`fKwB{} zQ%2iGcxnK-qO1(vLK(x%Y|5rhRso-dK0gCV;-SrDV!6|(%DU18*yRkJQ)T^#@xbn} zdbGr>E|LCr9nNmc7O24DEc^Lc*ST>$Yx%pPoVB`kU2t8GhIH1jixER3XI7Wyl<6@t zgJgQ;6t=y!jgi9q%3O}M#}L6uPqvSfW#~B<6l9g=6pNd03Bpo_wJKMPK6H&7h>X4g zLN;01+%HbqxRs?NCLf|V>1Q)*>s@^EDUO?hr<4t9jIu0^yw ztE#|y0awa$3c!|w)>nvBBW86>6l!hMA!=P(WWCA=_OQ#u!jM%AZ%XrV;%}IQjB{lp zI~3CbvGUrLXRwLNSg1s_qPVc6u*!NCqU>yE@z=9NLh=)k^_fv7LuNA8F}=}UCYuIp zxizhpSwGaunffd{F{?7ynwC^OWC^K_Qr&vFcafmpKS^bMy zfmu&?!}*V8$u5&tkMlA5DspqIp53uzVkf>#XR#dT#+_k$9pX8;#aYvHb24dXJqduV z`lMKVXvoMEOvizciVDlJCt4p~fcn9r0)3|oySt~>RZX+XFO(s|f$C0#SAoj0k)S#E zaoc@1X`%FzwHi@rRA;tWFA?Y+Gj)v|MTN!fPcZqZEfoL5-P@m*!TbQZv*IN%^AKwH6R zIBx4E%f;ALl$?v90?1s)b;;kGm=ryKB*!9)ts}Fa@Pne7gzc^Ln&$Ac(fi*&^fu4*%gK5`r7Y0P+ovzJ5pSDV2{@Dg7`%J z45f8@CNCAaL#f^k(Ru;>SSX9gYq)yK!&b8Hu<4%1z9`PktkA8KYsI(F#M(_2T%U^V zW6_ZNTuaF~tm|9kJ6Ag;S*19CRD}Cx7vLfTohE6df&(<^7KUna93N<9Jr9Gttjg)Q z!f{67QH;3CYF;qtOVL}3XwTu~j2}H2zY<)GO)2TFmF;92=IPulry0Usv?jT^hgr5S zbW&sO!bOf=ns!$pS6+9$0s*IL%(W`(9mrMLdBs`0Zu=IIB4-axtF#ge5H3h@v28sM zS@UUD2wreEPAdd2xs7I6xu>f&(tD6t{INH)(I)IFt;CsO#Nw}zQ9rRdFAvu=Cu*Z| zB|CJMR&(Rj@KXK}#;sGAXd|bwkIlBM{>6E?W$J?gXZ>iR1G9?rEH%f~4$aH6VoYpI zSw)W32vKZBf~1wxORQ-|IRdd(bKQg^3Xp9wqOwOQE&{4>%V9lgK)wd!0Gul)F|;D) z0XS)J#=&X$!djA5QIR#>dKLg<2#X|!D`eaY;WCCd7r3q}%qz^c3g??#;p0Tyq}>4m zJKTk5)}F~$EilkMOC7F7Tt#xNP-EA|s<#jopO&3l&b3hA_H#wWtw%02PA#gPYx{Db zu!jV=UO0cz8KidRTM>)32A6Glh52D?g0<4o$fmJ*ToJ;OwOFE);c}(C3>M+KyB!@? zlH79KR+W^8Ypta^Wo@=Nmy~6Pn=Elm^wPqn#mRQ(Sx{Q&H$bzItJQQ_SPUK1R>yHe z>0a86xLhoptF-mdW5JWXe685!Xh*p+l2xo9qU9x-xL~g26>H`hQRF=dfcNXL;iUO( z1)`93$92QwB1b7J(jq6$ks@~uD*+}}uiW?1xRFj@31tl zU5jZhr{dLX94Sm&XRXOZGJScKiPskUQ>_sn!N}mx#WGT9&Ai4nw}xD&yR4uLH?Xz6 zYAp)q?ntoeUms>|df6&=upzwR&cSsGE}z$)t+SrJ;p|bO?|ve049i@PS?g(sp~bOa zTOT-4w6FEiP1; z)d-sb#~f`I9xaqrSUqpk#?D?6cvFv=L`%= z=D-XW9folj6q7v64Q60&%$b3~EX~j;@2N#)ibY0=w?acRZ(&*9Fv+M$sVJ|h6&af5 z|Mz>I-#%xrgT3$jKOZ*V+57CX_S$Q&^{nT4*0a{`Zio)N*}uvyf|3k#8%FGFIOIzQ z$34)%TTtI9L|JdV7M*}YY{oi~-$wg?D|sv$wKlmMSC+4Q2VDzSPH${!h1Ui;0CMw6 zd=Qr0GD?@>-_==IUme;`EA&%-HVjBQ647(PUZO`2GKGJ^mxmiSA0HAl-`@A_o6upm zDS1r#&ojX>9o&wCawz>Bf9mM_{8N8(c@XzLjl*AgZ_+8)DHt-BW3R|(ayt$s{2?0) zKbDyM36AXU%HSFr1%HQ`;3&O)`lEs6eOGk5QA+rO%0+e9FL*Gn#9omHgG)l>Js9=a zDfVDohGT)hBKlqN5f~zG$G;3b807<%9z7W6YbSbnPd`dq=lcda|VH^0m7_>ugcb;nO)x6mD*JSa|x-SO7K9=qcm*e!^i)V_E&d7F*X>da`&`2*_yzl;Mx_g_8) z2ZHXuw{XO}|Ce~6;ES1jAZkUz7jpsjW9{Hl{Jpz&aLhsZi%L5<4@Y*>4yFywAB@Z6 z%Y{QO9{5rS{~;O+1`n~J;^BiDpbtl|_<74wh?&Ozcx)MLurH&@*y2wa5}Ayx3R{gQ zXkT%?j|JG;uyL`F__H2=--Yb~Y!4@nZ^hr+u8I+S{?kpWz=t8Di_h#_7IYU=OzV z^S^!1d8C{yIS93XFt+#bcLc^C&S+eXZ7sHSiQ}Bm_!hPZRhSbGIhm333ggdY96KG` z3~W`{;tyxz4aasmHqJ&Hk1d0ZGx9k3F8*-F%j?*7V%vo+{=~-yqy7%V#u+Jtu<@Mt z66bXtj55Kt65A?l@rRQuID=vbHqM#Yij8j@j6d(;?}3M)EU*p17JqKU-)pd~!?r$g zd#7ONPGMl3?J##kEZFAzf z{Oty8o3Sw%H~uhk_I2(LNBLrlKXv$f9<~;243?dbZ2`9U!&uJY*vha?#x@4qcx)rF zF?cin@K}5fqcG#o|L^h4e@TZSU=>H>*<)jPRs8vH$6Ih-8@3CvU5qXMjKFUh&sBkq z;YbW58iOtVtUVUxifse7jo9K3!-s}p8;NZ+w)n$%p&{5tU>k`o{;a{@Yq4#>wlQ&> z5kVudWw4cDi$4sM*~$Imaevt2&jS42gslf#U*b4JTNu95hK(^GGq6=*i$DCE-^H;W zJcnT=@u%WM^at4HV`HF1{9&ZST5RjEF~lMMJdD3LVPnhzV;$nCh2rmdoPh}OC;lCe zZ~s3WpNF(Lt{)HT$LWy&Q~wuuDyb2Uu>WA5P|d{x5Z^ix<`<1}89ijt_hHhX4eZFOZ;c1~US z)H9>1+PT@e)s<(@oLW~trK%F+5$0Osn2=c#ZJo=h6XBB0-MF5qC)jI;b368@=jell zf}87vgPFcz8M9VWT!1zk`?TiHnUbAZT~}E=NhRaRuD%|s6M!jy;(JbTLyo(o@%MPri}z}WdRRwLvsuYo zkdxL%7@|$l@@@?CvXJ0q%%N(ucEjQ5&ScbZ{Dr%+qU`KNBfvYbU_rxD=8zRA`|hZ|4NpOrjKflz z`%o)g)n14fHKFZh8=6|tlHob$$ghQ~_+VKMMi3mu%}AmtYU*uAMUUY6qPM^@Ckx(u zK}}0LI~WDxgT^_I(t;@6Z8i&6FBa-;z_=U=5T1M1CyaHnIiTQ{ z*DqvROO$YN(qjzJ?F2(&TjRMb(At05=|ca2)xjG|ta?OX!CCdMSPtqi>I z8`4uw3@C>Kta#s=H>>2JXAj0d+9<-{jc29F`OuR!akS8LYG>9}PJukh)>Y1`i7-6E znvYU7C}JfZ4M0viI&*E!&0VZGy=@q$ueGL~t(aL`cP`>Ya_xM3RyYXJfg)Lmrrxlk z2QdKNBzhn=@TxiY043aG7rD`_r zV9xAmbu(+vf@m!ae_^<|E41MuvWxB0Fe=3RAa5DyOwi_*c&>3;XHO3vP_7r=Pt-kn zh2UPa8kEBTEpKI~(g%-qM;MsJs`^6i-y5!7r%e{+(p7IBKDe+tt3>t7xcPHLT#v6?K*!~u_ zF6{JnR_Lgsikey3+0&-sw%O-JbTD*xyWC<3Kn~qx8+Yw7x=6tTW$(Q_hvCcR7&b+( z-HZ+xWluK~#tczw8+g-_FfA5lg}xJSHBXMNHKNC|$HLeN?tnms$m(gSUyd@e?$oN~Lg+v?Jc}^J`o5?z>fP1N`X0-7bH|yK z@HY%*+Z%hjp^QO2v&uXePlYzuB<-oIu3K@&vWR*N; zR(b82*;zBIy@ew$aT}NSCwBB;>3{1dAw4?U+O1vM04W*<{M6o+CH&BcZDTcIQ)SQE zfNq@fo&v+91)fAlXHVFC6mNhD7ihCNZ*Y}g&k8gt7%cTh(^^xL5mg*w{OOtlyVibi2g0JXoHcLx!OY8Ho$DL5+E(%IXFfCTRmdpn>8G-Vfc zLENlpXCJ^3v*a+Pec#ySx0>}j(X@wOk;OrF6!(=*izHt$Qlm@7!t7- z7RA8e4HwKF(18|7!7L4z(S_`ytFyDKt7cYLM&6suoLw`!3d*)R6{e})hutzXa?^!! z(Na7*v=>yu-AYI`GQv>TBIp8m%W6js;4E#VeCNUmIqqJhXmYN+qT#(j*h5W zXo$|kQgiIzsL!B}L6x>TMjg+T+fHcYy&WAa)h5bF3m0`EIcs*s+^WjFa*wt)-Bl2~ z6UKF51V!&)%<>HzHu&WJ<{Tn$P>DJkn-Q{=%l1m0%)9)V1WEuwXK4LsTa2oqE@-2l z?!Bf+vxpQ*KO1s`L@gQ@r$kzqGeMOYDYELpwu1qE{I&r-DPH}`d&es(z0YTrj~cA? zAr8(TWlO8YKvLyG3r<14_O?UH_EDzcLKaCz!J9+VZ-a>dNq_;7CaO|%s>-KiYb&Q# zmCu~zIuGB-8%G68B0+A@iiACx3k4s9UTHL~j=JeWjhdt4E50il`wV>y@dDgGEVX<*WDOf zZLA#jrcj=Uwt20t|f`Df0i6e~U zve9{TploZGvQ*-!=cAxwaUUy&@JpEO!jf!3c;0gie3QZ^3PW zdNyVD-0G>7W`&?{YRa~Bwm}ngB@^`#<}$S++M~#Sd%GzkG+?ByM2#pXiXk(5*a3%X zhkb`i3fa)A$WeQ;3Z=pY-OO?e6Td|hZ);;8DX9W+?GKRSSXq1V3{^|KyOwd>3$qsI z#|*I(S=fvB#X`$sUqT^mg@&?&VpTAmYGzi{om&GbG_#^`4cXOrjjJh#F4j~Bz0_$D zcXp>r)1`DIc+JO~w9U%|-EARFm6m+mAB)4)W0Y~;^zP@vDb;1S+OJLYRA;Ma*Ul=h%Fe2sHM{oQC<{eA! z@C@b<&#k?uDS{^1<>Hb0qt~=Bq|($h+%$|wzBim9_X=XA0oB&L5FK0nB82iR%vnpS z?ronL`&%HCsB%~muGa9)#<4f6&@{YJ+G&gI3GhD%#>S{2&J?FQc*Cc^r2$O=ogPE2 z6efjg*xh*n9=r8_-Y38kqIKqYl;z%Y=^0&gG$4;MIC@GG-9D(tt`NfvaFE>~hD9P0DZsD2s!B<4&( z*`lsCvTi6Y25r8fu?fz@NIjT$&>e_PLZPBAP$R(ux6m;ExjlGq*pOjO40*SDY`q8? zj+H;EGahQeDOo)mzDc-UXTbY|`s{)T-Ptlq_}JZqthKa4(d|Jh(398->lw^Ql>y%C zGPW)kPw)*Qz9|c}KWdm&-&aE$z->X6L9D>U{hQ@TvKCS;FDy}SETY)2&n)+O%gTo$ z=Dp4MwXAi&KXqiLbj*O*!1HKqhSP$EC^WbRub6gWs1wlpi+yvJ9gmrX0_>&`Js0ih z=%H!inelDZdh{k1um;%)!>twlrFm-^FvfO4d)EB!$%xh74%$M{QK4O;VN%Uo zh#hmoS>ZCury)IleAH0ej8kFYzz%0$%u`!q?SS48UOg{_aQ{(5g_&D<&4GPRwfw#2 zZio1ys6)%{lfo8z-!$G5y)$)Ao9ng8t(@635eLa0(DiNQj4B3nN$a&J z{CF64l=b3JG0cljz20sXQmwu_5nvTLj{7T-#S>+HLRb33FkH56&n}QCl~2R%I>BFbqf4)@c~TeT`-+!9=CE1HN9!g+_=5bA-hc z_B>{54nnQaI&l3DiQC8B!)B%#)ZU74I`}eLvy@*6=TlrCyK^uv|Lp0Q253o1=e&u{5-ur5rD1Fyac8vCJnf_$7)cIMWL4*Qi|<>n(1iS4ejNz z)r4Dsyvg=iRcBpL1TozYoa6&bU2e@-50ph1JEL7=)zCqHUd;t<9*9QG&76^Z;*y>e zOHj5<2g!@&hLRNIWIUPIo+PVDXJ0(#Kz#=KFbj%y6Z8nGh8h`S>){-TzHE*y&TA$; zk#M!)^a$NB`}c7z=n%%iE#BBUt^%@$<0ZLq_1z~obwg)684s(sFY0CeO(C!5yhe}R z+5ulieQO*1E6Yqcqrb4e4k~`9MZn|E;^}>fHlb;!c8hsOt~YloFdY;WO%Q3EG-}SE z6(-U3Hr7~Ov5o<^&4Ayiu6)j!Rh4ylVV|6$=ws4eqmXzv$MaD}KB$2V+sF+nf1zu) zD(JRtUbT|1rC>T((`VtKMwq5(mKTe{MT`y8(_L=9z=g;urU_yOOa`(K<^bHj)PG{t zpSBeWyNfCjH3Yv)^Vv}9nmuODH1&ukf@woRn?hZ}(`+}N@`uDSnuXX9Wv6f^x>|Y` zGKQBic>v#pN!f*6l=|w`T~b)3vXS0acxabnFxb^oEA=_3spHN5Xh06p?O=K;-1e9z z)9q?~tZ2E}BK5?*8ZH$rI+eaUuQo1`T{$yN+s6B5%$z3AUc|IytEbJ$cjkHD&SIEO9Emgy2V%)oxgK=iutG5f6ypKRzuP8m z@yDJEIN{(ZGDj#HI64NlOn9|fNrH)G5Jnxn(0S=u>W*?t5U>x?Mty>#Ib4eX6O4NM zmbpqyb;ff8;b5hKC=%Apgtx|OX56j2HWBw#v2|74S2dz0VD^08q(tIAGnMihLf5Qu zS$%9Dc=|AcmZDRD$k+Y21fY)6&7nAR$IAO=PBd>ntWIX^+f?_zA=CX z`oE7&MX*{?z>)htT!xs_h1Z6ZOH3(d>ZT49bVNlMS><=BzY5cr@#Iq*49G9G(C8i?2n|Hu(Aq`!2@?dLid`z+jHmk3=vF`UZQH$a}VF z1@0e1peU_Cd7VC+gCpws#-a4axm+6;>j!w1Hry4ojJ#LF$U%2!---yWptGCSYScO_ zS#zOlx3$v(pzYyMZ+t?Bhr6(;i zJ{D>}=5$0uwIP3#Q08lvjE9iI=nQ>s^dIFzujuCXes_5;nnNc~UbS#ngU*JNnT_C^U>hBN1SR&WG;mxbxA}SuP>M z9@F$vGY|_;3F0f97=Zy&>oGZa&T%XJh_N#DO|5-CC)=Lt!qz^c&dt~Tf#g{tehf!)La=bNzh{RRs?${B8hSVdWuWu7*3tks)AH6Pn1j}JTHC|GtA};@V1$L>nQ%oL zjZILui0LJ?s>cW8y>7vWih<49)zy`VNQ96x2Up(IWcNjP)e=)NFl?DlO_>!NfG`+a z%_RhvIJB57jj1?lBH>|5Wnej>3o?a8_9Z(X^pt&6HBBg)jKJe+?(t)>aL14>+|!Vg z4DvADq7f<|XUfua#lTW*dP0oL3ULJoUYJ}<2dW#(+?opVfRM?;&=X^c5T}GOGqVL5 zI_E(zcxcNdep$88o;7D`d9?@RA@r!-9%bA-;*~-$l8e3WTRa*>unqV62*9 zUs-ru5EurxwgQUaWkc5wK?;=*6-g6EO-|WF^jz~&clJ;PW=q#F0HbQ)L(|=%!o`5c1A z$ZE%;6gmO@nJ)avULD!%!5R|@>F4Ewk$h{YkR14dJv@|w_Y4e*Kud!Idm_3tckfvx z%jO_TmN0ezE@{NlWoOQg+_RLAC_$;&Xq?w15A>ncBS$mjyP^^3Bcjm>&9(N)*Sp^%u~NLO#sk~mC9({`mKnu6bm zQ4;zx^i=Fv!Y1*6LKq>E5^RPx?pO`~K;67VKkm{uFO$7TH9^WUb@NJX+TFym$gqL} z!lL12S<(vCkk6J4h5lWt_kH{uCV`owC@;DkD1~6#qkdz#C~F7SB2b44V>h<)OlJ=U z`8Y_5z;p8(ps;-z8fx8mj)-CBxG=^F8+)UABuXDx4;2FIe5ciA&@x~yo8Ij)n{G4b zT|%afGbYdD1ZXz!4miXQL16u7GY6_^hOyWqpkA|dv7iPGE_4tU0amE^MLrvo=yBtr zVv8|ZtzBck@mggbjMff3(N=dW%j0gn4Wm5K$TUhp>1?hD*drWE#NamKgs}XJ8!Ah3 z%j>%s)`lmvgn7kaC2SGOMoBPNqam-@WtyvXAslG19XTWt-!jSuwWrYL^N)@y93C6) z0zor&2bgscE9+i416l zVM-(-;d#?mJ7sS${0OCqmcY1uOEtHlaNBd;Uggat zT!OxX&JfcK5&L^KObI+_>8X|-nlOPI$O2-}mD44S+%ufqe4yR!Jzet6nTlx*#+)E{ zl<4u|fskTr1yK^cXtJhWn6yRsHimclIHal7JkX(0X4(uf&h%Q;OH<3EkgVEf8LjPc z>~0v)r;Y9|R)*0+8c`!T@@D=KhAguC_OeDt$^jhH?9HqwEP98wlwZjL`QoG?)GK-n zpaR9Cr(Ej{Z4E`@iwou`k=wjSz|e90VCW!^`#CBCd4p(Hc})!i6MQ)v^+@jNmgj`E znky+mxS?NR7)^emMk;QIr*FeDdp_RCWz^7u-L8;6;Jt68sz5hAdJoNc@u+QUfjOUG zLr;VEHz+f&>?r$QgcL$JwYw~mG={)r_m1Y7ZMA;h9wW2^tl5Ka*bNk%@DQ?Hix@Nk zbvZfG4f(=amPP475#`{mL=!Cy_R==J0#glqh6M(4xkM_$xDdC~1*eC#COiOUJ1>4U z_k}G755}WOR2rs#G`1jUj!~AB(^j?k=ru}Y8OMV__VH9GlJ!#;ASR;`beH$CT4VFR z->o%2kN0YN3!aU~4pOX`-eD)0r_(NrCxSUw(#Ng&v9L6h=YBPMJgsh+IRh7Ap~b+9 z3->Cd1ELm}Lm)NVfLCl3u|JS@r>DjuLD!HU!OHjVa?@Zyvl*+0*&1<-LQSV?tE}TF z%psgx%_u}f<0*K=qLmcqV;*xD%&^B06N(-akBLjc!aP7hpauFmVG2%SvxCw=!=bq& z8FxizoSPD6>Lh|M%|mKoX6AHpEelWC6l)t=XYi}Mk_!>{j{d>zDeJAE=&RPEp`zD; z+Z;k~VSX~Bb=K_TQI8S9;0xI&I9j!p$5 zxcGz5ErOe20@@&k(4=J7cQ2wN$G!TfT3w5}yQ1Z@5M7iXzOm45`!&S}`~nt}MOBYi z#D8Yyd}Mf zRmMgF)j1dXET~<|5xm0iq1xc1dYgF7&c1AmiMv8o;S-SG63wxTbLF~PX+hG7YVH;( zk8F;4h=_A4Ow#jXo@h&s%eh8Dmos#yYg0ceH-2ZL;h z9RxX3;9Do0A12k%sm22C1+arwcNoYLzb)Z!gv1_UoaqH|ymQUdX z#G2;rnXGygq?BUl7cI;H4O89+T+pQ{ro!}?3ddmymO4Zc>{rHPz^jOi#epr*j4;R7 zT_uH^YbYrxp>ep9jqalJLw{~k$0FxocUasZ=Ap{G;#F+~C02SoW=ZBM z70gb|ok8h9`)KLyX~Jke+NsNXyKB1s-SSP8HS4kjx?2k<9vBu~@MvoRMhZgn7Q#jiAhKCOl3{}w8oA=J4j)3WU^25 zz$wbVwA{jwe72rItcK^W!5d~XYiyoElnQ)T+l2hmyN0q8PT;t&cHQ?N+82>?zWK}OB0khh3r^ism6BG-zv7&NX z`P{0yygAEuW0Bpg+K7utEb1G<&VnJ|gy{yRhQWCA7Gq5iapll+U}U-Dr`7uxn}O*w z{tBVyE+ZgSINqCIf|RY5^ED_sI42EyHoZa%O*=vtZF7s}Rwri{Ssn|1N}nmtE?5%7 zmh7T^o6atTMS!tz_`Kjel$MAqA-dg%9!)kEf))I^efZLtP*`Acn!82unE53>W+?V9 z_K?=huB}5L-t?Jsu<`_Td70w$NZCMtPv?^64$~(faA*K{UrjHQPqjd^$m;zJij35iFMm@LxfHk+p^X*ejYh@NAR(;IV^VU3$W? zYj^8LH%j01EmP7U+Jkw&HZdE9Qd=jCMRb+s9mh>$nOpR@7^B9}BFY%cXftkjVNQNP z?`m9(a(Wcp5^%l1xfl;E*YVdVC}`KQ@U&&0y%E@QD_+BsIbnCuGOoNSA(|3it!Zb#U#pMG;G??r$D&9~mHHSDU@*7wY zI5!qy1g4;wZvn;4%0ye9?myKER!k_n7^<+$GAh}`7z}$VZgN_ zLm!z9Tpa~T;JGlQ0R17y_R+ZW@1wwU7fwJz(Ibv<2_<~9jhwI=YlgUw zMMFHg>~l@t2N~(W%fHw}L1rKY@h7fFO?Xn5L9>8Ab}&vN&H(#+ibdZt(7LupfdM z{xb9Sa3+V%`+^Z;y#NXod0oPlClXE01EJI|eFzjQWuU{%`&r?TgI;A4&7ugV&8@0J zUB?J=V$!I)vvQnf(uOu;#mFfb)DK|%VcL;R=w=;&osaTE&nOAt+5uV|N;~RkwbcV! zgYi%kUvQ0bl1*F*_&5;UgnH@`6mHzO3SpDhm^yN3&Vz<>2C#Ra^3RFKqI20r?vTpA zAO(+uVUr$pP|)+nBTxZLhR5%xNCb;faIniK}()c2+1*-6MMox|q0;6zq7D+WDiJrIohVl)_KP7g6C4&RVI2mAw2a~Gvl{0pku!_YV2 zN?{j3!`4FwY+y3m#`HXPdRgr7FxM6xYq3TaKgoP}pv92D+OE{wXIOxk2PO5Aqb%*^ z79wJzQD&QaSM1@!l%p%#2hyQCnGT6+VETl6cWj}&tVR#rZ3bh~L)E=A4F)9WTjEG7 zYOIM_I=5_m26qob#nf{IAh`DgeYxe=m-w?cN+crhe4N#$(#G=`SS_uC=Nv9nezQ<^ zU$GBv+vaja<>66?fQqod@n>dncWHAW=ZR1PE-=C^k2&w{eS_IyV%t z_{|pi(Ofs%;T?o3ZMq%g08I!Q-zElaSw6&>s>9{7c66e9?eQ@HO$vk`5xM~*(qmm2 zQzvPgpu{--7YE+LDm9;&3l%EZ@rn`V6tLU3`0L%5?zZNTZ!j*5WC!d?;ofsWPqorrM3ijh1Q$jHZ9o+<~1%+sz zLfC1L`MgyPMf7yZZDKOBnw>*Wg9~RDywC|+TJd@bG%T3hT#gSz<0w&cv7zMr-39ID zq-oB-7$dQK8=jS0D^_}Dh%`d>a8fA@D|+)>oYUE29>}F`A0gy|MUCoZlEx%B?=U$S zW`1bz0+F-EMr2=^X9yw^v@TRmYjl=aMP4c_G8OwBA#C6@asAg+4T|4_lN^IL@e+_0 z{)IyI{vOR7-2^A;z`K#luJB=4It{2&A)Fmm(gOH+Nri1g>9szm0mIXAi*b2seoc)T z7DjKXU9%{>*a6bT1PbMx=FcLch6`{|KVN90sdDIhdqFsqDN;6jnl05l8TnQkuW>K! zJpTfh{QHTLm7MwpmfyFYGBLPLL%~fzy0JLL2c{vegn3*=?q*rea9-M!D`bprIQCv< z!=k+j@HUIh$BnFyG4B}iT9BuZFBYu8UIn7qof}~;snol!o?PbAySaip zn9g7pE3M~Pl(|0=`WzlCvsf@N5M*Q#7Mc{Qz+&3waexm>5*{gr@Y!?6VvvY`u>7On z!ysQH9;MnS#VBela%8vQrV#C+_~wEqZC((paA4{i6hiNBHAX2J+(5gEwjW>ELa&L9 zKBC>A`XF|FA;#aCRYoXa+?0z$S|qdUXq=Q`A{G(PeEX33^sLa$YvYZ@meZhK>g)D! z=>*ib!kBJT4ny4ZZYbwwh;Aa%Y80`Sb?0i)eJcy&m^eHQ{=f2TtT}YRuGI(c6Cvc``N76 z^CF#&7fw94^-XLYCFovIXE=IhQNAX&%^70#n9YZ=0~GTT>8g#=QF}TU@pXU*5wUlj zU^LGvBwDOLRCpXb<^m5)U9!FVkd3Pk!xZQoXbdnoMiYX3auVdfhj@Cu!E5qRdh{)u zu4sxpHQ;#qtDY6(X)84s03$Z^zS3jt{#SIqg|=BTi6dKZ-Son>B!@{n8fJ4elz&JU zWLud)$JmDI0<&3eTHFLoFb*x*j4Jw3?Gg7d|!z~8%)+QGbU|_x&)0eE7 zs2id8KYoQo{O%(}PCQ%$u7?h_3t ziTrh_t}ca7Hy-nvRX#6joyk#0TStM>xK^)ducBeV%|)A4&lhqh=}~n{A>n#9>kZGd z_{}OknEl{m8-;0Rs82{+rHz}5Rc_3~u?A4|h%GQ*r_=umA14?3lPjHT&G3HN7a&d> zp{tB{vBqZ)!9y?1#)IheL45TESWE^Z{(PheIw_1VU|3Ou8+4P(cO1L|4l~o^hJ)vg zT48oH<+1{AeNsk#$S!{HuuS=quR`lI4TC*~4d1f(B(IS}dIq#W7vo;I1T+_hus|G| zt$fiA$I|57p=?9d!3!QK@F}VD;}MYkum~WTWe>tj(u_z31`uG;Sqm4Xq2dd#VqgJH zsC!Wf|4Z?|w1xJ#s%NW{a;ih4oH&KXmoDQ}2T#x2WMci~;#q`TWd}|qlLoP3L#2Vb zH(ZR~mFo4Prj1&(H!|bn5Iq)7Ra0A8Q*I+Lw1c^3rd59^lu_-}xv?vjMFmwTKmQh$ zJXWqysaflbo=03Y^VO2wZWy?!(0tV;`+941x!UiF6(5G~S|Ac09J=v2 zx$L@3^3|qzS{xtu1>(^pP3qVnG5U)YXvehh&?wB2BV{d~|6tWH5dq2hk_>>%Pi32G zehx}5U&zp98f_*hr*mzcNBJxALHAJClCRiCLxIyGUkeHnXLk>h2M03R%JdGY^X#b= z`o}t8kp^5F#{IpvJFz63V`&S7Btv@TyGi^cJz-KZ1va+Cx0&%JkZu+Y5FAa1CuNEP zkbI37+%a1mje*4Mu0%Q|rC12bDzxQ3H7Q88v^2;{X=#b#u&irK{H~-lD1_3|OfuEd z($a7@xMpeT#PHjqq$XM04@=c&u9|;KUT<4zCy^tr$eUOk(xvKdqsg|a7`$W}8>Qiq zNTUR<`(U>u*qs>MMoIYCO7Pf{za1YGY{~ebfJ(-fBKVh6O@p5V?cg^-5@jgKz{lr8Jn@4}Nl;Lkk`ji77Bqb{ z7B+85#Nda)l``o065pmL1r4JFSAj@o$W|P-l{mSiB$fPaNlCh3a0RCYb+H6jG`+&- z8h+>smcg%s%2`t4m6IJ)LDBQSZ1o8n!s2A9#LAMz4wSf;^Z;+43*RlYElp*oXlbABnEf5 z;^HMX2dfw*&X|OXOT!zzn7d*b&$QfzV!3W@7+aG3-2_&6Gi?(`GboV{4-m1X*7GqT zCR426O8hvD9|tq%r_Q$i#-nD;kn|X$#BWN{;Uh?gj{u5G@!H$LkHcqx1wn&v!)JiG zfWf!nGeEGSd3I4K^k75IWA*sN`K93lF2xf~#(dZy7wc>?PC*@7ynqJRf73e|Y<*Gq z7U)KVg+aHyn=Z6FAV%UDf8kW}M0QFtVdcae_~6^HV6X&n@NHNynXq8Op1LFxNEaHI zXkL6luMGt!l1+uOJT*SZVR}+&{KKT)7q16M%OoD!N~D=V^?oRDAF z)z;Ya2s3CQ^uOB#AlBEk`KBqr#xHyb5NH%EW0Y2yxz4ymX+Ay%m%fPzpD$E#MJHUIi(Kb!@ zVo*dS6N5WVL48U5HWexsDJT}fx0$?mGB{jRmcjK?C1s{kS$nZz({N#kL_(#g$TS|| zq+#4}@J)(6s2lg*kD6b^EEXzA2-u?Uz?@Zy-<6ah=$Rfw`vN1xW_h{jD;jAEew9wX zAU60WD6Wz+^lUy)-)*Ph)bO#D1=YHwEGV;*vY^aL%ED(>7Cy63!%2l24*V6#l1qge zPAcpGQ=x{F3N@Tms9B|;;g|<7oIaDd=TxW?WlDp3oe8CD2GZ4o0+KUk;4?x|7DXLv ziEl_0caRjGee9HSKagoB@De4mR5B@SdC;_iZ&Mb!#y(v${eo}9M~KcZ_%?imlfp+h zDSU*XdY=k4BuwH;rkqNLk1!o%BNZx0DK77u5P_kBluDObhl%kf$Rs$F;r?|`{D-cA zgqDGIkP^w2LanelD&`vZVOR7|){GLTW#ZaRl>)OJ;827&!^5D=97~*A658EZTO@hG z6dX*6lT$?+QjxfVoDNP79#AS1mQ1K2r68v1pGo>Ftp0>fG9NjkgDvrD?Zh=R=w1_{ z)8_37z7BGjK_BUggIDw2;~o;fEk$1kcX0B}Mu~4zp}!&pJ%_iGFm;Rbg1J0FX`wkn zA{IZMRFRh?^jM@q=SK>b4O-=#8C>VOuz*G~n^4K^Ro97Q5XyWo5yPNftvUblzk_g`gBlYGJrJk!n%564srd zRu}atVWEd*PNCS-g6JXdgOk}zg*s9y)R9u5j+6>@q!e_d-KsloJ2|eLytS|hQlUiZt}1;ABb$i*U-XTnYy?{O~wSz7M%Z z!*N_UfGof#kz6S(yrhN3hHh&qCC&+r_OM3^J0$c+3~=!nN-eLMOenn1@HWG{q#~0T z(K3go4VmWGKT4#VDiRcBVb=iVD>ylQ^dMztW-ll@8lU zNs*uk)vt8eRMMgPm4^BSMTYinGV7s7IgLVz9ge#h@1X-B6P7^<1WY2`On6(EPw5pf zc}{7lOom-`*i(lcbx}rwXA$}_!cIEuqeIab`Y=kNjVA6U73z7ZP|r(EN};c_#pZ(F zWOjRBW$-n|CX;Uw4!#TObt+Wv(nXD_xHSbeH65yV=}^5(hw5D#>fLTb#EE>R(cMDt zqS#32D-c*`&)RL$xm&mvJ&F^|ujMm76;5SArW{t(1Tctf4Fd)3FjVqG9Rn&xLOCk- zy@#4csAzCE|5Okz+dQY-W7&{=+Jo4(n(-tfc9%mZn2(GL3p#Sji)}MkwLJ zTAB{4X(p_fd>=)zk(v%Y9;J}W=K9HB91+h52T0cTP)7VR2GJLC5tWe#HGV}lMX9RI+Y@f?^gzJQXyNaHySx%1P+If%_);yWkN_ z3@TQrq(DcB)c_B`h^Oju<^TeY^8OXq=xu^2o=M*MXg<}%mD8w0&l(-m{5r+>g*w;;y2AD*0Y#iJ$J;^5t*^2W0NZHf9nI&Xb-N& zbM!MF>`3G_9kz-znnhwj(7fTn*+I)lhgM5EtPJU}aiq~Y@OYBLHi?uop;t45N9$8< zgLB}GievVY4=od_?U_(*&%kjk%a3lW-C7f*e}2+^;%ZPwl6yfdnG`5X@Hts$;8W3( zKMG_;=xu^Fq6g#gX&#Z2mOXMjP`kphPUYiN^+Dvh`6NrjTk^Kb& z3>huVz)M^;6RNfu^cpxdKTK;9+~x}7Xz*f*L>lR^a7&?f#4FFlod+Wy(1T*Zq7ihj z_>WP?Z8g183jsCfj@b|R5oV)udBwy1Xq;r+I{C1bWvte)uDC84Ea!*N#v+{~6M8~3uAx~0CvsmxRiyZ}q=f;1OsJt{ zLJchwYG|2ILn{gUy3)`GS{k}GN<$xLX*i5q8ft5$p|%!2uF_ChD-Hb=>Ci&}OF;D| zmblWCWSrPCDw@OY31GnF(E%8K^(rgJL*8UXRjV7L|CK znb11OKu1o#*(x}5BA&b6qaGX&Y?{*0ds!OlKBb{rTZ+1rNUAh+V3vjk$_;GMncGE!ziw6M4pJ1j$>-glcsr)J`(c zPRvtoUiKnKWN5BtLfs@2>LwZJCN8o5n|53p>L;b4ev&R~0dN!Mr!FLJt`z!7a^_6% zRarbr+GE`ci!fexkjA%FyJ6Dt=govJxYAI0C=Hc|(olIQ z4V4GJlR8<_q4L1x=!0(q<$>$vCBDtz!4|zEou%wEs%)}NVrgSK+-Q?)QS^dLFA1|- zf@b9@#E#%t_9d>&Nc~_pFgeobYWR$IbIFCuL1`#^)9^G!)2B{7WyI(?HW9ab#fa%A zoiw5f*7FENj+KlZpFTNLa)M0A|BqA4$3{_9-(26&8uc5AKlhk;a(T4pNA@Zo)Nk+p z2M!$C@8Eui4j9(&uzrX4KXTxhe$iM|P8wWe6)!M0*Ao8)?P9FOnT+LM)XWmQtiReV zubnm4=GsMeqVF_Nq$i{JCQgqT{yew3rx;ue9Kt0BO6E`>j!u*C1Xo0 zI||(QtohkY5^I@`Wwd7});k)T97h|=!5;g%p%<&GoQxodu?@LgG}hN{tZ%>?XUmkD zR&&H^7Ix!)22yQK?)%ED$rG?_aALQsw}FZYuE2bG8aPI|8XUv?9L#wS4#h|ON4V)| zELT{dUFo+0H^j-1UYHkVWti^-a;O;p$InqXuOGHOb$$jMF-AMUK>hhqaPPw5Xy`lr zqtW|C5$d`9p63n1wn+PNdUZ(aEgXwKaeAY0Aer9ey#_>mIL7n_V2jhc0e>g+S8;L_ z)!Ft3nPH!syW_tax@pC=W8|Hu7|8aV?*u!~Um*~6oIBy6J z@VETL=T+nH99=riLcv@ zzmwM;v-f~#2#)c(`{+FW?s9C&>u&ll*In!9<*&>0_6PIa?}PUfm)~RfJDFZZNfe#OLe+=g@$)n`{>|U> zbMsYE^f(JdAAZN}4`Q69malzyz4|@QOXhDS@^>+gG5w*~;{5#;e>2_qIc-FGAJ&du z!8ytF27Y8f^cH@|^bWxmr}r=XolI}*Poro)59q`5`1uF6WO_UIDbxej>o~mw@Y}tx zAK!20@hBRJ{rD57HxlRZ`Nj7!59e_|{>0~gA^oG)@%Ta?d~KhWqV%q~1M&}b zn&};jEzaMkiqd-)7d^|9u>a%qmKUWraC@O1P}aujU0sykG3EWE-yd2?Fi!9CqV$F) z(mOtp-nWX<`(R%GC~>>_I&yPSdLxnE2&BXNJt2|ay+!GbI~RrgA@%C}Md?)_z0IgV zOz)&bdYhD9oTqUM`bX0t6XFlPwmd#lbl$Qz`bTHSC+QrXyH)4KUpi+8~IyaVue+}8N@zj5BK_{+q3Je0iB&{rWh(ouwe(fjy<&vytmwxMKt z1CJaS{pmy;)F)253H!s39T2So`y&%qkb|S>8u5DaBT@7K$n#$2KF)hx-@hg9Byrvd zB+T>5$OF;$YM(NTzgs{e{U(w1pTA>!;qi4KfA;{1bRO67p}05h4=3?`M*Cgl2*_fv z|9(-llEigZkx1_f@fs4>xnBFL!6Wt^5N!gP?iTV$+#fl9Kr{%2cf=6`B8VSLZwQI> zhKj>Tq=!?Z;Yg>BL^|`yekf1y2<)%p{_(gU66tRz@uT-hq(2f5jK3QX9?>871v39- zB(67EJe|b#DzraCq>SSAE+&!AP;}HRk2a9$bdgA>N9-e!&J`ekw}Hg(Hj&8R783b; zi$wkgLV;s>4eChy?fLZm{rffI!ywb$L?YeCNu>9r_BWFy_`UYGird8P;tr8Qn)w()9)%Okz1CbXicar5U4k3}R@gUQmPa>U*#p_9w+joSa>pO{b9~L)@ z!=OyFJ&hr8UImHss>oDdH!$`=Z^td ze&b1$Uq&n=QGS!Pf4W#9&Je4_8nI5CC(b7)M9~86H;FwUpUY|z`CLPuJRrIYJmOTy zNs#&4NFrYkh!2y<*CsNB`VBIjT_n<>(ZKx?B=*b5k3pV^3rM8j1~UCF66yDdeI(Mq zP`sE#TUaTsB5~atL0;!Ba_oR;hxQ}rj@%zj;`(hQ>hty5UkmcO>quO8y?7Ui>u%8g z!ywb&M*asn5O~Ci=r8p>m3MnyAg@zFqW#v9s4rbQ-be0-dP0syeo54ahe@2jMf-ye z!#?WOa1!5-CsQat68Ts~;yPmvclMCD&W+k%OX9pOI{vbb@6`TCI86BaDiXh2p#5vK zzfSvikw|BU_QwpzKFV)0iQmdT}FpILb}j1+u)~BT?QFj3;s+iSiyq zLS7Bl@gXG6AEy1`B+eVD{W01ful(G5hI+} zkVtoj_QxOX$4@8I=zmB&ryEJspT|L#>ysqPb2Eu@-y&`$Q7+rGze9Xod{5s;$N29? zgS`KFB=WUdTu0*iTeRPFtbf0XM15JU{cR-j_qvYL*k?LbB#zG~aekMM->Ch&v_EK+ z&L??3iSw`5@f|w8Q^$uN=jYESaef<#^Dor#RUpgd3KHdVjd(qYa#^kY8^tx^T5+AY zUc5`(AZ`>N5FZvdiI0mIgy68*+%68H76zTc|vck25g zqwzg_LnA=m=SULwIa(Y;vR#0@-o@l8NS8bg{Q-Fl@{mG%WWB-DS9_x&U}81-M=LL$AbB-;Hpal5#K93cA=zk8kg;0TcU#O+7JMidao*`-1&Qm-AaR{45r|Ig$N%ve2>TA;KGZ2Ax&z|~k=Nt*<3(PN`=^Uc zpZhi9JaK{8B6f*=;>F@B@fvZpxJFzj-X(4n9~K`MH;Y>nj56p4xIZw8w(B^{m-{bk z|1EKs7~x)cKZ8UZj!x{)|M5Y2@q=#IKiJ=Z^H}a1McV7!e^{iyh5NDn{-pMq0H4nw z@+9;>WSRS@_`IO5+4sXqI5b9(FuF&Qc;2H){C+%%?^z%CeHn@0TYbRy72H4CegFOU zfV|^AevcxseA#uH+~?1HTKbEWek1h3y*$0u;##E1^f!u6irdAV;vm>nR_|~FW z<9&ad_?9>jH^lRXiEBl+dmevMWc%m-PH_<0KlgWtln2}&aiX(J+(hy@Xn(8rx07gZ zgCPg_yW!-~C|7bZ?w?$M`c7Vm@+3crc13<7imJ#;)PM4lD5@h@pg$)+4j(m%hp~W6 z!{0+zM^Oto3H~1P9O$8B9rR4{4ESxx3Fse4e0(nCszq`mWc%In$Lw1|o zLLX;xYaGgx$5AF*_`HYU`Lq7P$G#``VVfZ7s6TWqR0$*0Xd{Xs>JQxw-5Kgt6pht! z+^T(#EF0&Gtzw7xDe+?QO7TnL&Ei_|Uhxs}Y4JI6yGU0#^IIa$5a)`Y5Szs=k$z+T z?lSRO@ka4>(b_T2`-%3S7Jnn|5Z@Hv759LQVEPA&hlvkBiTXJH&s8ABg)xpfLZG zt)%(wz-ijA6C1>(;upmm#5Ll2@m29(;vRc=`t(ABu~y8AOT^{km&I?2cZ)w3 z9~bHWWBS|0H^leFnP@=#zE1q3*pG4&$M+M5izkX@;xw^A>=HjCULk%>TqoWuJ|=Dv z&CiGH{$2b126;Y)h)0QI#gBwXe)J#Wx<`s*#nZ%U@qDpE{ET>&c$0XC_@MZ-_=5O`_#bgU^m%rD zajbZnSS_9}c8H%5ZxZhi9~7S!Ul89A_n@B=_j|NhCRT_w;`w5`xI+B4c(?eF_>}lN z@m29{ao`ZY?qT9_;skN3SSxmmpB3phWxl^5t`{E?pB8^3?hxM;|1Itf#enG?DvlB} z;$m@`xKg}MyhHqv_=xy3@hR~+@i*eX!~xJzc>M#!D)Ah#LF^DO6u&NhN4#D9fq0+z zkocJRg!ruZYw`EupTt+hH^qO7{}%hfkIQ`TCGIO8BpxOnC5{qL5=+F1;%VX;VvTsV zIA3fKTf|QBQ{rdE&x==z*Nbb!JH!XXUx=@W1ECYza}h^~UKZTKtZ9 zulShwEAgM=9`yU7Tn`pUiKSwtI9F^Id&Nt|8^mvm_lS>)$H1S<>x>saF3uLSVyAeK zc(r)5c&GS~_>B0X__jEJeqCJeK#~4q?w5)cVx4%6c%x|kWSoDm_BV;Y6t|0Shy#Xs z`umGVh$o4sh|@&+m6@LgajE!e@e1*~;yvO|#9xXph_8!>!LQ78j}tTE6tPA;Uu+XE z5WgU<7QZ9jD{c{Yh&#oBux)tVq2fp}BUXrYVw2b-t`x5q*NPj&P2v`DhqzN5h-=&R zMf%6NpAjp>Ih9^Ch?czOX5Goe)O{=A8D~%tP#%>JH!jc>%{fq{o>EX z=fyvZJH-Jb{CWq9M~madkBimfC&f1LQ{orJuZru$ABw*f|17>E4m{egKSUfOo+_Rp zo-4M9%f-vY8^pEZ55z~sXT|N}o8rF5`1L<3o*UYsn>6weWx#hmzA@oMoK;%(x6;;+O%iGLG65ceIaauH7u zCyJHg9I;;P6hAFqE`C+~j(Csw6Y*K`Me(oVd*VK$JU=IhW#V-4Y_VDF5kDt>NxVh8 zOMF<|EN&Oy5~Jh%xx_=2u1id{6ry8SU3K|0<3jr~OiKws@YnQ0x{j6|WP&Cz^j2>HSpu zTf{$#=AXs)hn(QoA1R(H&J@oPo5h^?MRB!wr?^FYQG8X5PW0>SBOW5A#M4BM6S4h% zLTnM2iPZCL|h?$Uc5p4mUy@LQ}LJLR`CUKhxnR!z{#GU5n`D* zO{^2U#GA$2#HYpIiZ6?Aiv!2%e#K+NvEpR$Oz|ACS?m!n7OxV&Ej}tfE$$HC6#p&m zJx=)$M~P{%PFx_iiQVD~@lx?R@fPt;@yFs5;@e{X@qYaw;*sJQ@f2}}c(&Lit`IL3 zuM=+(?-YM5z9GIX_Ak-(#UsU&MNIOub~jy|E3Oo;5pNRLi}#CXTCNd_6?fD>a zq=@AV?D)B2vzQZqCO#+rQG7#uPy9&Q(-|h7EMi)s-;X#~Tr6HCeqH>o_%m^rI56Ys z94L+ue;__2J|X@_d`bMLIH1(i!E!H_uL`k4yiok2xLUkb+#o(GZWdn_yuvbxK7+4J}UlRd`)~u z+-s6w?_lv*5tFJdA0HQIi7n!D;)~*I;ydDArzl&C#D9u=O!j;nBpxG{h^LFQ z#q-5>@j~%(@oVCD#f{?6#OKAG;=qsj^@oZh#f(@dHi=9Rr*Nbb#4dNzoi?~DFDGr>f z>x(1BjCh{7NX&^Bi&u*`iMNXnh);;W6<-l|iF;M}^$!t8i5YRKSSt>%^z%;;%fuPt zT(L>aiI<4iifhC>#RtWw#BJhh;=AJB)BO6w#N)*YVx@SVxJc{~KPP@kyhXfAd_o*F zUC%|FA=Zft#18R7@r&YW@lkQJ_=5Nk@z5E5onysuV!1d=JXdTMmx@=4cZ&CmKNYu# ze-i&L_M7R~9U>kjjuk&9R*C0{i^UbQi6ChEXt>R1K+u|OxJRd{FW5twME}kXU zi%Z4Nir0#_hl>Zt)WFD)C0~d*Vj%r{WgzkK$Y6f5d%jJwJzu$BU)nRIye(Uu+XE5Lby`7T1d3 z7ata%7PpD7io3);=XidGipPlK#nZ$p@e^W;xJ+CrUMJox-Y)(~{Dt@{@eksg;``!0 zbt)(Ec(GKRDxM`~#dh%$@oMoV@pkb6@d@#_;w$1Vaj&_ak3+;!Vn&=Q&JoWSTg6`S zbKX1;&Aaqu}qvM)`<;bmw1tQh4^*xd*XfKGvYS! zHSt|>?{hpq!^Gpo3F2~brFfnAP4RB=VeuL91@W)qd*VLx{CbCrCx~U@bn$GlS?m!% zC*FFlr}G2xQSn)EyZEN~A93GL`0s{`CyA$sGsT7H`FT0<67gDbjd-W{pg4BE|E@xu zBQ6y`D_$qA5$_Zq6rU2eiLZ(8ihF<3uQN{O!d`)~;+F=H&Ejq1Ch=KuyZEN~AMwOi&&Nb@nmAW%5_94u;%O8dD`H1+W_-pa+;(x@!IY0k!akMx= ztPpF(1!AZ8De(*9SHy3No5aoH3*zhIyW(Lzo{v#tS}Yf5i=Pyih%3a;i#Leh67Lot z5}y)(C%z*7OWd>9^Kq~^QcR0e#IwW&VyE~S@k;SV@iy^(@#o?@;-1TNU2&wC7N>}3 zi3`L|@iXF;;%(yn;?Kpc;>+SLanN$V{xEU0SSHRBXRYw_y2J~`FN(K{8^lM&&EgB< z>*BlOpbI?RL&T9{N<3Yx7UzqL#XfQDr#zh*;wQycak+S@c%68Qc&GSd@d@!w@!#U! z7y5M$6-S9_v0SVX=ZlNQKJhZ~Ht{*}58|8R`{F*I_Uj%d9xs-PQ^m8ytk^ETF8)jG z{~1qjUvZc?QcQ`bi`C+Mak02Uyi&YTyiL4c{JFSQd`Wy;+~Xq8&rorsI9{ADwusBb zmEsS@y)O224ib+RPZci`uM{5@pAvr~z9jxr9Pn9B_W%Zf@v2KaA72yi6@MwdAigTTCB7{l^f~|iQR2zs46#mJC@vL0EnY5u zRs4>4kN6YuS@A{juj0SOy;piZ4izVeQ^Xqae6dZuKwKq$SzIfAUwl}6THGeSD(({Z zy43SAR6JHpiREIAm=!z3Pm5QIUlYG8ZWMneJ}>@R+$j#Y%=2-ec#JqsJWZS>&KH-6 z7l>aFSBvY!d&EuRbK)Pxzlr@m@A=qIJVG2Jo+_Rpo-4M9%f-)&*Na~h*NC@@>&5Sj z_lZ9hpA>&7ZWUh;cZjcwZ;5Y{7d+{~#9dW-ec)kx8M~f50O7Sdlfw)9mE?z2LC*C67DgIb|Li~;R zlK4+?z!yC~2Z%?BCyS?wGsSbn3&k&p-xfEBKM~&&KM?o3+^=_pI7U2GJVQKJY!R1> zmx(usYsC%XCUJ}SzW9+V{JKNLL&V|YG2&=(tXL{e5zi7E#a{7J@k;Tl;&;S*#23Za z#COEKuJrsJEFLSCh#wbciRX!};&Sl`ajW=}__jFsD!h9^ zCh?czcJU4IJ#op^e%)2#Gve>WSHypbdtBq^A0!?vjuSs7o++LyE)uU6zb<}P{GqtV zwVwU~;*sLX;$-nm@e|@MagQ(g?}v&b#VKO7_zAH^Tqa&BUMt=#-Y)(~{JHpR@z3Hv z#QxVQAL0mctT;#9F#Y!JJ}hr}nvZQ?89E^)6f>pJ2nF(XbB z=ZTBNW#Xmc_2Re0?~9L!o5k(o8{+%o;IDW-J}RClP8ZJ>o5fqiyTwPuXT?8=e-rzy z_Vf=Bj}}YB3h^9qvG{568u44=z2Z;B=f%H>Z;N|=Rpl!lCr%KjiD!!o#bx4U;+Mr+ z#e2n{iqDIG5#JF9f6cFdl$a7L#d#vv+vd2@MdFXepNr3ne-{5K_W!!dRXkc8D}GF@ z63-JCiz~!c;#b65#e2j};&b93#hv1wH+nw4Dc&hQC_W`_6JHnK5eI$4e}AZWoH$8b zEUpk&iC++~XF%{sH2l;t}Gp;)&u!u~M8P){C9ur^U;~uZrIh?-d^tw}^id|1S3X zrsr>nc$7F+{FqoJo+mCASBR^`uZXvb_lTRs=fppX(YJJc@kFsqoF<+lwumdl&x<#R z-xBW@9}=Gue@!#@i;Lho-S64^TowtpLm&gz4%S>F7ZL}N%6Ph%i`PO zz;Ang4ira-W5th&RpNQ#VsVAIN?a|j6E}*Fi(AE)#a-f{TRk7c#L;4znEQ@@ze2o7 zyi~kgyjEN--Y)(?yia^cd`x^od{+Fm_@dR=Z8$FB9()pB8^7z9a5=n_uTp@mO)Dm=!M-uNA)`epkFld{o>lzAWw( zqxHI;I9g1L9~W!H^TdVXh2mA>YVjWNNpY+A7jeMte%&L*6UACFD_$sGDSlPFP5hy_ zNqkn^CcZ4bEADlNU-vL^lvpB86KlmLahZ6Dc$N4y@jK#u;$z~o;$OtSiv#cUd<-G` zVZOXLj64ME!sz=k+CNo1UB}PVehrD=*NH7U-mU#*% zecFFe`#&c?f_2`szm3H8wu?JR{Qj@{ewX&&*Z!cp{Pzcuxc*Tjet)cZJc-|r*Y~Gt z|8(u2sr?%5pQrr=+FwEQQALI`=#1HMf;W7uM=BzJV)aGE+mn!i%C4s z_4-e9<*L3_%@gF4ewb%EZgGuD?Q0))b{)u8KiR+(6;`&p>YOz*q5?jR2 ziSNL=p`9e?cq)paLuHkR+>$B%~W`@UrtQRXaTX6##*kX?wzm>CSSnZ;5R zA!ILQZ4shSWX+PbP=vB1dngK7L&X2O&ht6Web4vzpV#aAd(Y>2&OGNn&pC6=8J#&l z+{6Bp_?s%1yN37K?poz+&#lVw3ectL@^lS4l&(uRqFbwSyE?0KySiZtrsGH)gYV-U z{2DjoZdKOxmn!SO!}k05i2a3EJC`e=%H=B2)o3prK{uuQU_Z8}s&YGCQ{{HNp~~Z9 zsw(T4&Grx2zMSoAaVz_Gvi|_vkKt`q)|X|CbNp>%8rz*$EyH=ES7FFeXN@7{Hn7scZ z)>h?mjp^oe2f8aAP4}e-(PQaps@$&Gs$Aa(xLhsfa;>8`;y$)tQsw$@v;7|a$NneR zIr|H$#pLhc=?ZjJ+D*5^Uf75IiK?t`uqx|&Rh9GpwkpS+!S-2fU#-fzwz7RE?pEdU zC-AH)m%B_~rytN+);s(2V_B@G%6i&T+D9Sm z`}?y0HT4CTYb^Vx;7nYED^*#?7CeW4W5Es1{-^L6jKHqg2a|9b&cju>33uUsRc_bM zcvO|!^%q`KWqtQ)*G8vvt8%#lbZJ%2Q)N|-S4}M?@B69B@Lv?`Y$Kxe3O zoMAYD?NjJ?a4y>y;&NPzTW~iX#9vi8{wY#k4&255<9J4u z%l$=PqaR|PZ=C(bRXLyKRk>Z2F%*5+9ACgh9E8JFxgC?~>9|ytb*!T|;ucjdznlF( z)93Ia+i%i$>5whX*A>PRsvN%(?ZI%iH&NyGwN~Z!wNvGB7NyGd$Fn^VN3i`ZoXGa6 z_z5n?rMOy^<87w5;a;|%qJLBM`-$y$u<%ydF1Mq!D(ftVl~g%yP4SLo^_k-m-XgU<#I*n zl5}NN?vGk@T{VmR+`y))eEmzx8;x@K_iwE&A{(*nteN~R1b%$eKRc>EFEW`FH7|M1ZHe-8R?8x@6n1Crb zOqKIEMwRQGK+m9O(+la(=+*Q$s;qB2{>1jsAvVS7`->2u&pVCX|wW`d4EvlT49jct? z{i>|zxGL9k32$ST@0{(qunM|WIZhZxs&bqr>~BkVq07vX34l`5Cptjck|WBd229OsNGx92k3ui-6KzAncu$Goast^{3{u0}sgN6_`@ z*4UNpv6zNKRk>ZmajYuWGmZUo*#4m^>;01b8`-`Ecc`-7qj*A<`zwZ{0>$1_NcPncj))&?W$bQk8J-5kEpW#Kk;u>F842; zYmc)(zbe~HV^y}-QssKRs$6dq_P58L*dNnzBu>IvI3E||2HcH@@C;tYyO{NRXPpJ` zX^h0@u>aSncpU*R{n3xC2>s+^DC@OM?t@89hImwrU&`oYZ9)hQo0z zPEqB0-cjXxK4kmnZ2tnkVfzkx7am~yG5iy6t8)7us&f1%esqpsNR{(nMwRX5*guc>moX5%7UiJNf` z9>!C69`9hz1J3b^VMSGLM^$`AmD|w(o2qjCFVdapSLh^6WBcp$XnG3$F1?gqt;+ST zSLOcO&Gw(zeuV8;G0Q>c@=vOA`J!}5+DnJiEmXN3?Xe5nU!nV93J$|Ds+{-9s;qB1 z&S(GU^cT2+?OW&_xR>pR@f2QC<@ncCIsR>Y;wNcYZyr^)7r-)XuSVBY<@QIgy)m{_ z<$h|f%GY56H5SQR8 zRgQZ^mGki%+keMD+5ZqjjyRXgr^?qArk|oK(a+Idx+!+T9;%$D80@FY?HQsLbGb&b zeJtCjvwbn!m*RT1e@B0hKj9I)fS2%wT1@_Z8*?6&mfK$%pGGhC#Z*<+Js4kAvJ>VtYrr zt18FoPbc6oRgU{6PGb8sRW3h|?ThdWT*dxP^!KW)>qoX9!OLvFhOT4I<+5UK%#RhZ zD%MtIeGTcR*pBVpFq-XgIGF8k(4%n*+h^j(s@%>+s@#7o*uIJ0tv(^&$9RDK$Jl?K zzC_*}C}xLjSZJNx^vKT(zI9ZFBb zCAblH<7Iq=C5}7SQw2TP5Zho6?2j4vCQic-@H4fb%tv~Inos_ng#Lm32j~;*KTBVs zZ_p3vkQ2^&^Q&^aB6NAWHr<47L3hDEY#&08QRVziq35#yV|qFL6}^StNgt$tr*Epc z<^DeDth1CV?V}sht?6zUr^-5#>EUW#d7TXXt}4g*fc~6bO&`QlsvPGceOr~|{YElRytsJqXPNCDHtf!nR z$BCqy)9vYAH~>fB+c*oC;@9{c{)}hvDn7tmXPk8u$I9rzhS*juEdPI~)j}@UD{PO! zemGE-d6NDQ zO`MFgaWVdgr|>$uesk858;fB@48?}{3dZAL9FA||c$|VWa6T@^Rk#h$;AOmlckv-+ zJ?E@D7Z$)`SOzO%HGB?zSO*(nb8Lehu^YaEu{Z!za4-(X(Kr>~!?`#g7vpkVja%_M z+>1ZqF}#2`G0S=9{N%^yuoZU2I84VGI3HKy7W@%U;$^&#xh^=@TMFyo3)lk(;H&sH z&cV-d1AdRc;-C00=K9^a-hP;YV{is8#MQVH58-*dg<1b_j#~sPV_j^CFJU6SiW6`) z9>$ya5OZGSdaxYUz({O?T`&d*;Ygf;3-Bx4h6nI8Ud8_~&n0I)rLhKvV^i#aQJ93U z;RKwCi*OZg!~J*)uiyjB{im~@>KKWwusg=%Fr0w1@iY7y_uw(Sg!eG#U(WTG#OfG{ zt*|@B<1n0nv+*{@b~}P;7v0a5G-Q z+Zb}q`MQGG3}@iS_yz99JlDB>SO=S9XY7M1_&QF)Ik*;g;!k)6ui^vDb;G&-5?B>| z*aV|-G)~32_!;iQU+_HMK-W#@`to5JdVFwD(3#jIeu|9w>*!h>(ejMF?1q5 zj2=x-rDxNN=r8Gw^tbdu`Z)aueVzV~&VI*PUtv|&SC+0$d+COBE4m9EMGvGi=uz}U zdL})eUQVy0chLLjWAr)tZ~7jc?XI)l{Hi>kE=^aV-E>{L1>J$}MfaoA=n?b;`d#`X z`ZIbBy@mdPK1`pb|Dx~ES?)RO&8y1!E>2gXpQR(|rgS^HI~_+S)34EE>FM-bdNI9{ z-c0YJf2L2;m*|`HBRc25&iae0vi@>(4LXc&Ot+?AqNC|VdI&w5o=nfC7tmkQU(?^x z`|0EK1^PODpU!^YS#LpA9xr9-r)e);pKe8WqNC_|I)i?Lo=Cq(&!?Bt>*#ItKKdwq zj=n&>sq`7TLUp=;4~>F4PV^viTVdJsK=9!I}Re?WgmucEimd+5XTY5Fhv zHl5`^XT7=A((*W`E6~r<;dE2FE!~}tp_A!h^jLZ-J(pfYucSB9yXb@TN%{}^CjB3s z^P#i;!m6yl99^9bqZ`t#=`M6MJ&+zkkD@2jGwB8Na{6m}2fd#@Mqi-+rtj0)9y#kR zsLJD|H2pN~rt8x!=uUJmI-X9W-=HVZ@6jL8OX)TAHu?wpD1DZ`Lf@f7Tv`0<&8y1! zE=gCSYtfPP^K?7m!(2MC+^k#Yw{WE=0$I}dMZ7eUPOOMZ=}Da57Ni!Kj`c9e{^>F$1h!PVO1V4W$Eg) zmu^V6qPx&h^gud;9z{>2XVUZO<@7pw2fdFzMxUeqrti_&LY(#HS7rUB=_<6Fu1mL| zJJ7x8esmf=f}TLXOMgUvMz5i_&_B?J>9h1-^c^}&R%g9=RXN|q=}PpobR^xBZbx^g z0R{C^hx>>eUpAf=gj7;zo;tfFGts)!|29zYx*TRnogvL z(4*`yxDEvU-lr7Zn4?WOC}t>{j46dg}z&~MNa z>G$aQ^ip~qy^Y>SAEnRHSLl0mNOotv`BgdJCFv@3ExIoKJl%nQneImqqDRo<=y&N4 z=+Ed?^cH##eV9H?|3%-Xv*d8rn_HFhU7W5!KTC(xP3g9DcRGenriamE>8bQwdJ(;n z-bnAF57H;;Kj@qEe{{~A&iV_hvi@>(bvlf0NVlfD(9!fjdI&v=o=nfA7tqV;ujw81 ze)<@Ff&QDmPiM>Jthb;lkC)Q))3lqePq&~u(Y@$+I*lGlzfI4i=hI)%>*;Ul{qza? zclsv%ADt_=v)&@AobL*B4LX8uLbs#4(|zd_dIUX=oRjsBO; zp2t~lK~>iK6kUxDqZ`s~=&p1Ook+h*kD;g2bLl1YSM(No4}F9_Ltmlq&{^|3>&>Ui zdP~z)Xb)YFZbf&Zd(#8xA@nGE3O$QnM1M(dqQ9emrccs;(zoa=`JDCUR%N{<=!$eL zI+AWqx2Jp2{pfW1b$TNG9{mZujQ*P5K_8%hrT?I>(+}w!`JMF^RrTj1U6Za&H>KOs zJ?L0^5d9iGo_>e^i2jUTOK+w3(MRd?^i}#kovnbg-a@LZw+vmK_R@{$7wDJhXgY}= zN{^+d((~v~=~eV*`g{5ieU|=!5uK-yv)*E=Jf17j&(d}1W^@PoWx79|O20u*px>uIrkB&} z=$-VB^l|zEeS>~L=Pc~3x3DVfEl)o~htrMe7wK+v9Gy%Lr{ALAr9YrQr&rV4=pX1` z=-=qS>3j5(MV$2(P-VSk>8EKQ-GFXQccJ^x3G^^}G(C-;LocRR(%;a#>BIDC`ZE0w z9a7X;Z(dc_TZ*nsyXm@gOS&T+MaR>F>5=qgdM3S){({~}e@p*FpP(<%H)&TfXT7;p zS#NQ=0{t8vK|fEoqkGbQ=`?x-{Wd*=o=-2O*VEhS{q!;VclsLrADz9pv)&@A%!{Y! z8gv-lglXhyIy9L;p$Np|g~9)|*e2^_HNk(6#7#baT2B-HRST zr_-b8iS#V`6Z%W~Yx+C-0DY4FgT6&Sq;r>Y)>~AS$8$xxCLKvPrQ6dz=zjDd`gM9d z{T}@hy^LN<@1Xb5ztZRF>-2p(M`>rhg;ZH@Il4Msn{Gt6rC*|B=_L9!dMy18J&*p3 zUPW)Ezo(DVXX&f-T{>GCXTAAVS#KG-D($7~(=X7S>1cW&J(PZvo=VTAKc!dDo9SKj zA^H^k7k!(4qO7ytJgTg>BwdLPrR&fw=nnKNbbmU7euJJwzfUiqm(v^Qo%BKaIDL`6 zK|i8%KIN>pm@40Y<>_bXaJm`&BK~yXgjWOS%gkMJLdM>CyCLdJesiUP*7Hchf)7r|C=dKeYVAv;Xm%SC#b^rz_LX z(RJzP>5geZ zew7|WPp9Y7OX#oYE%YAx2z`dWLf@gYR(95#PnGqSrmN5%x*pw%?nL*d2hc<4QS=mg z7QKl6lHNprNB>Npr2nLE(OIfE>&>modP~q1=~{Fo-JEVu_oDmJ>GbRLMEX7Y6M7l_ zHNAsAK>terL0_jI(mAR+>n*Cv_g^`>Cf%IwME9Zx;1GNpXW}AUkKf_Xct#Bgapikb z{<~imdH;e!;u9{Hr?40zue*1NMdduIvOkpe(JkpVbZXVA0g74&L)E4`CG zL7$=JKNI`c*-DO8Tvf^fOg3_((A9R z%K52AH=|q9z3EtbJUxkCNH3vx(!1&N^hG+W+$VZ{IaIm+GIV*m8QqfZN%yAH>7n#I z`eS-0y_>#BU#9b9b*{gFD%T%M`&3zDOS+9JU!xy-IZ3~HumG0F%2)$yVFPS}t*|Zj z#NL>K={Oq4;Z%GV7vN(20>8p-_$}_kgLoF@WySv6CohNedky73Q~Nta&Vil>`Db9i z^3P~~<>`W78Ml5tSQ{H)6YPLpuop&S3Z|p~@h+bS9`DoGJ_G0CNB9MPh2P+IJc7UC z@AxM^M13si?Jb6-@HzBg9c+Nj@dfOGuV5k$!eKZ91K(HE=$UFhmuoKl5q^rF<4RnE z{_jIsf8hJ@7q*{3|M#Wr4}4$VW%~on&G$=wEP?*-SNXacbSn+O7W-ogrsHrNiPLZfF2KdO7B}Dy+=WN*S3HXs@D|?1?Ae^#pBsx{349uBU|np8 z?Xfe)Vt*WlBXBHEz}ff#F2fc0HEzbecmR*$ar_gn;%&T#Ie7k%2a94!tcEqwi{aP? z+haHEiLuxphvIOYh*R->oP(d?a$JiWa1ZXo6L4;SHQxE?p*PTYB%s3maln?1)`43S%%82jd7Fh0|~bet`3F1+K=8xCIa4FL(ye<1M_4k1!;sa~=v| zF|2~su?{xC7qKID$6lC#DfkAC#u+#Zm*EQBiM#PA9>>dg4e#Ou%$m!&T{*BMmc`0g z4a2c6Hp778qUB4xER;s2Hb=D@Q^D1J4;`{TX+{AsRiYE zocxZaKi~3WaV(7$u`1R=FE+vE*cLlrH|&Wq*bkF16-VJ%oPzJ*0$hw=;8(Z}zs0?H z08isN{1dO@LwrJ>;OlwGiFvUImcXa6270hI*2l)!5xe3m*azb=5z}!fj>C!g4!(~c z;Cx(y%WxI0!|(8WJc7UCCA@+UQU4~|e||787Qqr&0jr=7Bd{%Yz;4(RW3fLbV;YXe zaX1Cv!P)o$F2p7HC9cBl_#Ga`V|WoS<9&RD+2uL9o|oKM7>namSP`GW=P(Q-u`xc6 zZLmFd!=5-0lks(Y6DQzgd=F>i$G8wz<9ghMKi~;GgV*pD=F0D!k9=4ZOX73r!6w)o zyJ8Pa!E}5L-@q9-3zy(BT#f5-H}1vbcp5L_WxS7%@Jaax0KLC+VL7aXHLwtSnbhh4D;#$zImz)?6I-@`@t8GenMaUUMU-|%<5iZ}3Ie2Dq<-yP-l z7s8TQ7HeWChGSiP0bj%}*d6<00;b^*d<);kckq4u6hFs}xCM9N4|p6;<5j$YS@hpm z<@RR7JXiqBVI_P9pTqjt7+=5_u@^>TJSJiW4#T%`3Vwj|aS1NNRk#lK;66Nrzu-l@ zj5qNPK16*F4LvV8F)tRwQdj}2;B)A~NUV>|uqC#`PS^uq!9*N{Lvc8c#&I|W-@*B~ z2$$gsT!$NRJAQ{h;!k)CPvT{~hIjBj=9YgW*7KMji(_eg2A{()jKr4M20P(P_zL#H z0hoj%a1@TmN%$_##82^aT#0LN6K=(y@Cg2nf1<0HbNjPmZp@FBu^L8TJ#2&Ru`dq5 zL70JW;}rZ5KfzVF4!^|Rm#*Ww(<1ijmFdg5*w{beYhYN8DuE5o}6L;f&{24FcCA^CdFhu?vwmy!t zV=*j+6|f5WFajH5Q|yRcu@^?;Ak4rKI0~oX44jJ};YwVCn{gZN!F_lV&*C+_g&}3Q z{g@96VFj#$H8B($VpDtpU&LM*jq#X>!*L{z!-+TtKg3V*b6kmQa3}7@19%9}<3+rK z_c2#l=X~VDqF55EVNLX6I5xm0*b3WXPwb8TF#*$YC{Do1I0I+lN4Nmj;McencjC`@ z6o13t@jBkdtWP=TBL^11BG?RDVh8MkeQ^M$<4}AXr{McI2S3Lza2;;My?6jm<2n2j zucE7*b9=I4Zp@DrunN}1P;7`zu{E~CSFjHb#AJLO-^A(o9xlWsxDGescKi;1!4r56 z|G<0rA7(Aj{fQ;9ELO#5FcRxyOKgKLV-)tq0XPgt;20c_vv3|R#3lG8uELGD1%Je! z@ED%Nzwsviix06t1?PMe!O~a`pFuY6R+ZJyoWg|I=4R$7Qqr&4QpauY>3VA1?-N!Fc$k`GN$31_!dsa={O7L z;Zpn(*WpI|0r%r6{0%SR6?}lMO3r!6jrp+{mcj~H1$`KSEwD9q!j~`#V=xVe;OqD% zPRI9f9)65p;ws#L-{3wxh`-(o@dfOFT`(5= zV=|`UoA?$^#_9MmF2tqyC9cH{xDCI>y?6kR;&J>9f5$6$9q-};45{Lruk4r)3t>qt zie{HnD5FW?V z_y_)lH}D^Ph)+~?&TB5rhsCfIR>x;C3?s2IK96m&19rz=n23XLC=SQbI1Z=aJ2)FZ zz=gO3zrwY+8MonX+>1x>S3HXs@G@S*C!TiB+ml!nOJX&wiCzrH2G|5!VO#8py)g}k z;6$8?3vmg4iK}oseuqc!SNseA#yfZ)L#pxphb6EKR>G&THrBz$_&j#TZWx6zn1(}e zB#yy%aVCCf!0jS*N6n_>%m z5j$dc?1c%Kg0JH1I0fIqPw-P*iyLqoev60j7rcm<@jgDn{LeV&r!ZE;s#qKAU@L5k zy)YV6Fdc{ENF0xoa2|e)i*YG#z;Ezd+=IX13A})p@Gd^UkQ#hHU@BO*2AXQ0=r@l9Eiy{3diCUdDsV3`gJ?9FH?`E-t{uxDGescKi+xt53LG$M7s(z}t8a^$%$D z@>#Jk7RRTsBDygQ>#6x%u2yP@%heXUV0V1dCHv*Ssd_QcHT1s^%Jx7P(EVBX`yN@B z{IkRV`F9&RxLh9d^73_M=<+DPX84aM%kb;N2&{)Ku?@Dz&e$7cu|Fo@P#lgUaSTqw z88{2);m5cTSKw+~kDG8e?!^Om2+!boyoi_aEtQ2ohV8L4cEg_7 z9}_SI({U&c$B{S&r{N5oh4XL;F2fbL8rS0{+>Lwj03O0KnECHuF0=hEK0ueuD*xjh z3t$n<{P!`{*j^Ju(T9!D|MzZk|FxvsU^n#t{hRFXO~+z?Ou(Ty97p09oQ5-S7S6*Z zxC~d|YTSxDaX0S8Uoi0ZHD~DacnxpiU3`E!vO4G2|Mz+Nc&3YBd8~}puqH-eJd!jy)pCO%1hx;w;W!e<;53|p zvv3|R!DYAtSL0UPiMw$x{(>j)44%hpcnk011JoxZ{`r6fun3mGGFTofV<`GC0_$N* zY=iBwGxo;Je`l1y_7qIVkvIm&<0PDg^YCL_h%0b4uE$Nd8~5S?JcMWPJYG~~)?UVI zs?3I4C{H{7zaRP@%H~IiOTN(f2yw}sWPF6UvK!@+OXtYcxiWR`Or1AV%M)7TBg9p} zC_TQsXwvuyamf={<0HiXSL(qHA^PGk<0HiX*XzLzAuf4wh4B&Mk{25oA0hr{wZRP` zF8Pnm#z%<$M_S_}#8ts4U2mmKT_sb?KL#2fA^MME#z%-t{!zgA2yw|TgT_aQOMZDW zK0;jb%Z2d~BEMvq_h?qv^+$P({Vv&?pKc^RAua#;+4#uezeSB?OE>vnVE_2Xm&oGM zE&mH#UY`RyAI|0VIdGs`$tT)F<$r<8_k6r)=kofu%+5y^S9keD zyQdhqygny%KAg+zbHhNV$S2zV=j+_Qk@Ec!*zaGz(QnBPeaj_2czS)>&WH2(%=&n2IQ#1v-CVw2 zdx?BOU_FP7{d&CfMt7CVYx|%7b3V5QzA3nV{Tl}7Ba16WF0cKIYzQ1*{{|qiUyrYU z3lM01tZMszpXK=a8vnq4y?ha)Uzf{kcjor%m^>sf8= z*W>RtTL0c(d#7>vgvVo&`^)Ih zKQQ*|`m&bb%jNu>mCI{)lgD`A_S`KK+^?6{*Csh1@_3cYYxkE8fy?V_i30oWd6wP( zc+%Gx1@;$^?``e&vLW#Gc^-d}b9?kPM1jlKkjrcPpNDgQ=6U>Mz`1-iqxDO7R|tN+ z|Mpf4c7z-+tF-@lDaRXMHMn0df5_-oa(Qi?k%9G=uV!C9)aXufd2RpiyBxo={F}S; z;jFi&(J^v)ZU67fTs~_}`|^R(pKwWXdHuL1|9e8(e|!B~^#3^hI9<8@=RerlTtoSK z=lo~$e|^N`3po8aUHM#Z>g|yYGh~ff7MerybRUfSEVzI{r^dimey}Ey}bTxm?fX< z$j~k=y;wdET>mrD8>Iu+A1VEVbl~gt_t!Jh@-5*1`j@2d%IATv?<<{0?)$*kXGoWk z){&;yr@yCGmkzA|UFmRXedeY6Kap-?^h)Wr(t+#WD&0p~pIPbU_e*C;>xj}mCHwAg>Ztp1R`o{ig(k+bsNV@h2Lji3Pan) z`g>xk^po^I()tl8|H~prDI{}CKi3hU?UC*#pFd4ElYT=!ckbUpt{&1erE9Z)p!7cZ zTt}pSz5f1oUOq2R>+f$_<@`A3zmRL8bO~vl6MFfz(v_w4nW47+Ue-~10BwK26my-F z{raIdL%*N?me$Xm;}>&<$PLxC2D+5AjsrOb{>xX8zAH~to%2=9dF~+>2y`3SpTp?h z(glnjEM3Crx1@K<_x5g%ukYV5NsgaD+v_jl`b75YhqJySF8#epKM%D2-lVt3S#N2V z{@zs0*ndvCp3&E(^}{(Ir8CW!(ylukPcM^2eqYe_==Y-YQNb0W4-`K1`F0`cO>+J# z$u_+|s!E@hmYd}7FzH;fxIj0P4l}xwbZ?{kNKZ6+kn~!kM@pYHdaAU}q`>h%lnys~ zxpW_+^?e}pJ!1lw|3P}a(Z5QcGy0NrJ~>%|%ioobG&;LH5MqrkCOy^YD$@F1D}k@~ zN$Y#51iGno0eMUYTHg;s-yhtc|e5QXGE4IFQobbX`s z{UG`q{k`8J7pzkauLE2ED}>w6Fcj{m##M@HY4 z*7ptw?9VF4zHM}2>GJZ!J+NQjPolNaZt1~BHjR zbX%h*N)I)9j`RYfKa>8^==IX~jNT<(S)L5l;P^+R+Zla9`cKbT8?jj82f&zr_w5?=|Ua@?;~>Z%cPFdbafI zM(g`U=-);MF0bzsamZ+WzlcXhAC`Vbo_qu@e_mSuW;xI|rAHdA?;Eky=z`KmjMm3W z7J0H2`1)GXHH~f{{gTo8{t<5)t?wJL+~|SQ`nS7*1L>rx7dXmvkNv|{dS?S-5t|y&We%T2e zzqNFP(LJQ~Zv+GT-BvmE*kxUbYc1T zh`|2t(hZF6FRgz&7T7;TdWO+&NpCUwJ?TG)lqbfol$Mz@sSWAsbXw~X#9U9MvA_!-jrHz|ShF-AJW=y#<* zHu@83{o9eiO) zzrMQki$+IC4>P)jwEoRQ;QG2s?>9P5`d_2drK?m4UVgN6d!yfxe$8loUy4tSULk$Z z=q=I@jQ&yj>8iowpOo%sw7xIJ2&3;y>ucZx>(3=Wt9~}Rr1V3ht4UXXI(YeT>CQ$s zmwvm<=rn2lg*9;fZ%WrNdb)I1qd%4&WwidRU1sz*(npQnC;deA;PFpL z>uak6*Y}rnH>3ZR9&L0^`Puq~(Iuph8U3_$)@Oppt1Vs2=;x(-7~NTVtkE&jD~wK+ zK5n$Wuf&tG*uZ+HNxO~yNV=!dUr6g~djpr>Ed7E1^7k)CL@zW>Bpqen`gHF~Oa zp67zc)AyqYH+s2rAEP%(Pd54o>GekcDt*rAOVasj1&@DMI@0Lu^4ulX=wi}SjjkfS z!DxN1q_3F_-2SH01ww<}QM#_t(b9d5PLZB&^c&KfjGiL>htc{z6ouTuc<0nbCFnWY^s?qvB z7atfsS9-V6pG)5~TA%Aa6&^hPZs}G=AC*ow`giG%jJ_@Xz0q0ax$JGD3rm-e2p+$p zbZevaeJ%zY-AH=A(e0%78vTm&9itPaD@F#7KU})4(G#VI8a+pPfzh8y|7i4j>3c@+ zlCE4Qc>E*M?TpsBUC( zlK#o)1nK{beoeYsz2NcRmhNQqZ0XmHULyUO(d(oS8U3B~Bcl&XKT|(={PWUXjJ_#7 z(I$nXC~7nD9?bb0A44T8t3C0)~K{axiHquWZqX>?ENA85r9&D9k3T{B zIiqJucQ<;m^cbVpN`Gnex6;2Ft?z%4tx@p!=cGf8z9Idx(OJsM@Bc;@kX~tYIq4Hd zKPR2Naq#%{r9DQsk?v*m%hKbG9w5ES=wZ^Qj2HbB&5b@FJ;>Ny2-;D|{29K}rx6#IEecz2C zMqiQs#OMdo`;5+AQGWk7x|DRKcERIUmwwUc2Ar8^pZPI`pV*QJ*j{Yd&}qw`jh z-~Wv+EnU51@c7lGI~yG?{f5!cOMh;(z7NM?qobu=or1?pmabv+20?IctSrC(cL^T9xO6R}t4Q}S zTHlvrtkI37R~X$+`nb`(q@U~>JpMpwx6%44TV zg7gNXZ%SVHU!!YCPd7SJdXv#Dr2jCwi*%u$!Q;nB*Ef2Q zbbq7Ykbc+b$8jFU@@=iJ2a%^I#z%=voq2y@|9*Wv ziStp&^}QS~@KHcMIi9J1%hdXQ8-WkK{C}A`@6&<3&g)vL&^_fk3(6~j^nEu1ANut# zWa{pjIw@1XmZ|mqHUb}dyjgU6`Mi)Tn`?2V{W~-D51IO4raqpjFVNTg#}9E`&$K^B zwZLke+h0mLR5t1B4GYTaquiPHH_6nUGIe~W9-65~X6h-KdVZ$X_uUA5==u5~Q=iDx zS2Oj!Or5iO;Aqb6Es?1!XX+Z6x_+i^lc~FA>ex)J@3Rs3(A%T$uMzmro|CDUWa>4U zdV8imn5p%BHv%7e{C_ibcDbJeAG*JIrVhSV);V8IGwtt~sbezrkW8)r)*blJ>zkXY zmu2cTnR-j6{wY(t`liRmN2SFlKNsVw9R0YWQc{!q#JMWRI$OGQY7*6@RmaXzX>sWp zDbBW*&qsA`)v>YL+%_ORx*uQaKW<|B(B#xUQT?N12AUUpv01CA*to&*F>&TrS%iFT z{NSk6xP-Xqv^eK#()*_-r>7@SLsH|@M{is>Jn znidtGB$w>lH!juL*e5kETD~kj!Q~t!Av!%SDP~wydVFHwBF>J~OVTp>B*v%9 zf}&%iGE)0E8~ycvEFmN5@me!dV&&jbi81M^3C6HIUolj#D zk^{Hfe>Rd+^~w{I2gkY6(vwr;qU<$0+u{btC8bB{O?IXAPacx#GJ*RyDn$?G+^zm? z94ia#U>m;P|v;&Xnxx^S`^~8j||SJ(dy|$HPKyLR5NOYGQmcH!L|N zF3F`^)8bO&qZ8yF=$q`^GP%Wa;{8_~pA^q6j~gnV#mn_a_eqG0ib+oF6Q3lx;1VhTB=&XI*bZ zn4O+Ta~YB0_L05e)?QD9nc<;cGiyg!hpO$ZZSD<=ur3@HZk?R4Nb4qq$*J?-8!`Rk zQ=*ch6XVQ7`64qND#9fXkiMzWF>;^y+}3&Z`D&XxJ=V^MNNb6;?Nbw(>BdJ`H$E~_ zGbK7z9;RvX?UN*f%6|Ntd*zWGn-P<4eT95u#L8pZyjW~ppNxL8B{4bne-G#h^XXOo zpZn5>rNqg8y|;8fS0`Kav>IEuoIV6}tFr{Tn4Zw!1}>!!1>NXhm0U>gvB&LP#;bR^ zZcC7HnUp4L@Sim2QfV=%@hLJ*l4Pr%Xx$o}k={Q!RW^jV{`ZW@)QyTxmy>A>jmO*U zlgr8TKS<0uJ}4tTm7)9iM}V>I@sA2)n=$W=t^OYtM(f0LekwSR%vkwZAcHw@@BQzM z3G4~n^#KFhGu{2pT_1P=42&BlkL9q)aOcYOC!m}?`6=j}#kABIxpLW>6juB3nN5g~ zP7A9YxND=G4BWA#KK%W6gR?hq53@IL2Rj)SxNph8gO3b6)<}C9VS&dTd+k+)*{kwT z!r-dH>{ZEo#+YmN*{gc|E#X|z~{Ue)982KL&kdi+hmUi)16>{UJfW^gY2`1^pg z&(-7a3HI8nl5Yj`272vPdF^xMwO8e}SLL8)@Hz9(z?DdsQBLRUUg) z{;_Ht*`F~0pd+mGB{}jU5Ypu!`X|2lV|C#gn!af-f#!c|~f0`M4 zt#jpzv{vQ(3^gunt;!c^ohx6Yy(<3?`rz04e=r(puPVYiSI%=4gy?fS&deDK?|-RFPO8(ft=+kHO!T-meTXU}$@J==X=`&`+x z-4}eKqd#GN_H6grv)yOUcAq`lefDhk*|Xhe&vu_Z+kGDU9<*n>&z|i*d$#-R+3vGv zyU$}kuI$h;>r(LUwr9J~p6xz+w)^ba z?z3mR&z|i*d$#-R+3pLqA6NEl_k~*DgI;^Kd+piowP(B6p6y=$uS<__uh*XKUjOe$ z#$IbxUVFBC?b+_NXS>&)?cNCMapkpVyVw7VXYhI>ta;_NXS+ATUX?xDy%F}gvS+*3 zp6y&)?OuDfd+q1#UVFBC z?b+_NXS>&)?OuDfd+piowP(B6p6y&)?OuDfd+piowP(B6p6y&)?OuDfd+piowP(B6p6y&)?OuDfd+piowP(B6p6yIq?H+r!d+gcnv1hv{(wd?kd$xP*+3vAtyT_jG9(%TX?Ah+IXS>Iq?H+r! zd+gcnv1hx-p6wocwtMW^?y+aP$DZvTd$xP*+3vAtyT_jG9(%TX?Ah+IXS>Iq?H+r! zd+gcnv1hx-p6wocwtMW^?y+aP$DZvTd$xP*+3vAtyT_jG9(%USzvr3HpXFcV?6e-DW6ySvJ=;C@Z1>o+-DA&ok3HKx z_H6gqv)yCQcKPoS)~T~+yT_jG9(%TX?Ah+IXS>Iq?H+r!d+gcnv1hx-p6wocwtMW^ z?y+aP$DZvTd$xP*+3vAtyT_jG9(%TX?Ah+IXS>Iq?H+r!d+gcnv1hx-p6wocwtMW^ z?y+aP$DZvTd$xP*+3vPyyW5`aZhN-Ne^;?QVOv zyY1QTwr9KBp6zaXw!7`w?zU&U+n()id$zmn+3vPyyW5`aZhN-7?b+_OXS>^;?QVOv zyY1QTwr9KBp6zaXw!7`w?zU&U+n()id$zmn+3vPyyW5`aZhN-7?b+_OXS>^;?QVOv zyY1QTwr9KBp6zaXw!7`;?QVOvyY1QTwr9KBp6zaXw!7`w?zU&U+n()id$zmn+3vPy zyW5`aZhN-7?b+_OXS>^;?QVOvyY1QTwr9KBp6zaXw!7`w?zU&U+n()id$zmn+3vPy zyW5`aZhN-7?b+_OXS>^;?QVOvyY1QTwr9KBp6zaXw!7`w?zU&U+n()id$zmn+3vPy zyW5`aZhN-7?b+_OXS>^;?QVOvyY1QTwr9KBp6&K%wB+XLF3&-Qq>r?Wkr?b&RPW_vQ*gV~k}m}6-$oszk*AvZ)#keKlGIk@|v-z*wn%DdaY>xMS10t|J71y$$it~lhWm?()-7! z>3`Oj1xQ85MfZu1%19a#pA;JvlaeB@1_|Z*^>BTXlM`I&>BFM>Cdg}RoR^?QrO2xM z8waMw^_5EZUt4NizxXtH36(6t|6&LKPJJ0$jJyOcDI+Ctow{sRCa=PZmD7+mEG>1A z^Qy1JxJ1371NC;f{73M=#40LkNc2Ftp(!rSz>#!a@$xznc`=xOd2*KGllr;zR5)wU z*V^b7=Rf`E6+17=a9*Wl+)PgMK)HH(F`l2saMv~k!1EU7Ur6$EC=qmI@fidzDJ9+tB-*~ye|Gi#Wdvrg23^;d1yu3Qe zl_EDkF-2Z`CQI?(QPHvbIvrw9yc^fuhG9ASzCH)aza#MT0i6Ax{;TV2EJz=M&dQy$<^R%w@d*k32XR__Vv0T<(o@ruGZN&! zmWNYnhP*0BUsIQs5Eqvcl`JpH%jlE&TsYqpY4NYdrTOoEecfK*J3-I7yf`vBR$grR z_~r)Aw)Mc*|5z21oFXryOqOpvdA*MDP?Zf@}zf@ZwrlQq~)(cjY-}CG}=j4F4=KH?C&->TQ z$CES9UTd$t_S$Q&z4o4&<9XBP%+PgRi~rNLVyz!(+ByG_$f}YI#ag8n!&PIi-7xN5 zyZbk`7T(ksayRwau}yutd%;daTe|b>0|!v6XBX&u4&}AM8%pBUwT9iv{FJ*>>y~Ai z+KxW7zMFD7P@X$wQ{PT)ous`VySYz`UEQZ?3wpK2o?WJk~uw{p|r5dHM`qE19T}!*nqg^hN zcG;9{mj-2*ZpiG0yl!cimz7-_5AM6BZSGr7d!dds!2TB`we{b0ul04G4t=RRKga)H z*1hHbBi%>&y6>F}Ki$^7JG$ej-LzRc#)xC(RwVglld^xbMWT6{iCz;!1+*W$AkpPTUc z*OYPZYE3=6+8X*}UTyi!eN~O{lX%?gQ2te*-`rP_iBDd?e=XP6^xDwV(6m3b;Tm=t zhB^A4foqhdam*@YKeYFDCfSqocqjT`AqMRT-`uyuRrXW;xukC_WNhoEk8er%>jU7w z4ZOD{comJZwt_}k>p)-U(`jdpy|guK``>Im2r`PbYx|b_@w=Gw1Y_IbUfowky)niI z*&OyZ;gdG~Y|3x;MB!)h`uu}!PTRkPPXG&yhtIM2{A(uHp7Rl(dv@uKJ-ZCppJNKJ-g#P;*Dq7WP(yt{pPJwT|mxuSLBn4Ly1u=$yATU&EiY zg}dOJ*K=J$9ML&<8Bapmb$ur0uOa7e6Xx$i#2D@RAo|NWY;HPLuCuAU25(yUVu>*? z`%*VuxHGirlD-s-75Po@upg8W^5?FJxf`OLl48xb%~_a8&OJ-(+4U&&r9bb#MA`C( zuo+`{6FvuEJL=um2!HLqXtxbMwz;+vKHGu$5%<|9>Z_%-1a9tYiQtn@pY_)y*k=~_ zJ=(zMC+{@yro?)7Re`?>{FEDxT?2bA=*o;xgL!Z;){nL6j_Vpm< z?{T3IY<-6>m+>Yg{Q5h3$0fVB_+@F@A{lQs_*m;Wcn!$xex+}9?5W<&*zfyN1~@J{ z;+3skyc_cgd4!6Ark@LFO^v&kLDxpiH|o9=*QS=;TaUiz9X%1+%>@qN8bdiO+>yQ8 z!1WVJ{!aVvM0}zBA3%(G4KapxX$)`f3u27*@cAq-@X9y=od(68?Q_D<_U-Z4 zHLN{pA6mnAEdq2XNH+yJ^Bvv$lW2t1+@Jh+ZYtyxZ80z z?$-VOaUN;iJ&`fc`3?9E`v!Zbz3KZzN_S6YK4`3)hB0YGe5THrcT%2(GTVLQ9hPz4 z4F#_qd*hu!9ncwie?w>JrN?!qjvbFmot^)pvjd$6CF#s{hvN{yn)B9y0~4tm+mC<8 z{h8~ThJJ9Kxv(RBvpBX+>K|WwinYy2@ldTjjEC8NJgh}rqU;0yJe`jD$$7dGpL;OS zf5K-kKF47pNM3g?2fhS69=@5!e2yH4bDBD|HEoi1uHUw)uW{2RtV5ePK56^m8~foG z`{mm6ifor_&rbMI^7?}~{*Cn~g8EoX6Z3Bc@I#Qt_2Lf5yaO^rN%=y2o;HGSJ?L^> z0nd8WVSkVCW$o;~cz0umKVRYN2hG=xjeU*KZI6p}guda|<$SfmZ@i;7UbMTxFH1qL z!~CGi$B8))pUxB*8`wOnT$FAD-X`YU?b>6PjSWm=;ee^E{pFp^*pmZ}37MD^CiW>9;#1Li?ZXc_*XffM`le|cr4M97r);dl z*;t3k%ej*azlr(#4jY3@|Gy8Pz09jnpL2*dv2 z#)0n*x$k70(GcU9hx`_K2-`N$c5d^gzCbs1xLC$cP3APP0eF-5sfb}|hx&r4MSH`s zmj@fr3px!pe60JJ@mu`aKg^Li zrn%*e5%V!-SIgM29pkbcX5shK`68z0@miX3t5N#YV7I7M0+oa96Ww5qjfayCclQf zvlsJ?xh(k^JI$txcRM(H2_SZUgxI;ypMzU`-54LZcc!g2(^fs02i@1at#3lUy^Zr) z$$Dxqazom%qi0u%wo%TLhpPK+#29+Fb#vd{;Jdq!{`I=ld6ss4UwYV|*I3(6(zUc% zvFrPGgza9t>FU09kYQq;Nne7ExGu%p+~fYJuZeA-eiLMqXOQ;mJ+m6F?=!a}57F-4 zL(K0K?FM`{?3tls{nD`C!T99)W3FM0>6a<~n8*F{MBwi5`Iw&@`zGPq_I-0_Re!%U zm+fe2diW*Ce5vnElls7CfK7Y{@NMJU#CHha7QVyy4&pnC@2yd#cg!8K+jTc0uhP=O z@bw_p8ie6A7uPn{9OQF>VC;#$mZY|6(+;$^7%~TowF3uO2d&zu9JFYh!XBxcTggT6y zsaIaOll;p!<@6P7Qgt{^^pk?{jk2AB#v75B9k&a0pGV)`(>GnZI|s6MA2=}V$kbzc zadz=W6#F3qYsQhs;hYX*y#@OP`evZ9=f}%&9iMaTOE>lz?8{>8GZy>%jOkUJ15aT7 zJ<&J47Cwsa!up0Ut@GML}bp zg!bP{F6aE(k9|V&UPP}SvO6E;MrcUy-N?`MydeD-^H8>%7JzIksom|y&4XRgb7`AH zXxOI=My`=I7_@kO^AMi(;9=j8yGy;3Wp{vv+$Ie%^gRo<$b~*}TT=Ih&^>mwYY4~5Bl*wIuM`6{lGNvP6IFNvrmaU4Q(8nCuVkh zcTPxuRrbXhWC!y+bylBz-V(yvZ*u*|M@R1NQm;eqPh@s~cUv&2Y^xi2q1`cRC(MjI zVrZ|!xD<-YJ%Is?pfRigJf!Quj9V`7D+dmwbpyYIZ_wVG244a%Vg%0_@a^X)v=#RP zjF-vxDsoY_-#=?R27|z{{vHH%;#z|dHsbrMuMQlLc@xGio>SbG?9Z?>}ze4*kBs{bU|kjJB8`a;)O#y<7bJX)V4x{QL<$ z(Wc|WzAZ=Jeuh3Vx7V9`cGWVc!5Hssy!LG!{fqCvn&4}3+iBgZfAqCR_*$d%HPyc; z&Q&?zxF)DG|7-eUVU@3J!Ja}x{u{^05#PgHMa-v9_4IyE#wW&CRkjG2XC>?(b2KxI z92sX4H=%q-lD$da0b4(T{y*XOpKa}c91Z7MJpYc{fw>>Lo7h)s9UBpAFy~Pp=P2*3 zJw$Fd%G)5f&6m6O5V^FgoEzAG;$B$*YrMWNw$6gj^|#Te+Tghc&)QwI!8(jJZTOyn zJxMKNj_-Hz7_$ar^Bl(ppF%kJk@(2{AI3-1uIyv3jxoZ16EUulb6c%VHsS@=LYb?d z;OB7cC-Zi*X(R5Xo!=X3P&rA1-`^nC6pky`L=Ah#?Jnob#=Zjdo%x>`Lwth%ltUTR zpXUk8-{X4IpDu!q`;Z^g_Dx(<8|W*3z6u*%DdlhO3pKw8KS8{1!Wja}29>|q*8smU zfH^)m(e8ym1{iw|#AfW)n!0uenr`12K4hIXu}%lkS1rr8=_Xuv_w$YkApm7>L2WAUyRu-~AM zb3Uvy?cNJfhjW2rX_{K^)%)QyN%XTpkK+picJG-0UKCGF<_LOz@2lF9Tle3tN#nl~e2|}NC*XtgXKgh;+qT`=y#dPn)V{BK z78K;S3CG*^Gqbw|ljH8deci7?k9+YQMWDTR(0$!+BRT(B%6;8caOQ144R$}m?`?N? z*CN5@w+X|rJcLckwmU7HFthxQ?(O)#3-TMXfPYrdy&g(X{xsakp&rrU_`W-%`w=AJ z+wQiyn?|4=@Iy^mKmOg(R#6$NJbCqs_N6ONX>l__d-gS<`mf$xEBt+LkmgJ?$V;9CWrew?Oc>uyw5IT7Gg% z^XledyAIliOCTYVC@%E`eAyyt*x3(AnD7+T7KO_>0c+9%l*0 zW--QP8ywBXBG!Ze7KXjI!-g*G)Lp1)4YgoIh3*c&61-b`3>DX5AP=pC3fq4_PUeoj z-KgE_*3OkH+7o)gvi&+OZEJ@{K686V>ng3Kb;+7jaGulLxpI=co;ZyqZtJS%C2g%O zZhNP@svYA3`s%YfT78}+?d@$^+lr;FtGZez&1{?lFvD9sx z!@+frSuoXI-R^d^cCKh{bDLY5J61z#OXrF+FtS~pOYzmkdef&*onAemdPZ!@jOpX2 z*VIfqymm%SET%QLt!VC=w5Dsx#52mvr%daJ#bV_xV_KGuY3ahJW6X-BV^-j5MaP(A z)>w7b;T^H6%9;VNR!yz#h*eh%L~7-XSVv`bMb&ppt*)%8=%4|AL=Zq1lFWdN)- zQ>MTI6$4-`FP|~Kqhf%@s-4j>p{61>00pXJ(6yp^Aa<>(ET;kkvB31|>W=dA*wg_i zP*q;pQBgi1AE=oymBt!?u4uZtW6I$*1F=9&?bMF)ipl}_K&+;!dZ7MVHKn?vYGAsS z&yZ59zuQ>w0m(W5UE{0+7_B(#KqgGp^xBTv0XZS0*1)r-&G_zajW4gA0M8m<``xTD zIw2K+|yg)G1J)b|6y8 zT0St=>haS%s$;PMxJ%4u9e}$a6xR&cSk(h&t(uC-Jta1M0Cx3R2cqlv8b}=s5zbBjA={!wStxLSS9OT-Y)?O;f2uR~b@*G9|Z6r8K2WlX%CuovmGK+E%-h+`_eK2N62jJ6F4fEe98N zwys{&xvHzb91Y4w$GL5-t4>+HoPt_PT;_+k)Cx;0*1Fhn)>lHie%@uxE0{NRty!{i z#p=~7R-NL?ywqLOxunEx?d(MAb7;#Txn0ZGDDIZ_GgrB1u0V5LtD9G^p$dm6Iu}M< z*4BQey8?{Nh!5_^s`gdiZ|!XNn`NHsOM*R?wj$|j@kM^C-n7}kHTMl!0v+8YXRU7S zI#?CiG1&`gyMu|c?usr~=A^J|>)I7GSLwlAOPkl6vV65WZhGVVxeMo($T3amw|aRi z?TQ-T-4|y4|8)>#!plT;dGo54wpN$I<#_!k)mE=Q>*Qr^&8K`z-{NDCWPtx_e0cK7 z%I+t#itj_x3w$R&)CtaLZd=ppdn7y;&{v~<*)pwt)j{q~zosL~EebsKU<)gs2%pkOJ93un(g{HWQBrp#WLTo3y~gt-omwlwlL zD~~%QtiiVralWKr6Q7`H;$XM=W<-s%{-=PNBo&)?IQSZ@EB_@>{3rfzk$>DhfwF^2;eq+4*ge!vgBf(HT`e@#m}k! zxAp#S@ef32_VfSkKb)Xw0qyKyApc-VEc-PN|C0W(tP1Bc$^Te(%bm$3N?y;mlw}?= z4y>E?EoG_SDEqY;z<4MB3uwPKoo|#avTQe*i@MDGma``8S-M zCI1U(drZAMxrBV5W*+J)EaTWG|6|!9LoVwcq6*4>VvcG^uE{p0r+l-G%TvDTFAs)0 z?mo2c4Jo4zE`q#>splPBi2JloI?h;={{^)2lz^LDLR~VfMc=T?6_$J5p?sfZ>ffk) zXUdp^*&y#8>tUSzCjSd)oeRD>XZ8jP@W6lazkv3TnRkc*1KJ#`<`6@pjc<%mvYc$)Mr3iLTF%=y<5v%F|{?%0LW~XEsVwico@c>mgde znV4QD%ToQCxB-!daywq0K3E?WqL`2+D`iCV^mGzg=42!!)FKiNs+KI_!P=-08_48^ zre%T4mq)HhL=QOqGNKX4s0Z8Np-Ga5WJpm%`y0Rw6_!y#4s}wU8zzNWafOBtrR)UE zl`x_1hy=4m?S(JgQc_3yYWmRar>3W8q=(Yka-Pp4P39#!BE{uLU|uSsX$9<)1ekY) zX1u?Wt*98ZT--Ptl_;0CEcV-j=>GOb%dvxyF=)%~H`-X=R#IX~zv6frv|nvaEAQ=puMnd4I+JCM(#ard1}ofc{hg*c_v3Q;m@nI6k41gf-}x&5qTUqQf)< z2g#M4n_wke08f+yB>b+fDv46xUsKhak&Dxh!^qCDv~pQ~RDZ|Fc67h;gmWomcBCp~zzrKIf>WO&sMow?nJk!}jxdph zo-L@Nc+^>##DXC`CP^t!kEIs5C|@MiLCNC&zV-M2xO6m%*JY(pTzs!z3T}GFRm?^B zInlSU#Wm$5@@v}3$!cp_Q@@S-TWC%LE9)#tVuoHzsh6g;q-&~Qt);#d)xa!c3)KIV zS1!Iw1dKRmM(*Jf0PcyqqG^1(pEf52UV0#NsiKXf0Ry5j?!t#Q8~Rok}zh4R8&Ub zP7b?{S}+F1qi?uBddaZO7?7pnH`1VZG@})x@c=eBQ7-2=LUwYPADU=SdMJXooPL-D zGK5Pi1GS_M>yJdF4v#N7xoXit;8xL;?Th3%HZmbc>JSgw2L;i*{^i1p$J6}yT2hd_ z>J;{OLDPzohm!s&WVbEEcg@CA1X`MSOO~XpI1*q@t(G>Ht){IhAFrjAQg~WdWrda&qtvuD zyey}f~(Q^p-v%FY~(%b&|0c<6J+1M>0-^f}{K zG_UKo`FZE4x#>N)pAV3mq~WTS2V(vgl2vp5S`Jh&98;G~6k=kh7ArBf7C9Y96!sv8 zRAt+} zsb$JuAt^L9rchXmHp4`E(4@%0Zff){d=D9pc830p@?9Ey=s5UU>geC`@@#liYIz>G zv`C(T2$!1mEI`(>Ra$BUPuo%N>~rL|t>s|Hp=oach4=?Op!lH48p9?|<5-7>O@VNy zdJI4=FWK*>kt~GsIc);@-G(y5w%0MUa&ABV+c*W{y#81_LIZvjeW>wtBKY$yU)$B49b}Bh+hBgSHw-GKc&lj@2m z8ZiC0o3~#~QJS~|&TceX~C? z--TfV`7i0B4S9+Esrl7e#Bb^&SFY6T&&}_xCfuuw5m*5d_!C_`OHKbRyA{aar;GVm z&g?IJyk8e4Z4}4dhPaFB?Dy&G46y<+$^P0`Z@uAWz;)~c5}W$SK>h~99fvi{RujzB zg)B;;7KWT{ranRzaTeP_zbKbQBRf{KXtr(r6HNs2HyPrC!C*=C@n%B=<^T`2IPih| zEryuI#eIm6w;Ey<9MB$SDbw^Aq73715BKpMhM0&zWas+)+YIq8O`Gr2A27tF>}!FK zA2CKQS>1)D-?~o@)f0xehFRY@>z5KgWr+JG0hjvx?;GMt4n@q;&!K*w7~;h!aJlv6 z0^)s!_){Kmg^%|e;wkE1W#z9Sy*nWIo_qqY3y7C6O%iy0K(yo};SB+C8rQyRzy79x zm_RF!_wnX{_{|YXcuPPG!u+#qEY89}{?>q~nUREh0^&^STWfKl4CLPy5KRb+_5>f_ z9T3^nzs|4!KtNQ$ClmOgfY?m^CRtCO$NJlWi-9LwufZ&E-GI1>jxohL4`vMH?+J+G zJ>bKA{66%l0G@8$FqHJY0r9sY;91rmq`lXhqK5rB!g^NX4W@Yf7~r`UXDs?-iUpIC zaE~dTWPj#cr%C(XW{No+pJRRf?*Og@KF+#LPNloek;^dL-?Mt9_-9OU)fA9Vw62xv z?l8r_=;|k1pPtR;UNVJ6^_s1BCI4%tNM-kySRYFKrYTmDzs0&yHowyp*V4V>c#kP= zgJ0OKK7Fq#UQY*JW-XF4d7mk+C<9*ZtGnJ3*VElrST*o!OczUdSQ+h8E$b5EO_n%g zCh%z%gI^$jvnATGirQ^fx}2{Izl9Ug838&{J z)?^4mbmhc zCCB$|OU$9Zzqicwln2~m1OLgN?t3h82gmzqD=g`IE%C2L;8!fJHkkg_$j+r}H2YQS zc^SF)S>hMi&)9ETuS_AmJ18yHzCGA_$gCQd(gBUcY;ct%IK`zBrNdBQnc`Oj3I573H=?l0N52?5cY>tI_I;4_) zr2VD%DkUB~ujGO_eg*jCQOiBJkdA=E`a0Ow9Co_?HP(047FDCbD0&_S zG>Wdkb)e|_!@!C&ioHM~`G^}J&&1&mhqYa&>ROVik3fX6SxDE323bbNh331sEP-bK@)~1r2374^{ z$%tP$6M4ygKL;<&sZ$LjGpDrcK~f2hHtI!;zL_(35|*H%6A`$yqD2TtdeK8zUG$>U zP+}DAL%NJl+N?$O-9_K@%sV1h=qYITFQMxKYj! zAKGFv^voG9IkD4G4tg}I`D5l?Oh3qJ)K8=u`HV->8&~Q^)DqISzwy;8GY$U;Enol$&Y2UtOWRnzC0|W zXSu*v_!!Hm4a4MY)<2Z|ST>7sk#nt2$Fj*^h{(Cc$M0L>w{W$bTYZdWw3CLuLx*ou zKOB5<;AtE`ZkWw5AFU&C8s;mzYI5M%Cx7tF*Wl*VS>hq!Vyqgm5WKa)oK}PCi9aAi z$ysK!V*og6W2XV0Vw?wv{4-tb#0r$N+@Mb);R=aN%(0wP4aOfNTp@8RW?oLaagF5P z91anmB;b9~$r5*C*0oFDk|ZwrZ)rNHMIR1^tTNPKxL zaJQlMJKI9y*Tm=h{11fCr#$q+J04=~oKhnXdI-8@PMN%Bmu@ctjL9lojDse9+1or% z({gjB84FnBqv2qgZXAbe)_AKLaE5WRg!s`RJ|KZ~f~@AJXpY8`HpQ_Ch0$6P<8WmZ zuCIt=M43;KF`zDsB6~2P*~4S|aV_J(@Cp@{H7A77G2CB2Oy``1K>qq+Itvj1hmU6^ z!~ut{F?<3&1M}4x2|pMjFpER!)K~P4qH{8 zttum*7+Z)Snme+C)iMx_bKP5|T%}!Zo|>ylyIfC+L=H3qE3i2tgPU{bDMaZJ88>3^ zU`8auiwG$&UB3l?7)>%<|l&>pxB%CnGRqhY`kboaf5SdE=08n9fxzvfgW zhemQg^m`;N?0!6E1!*B?BjUXKX`$qt<=k5Z^x1=ww$}MKLY({gY-y!)oB{+5cOQ{F zi(7zj=zfup&>zTOr#nBN3AleVrQbV;8!C^&ini7uz4=)3@v5 z4HtN*Pk%xeCm{~G*}goS?<_0^9`0kD?;M68;pXZuN^9VJXKOj|NS!D9@_gqk7}53g z(bBZ9>EerNz=b}3Qy0r=pJHF$PF)Pcs3-8-x>(Boj`it#bfLlZ68L>xY{YzXOZArJ zY!3%UjqGpC=f|PT4-xL&!}QmsemHdbGh8Wwap>|W?a|=#5koZ7 zM_c5&j6(-QI9M&*Q*;$HaY*wk1ZnqFo%cX+o@R{fY+a_g?fP-DzdH=^Jng?m|6I2B zk|F95gxxdz{=8;j24%ydkyUV`#+01XF$bOb$i`EK^O6(swPS!r(0!R}KZ}rk6bd^AR+kh{ZLXp+Z%rvwwCt=^YgQuTQz+N@YY?3BPMMMKI@=MR zQpTNSu)PAOj#A2aCV-Ph=PR}zQ}s%mbWE(2@{Ll@m{Wy;PpMF}D(7;{)s#wwY8?lI zk}{rQ%E+&mK_JBsvkfxrq)b!+Vw$rYktyY*tEJ32nt2H>&c{ct0EqY>LmfnX76r}Y zG4$q7ad~SJ#|sFP;9yZCim|s-T3^Gp!v<28sg7Vz0e??9MX8Q3I1^4B%F7!hz<3pc zNuH-P*Rt?pik6qJkSR6KDjflg4Xf$jWi4A68M}?se&>()&RebwT%3hhf3&=Io{iwJ*!dWF zPF{zi)jG2l0G+N71_qv+*NIUD=Pc(Knx$*LM>NL?9|5%b_gD;#{6=RlVn*H?h7cov zp)(E(e%_hSNZMj;#1XidrF+jA)LiU`QM?^;qYUR3Yi9sHZ>T11fgWn!3qA~srHCEg zi$2U2wOB;Gmt=keM-^Kp0={f0Ll%g`;EmoZhO%U_xEc2GUNwdoRH{Ubz~Pwpnvo}A zOne4M_Fgw$L)0+xt3*AzdYyL`A<{0Q;M+ifhBb(_Qy#eluORxP3(8w>AkW2-dPa&bQE_8EmzjZ?+_u)p_r zLk)kM7>m&4y<_ma(#UTUC2%TlkHOS~tDYEwiR!&;{0d)47j@Ax3-~=_@pNLWYc$%- z;$gsIG?dbdsWIY*u=jS|E3i0XVrL_iER?5#oG6W0X1pRxIjk*8*u_!u><+;|oPwmq zE4J36M~DXEZtPLL(LT%+f5(V=V=U#)+2S2E=8d&>97$$ZoW#*7vBL0q1bp!#LZLU# z8ZKe6z;D55Ua3_iVTt&ZLs4ecNEj29DS$CwjVjU0fh_l7t@xVbTw$rGR4+ao1z2g( ze~tVGF~kC_lBe;ADB>;-dbK=k$4xu&KL`chcpokoN5R@&jXeA0RMXl6t}@_b{o5G0&2lp9 zAMc-|A0kX)O(nNFzRQODDmGq$jcZNN3;-ww&WnDAkk3_+pmU~3I%-YBb-K>k5-&Mk zmT<->8C*HQ*oJ}}nVE6=C=z?Ao+=8O7os%c!UygAlxJ|AwGxj%<=Zddl8F@8;QUnO zjo5hNX-#&DjFGQk+s1;)Hx!}LidF4e!C`7C(6aENkyg;)Pdn#YxKhCs6|V8b38r$v z)TwIHWv#*8#e&1tdK1k$g=m^uZnB-VNOB9ND=E3oE(GR+8EQJZP94&}f|+V@DRzcp z>K4pWDCUHra=~ncYMm8q{Rp)nH#iOkvEazJWb3oE$cL3ML}Bg==z>gB3P&Ky$$oQ> zTPV0SW87jF3P<+BY)oMyPeT1rp_huesjB72tDR|rvEXA6SnV-P{KBGr67ks)3gG@L zB>%k6E9NN}rO~*K)L?BXD5_(*6kAju7rP$5R5VE~_@={KtVNS4gE>tLCT`JT_hB|O zr@5g4sNtUy;c12zt!T=>CCGL@hn0$^&XXv&I0aoRI-KKxTf_)y#Ty{6XqqYzESQBQ zv}n327{P)@s9!Wg738v@1Yy5urYabY0(6Al5Hx9-pvjKlo(IBCWHJU|;n0hFaqW~G zhdl2R-VCRMxwC=RtMM_Nzhjh#UaFAoyot4Z=*F-8j(!ii4!z=71O|5WC&vP9Qk+pI z58-C$RljW~En8;zLvN`$ov6V1-E`3IRK}}v4uh)?z3UX&dcE`Wc|iAeNz~wc0e2XB zpOQJv*%$@-`6uvKrgCGefgXVIfaW-x(DR`WD$YinRA8~N3y zT7=FJE4rTEAWvF~ZczQ!oQ**=yfvOA4;ce=BfXAE@;|T=7Tq)$iX-boE0i4hHM}uY zbQ)dB;e&fcZ6Q?Rkg>N#E3+grojWkyidMy)JZSzB6{3HIM8t_taE)$e%_wrRXF^IRFWG{DmAa^lb0dJKh_di=OIp$D(?OIc7rgsYv_?_a zWojl3NTLkNBh^EA7XXi*3IPXFw8%dZwL(Q}xifImk<%8P^=DkNAs${8eg9pFOlN}! zbT;qEbDFE5OwJJP8Seq5VU%&%UrJhudQy=<8Uts~WJ@ni7$<0E0z{5Y$8Y16F6ux^ z<{XcCU%EIRqzbUCmma4)%68@|Cr$xc z!5gc%0px7U2Rc=yAB_%g<(4u^g0|SnJql=*a^(}8KO=UPwyQIfCMPxnsDlxTPt^@s z40O7pEqAtHtt{=l7~YQb+~FgfrCq5~v(?ViaFx>4$`WgxbE)SVh0bv zpJG%?e=ryod60{p2Gpwceydw>RB;9>dB4+rhY*A20B+Y+GG>ZhQNTxam4Dgd@(RGm zbd`XG#HrB8dt6tY4vVjj0DMAMiB-0^u^#YAAG%@@jPCv3hsENZYQSf8H9#@V+XC*j z-i81RMlQo~inlqi1Y?icEAE2by=wxuV%}mVh#e8YEdg%Hxi9+yHuHWIP!1jyv*8rp z^#R^V;%z(LtM_gQsQzUO4TI)w4KVG;DUNtjdx2x<+M$Lk8XJXBlo{X{&MjYqKbEy+>Uc^btHz%yC=Y7 z0V97kCNqs6X`hQzoU&6dLdxNMhzez=Dd*Chlb~2xn?km8O(xJvg~HASFnif5g|eMd zM*_7gp|(F4O-++4Y<=&cHW<;%1^RD z>Q;=JbG`?3zCyNRpd)1$sA^&7ewd`}LWQDQqyY|#pTbHqybSO4Op{Y(M*5KGw z#W~Gc4G)eTu4K+~4q&FlrYY3u9E&L)o37Ae=XMNpY=)}WnjitG+Q>ejt2reAk5;s?EEzpltd$XJz_)YA3g^qy#{~K+2c^K=SGFyKd zpyeCuTH_7LXdTqV$jQ8Q;VtT%!YTDy`h#}f71VDtn4&)R&cShH>XMzRpH?+ zg|Z!O9B6-ytN9w{LD}EpYW@xmShiCwiir4E!jr;fjXD(&0`6EgPd?AUh<`mCx@^Aw z8k`0ho46WoR<=M_yKP(il%BFsRz#W!XJU7}6Jh1tvRwVQly^%eSVrhCs?Ldb(N>x8 zp((at6(}3&Lt9)=cX53f66@Jop8l?^8y3gV13Vu_#c{^~=KC<)-vqFo5FIMMU#Ajk ze?T!IPDkkZI1g9p)L60P1#ue z90@~W5a&RNew~D2apyF^aXvLFE<;;orTRmXnk{~hoS>}CS36fUaD9pCFG?y-{ZjzT z^*#v;#P1QG%PM^4V(|dgsPtip_zD4`tjdQm@dO9C+P7Yn*uwc!A+jt7rF3eu%L6Jsw+ z*ztoJ`3DMe^eh;FpLpM>C*BQ1i8mS}RZ=!pe;z=D>G_B2d_;rp@-EoQrs;$IX<~86 zrzhNc=dpk@^g2n!aW-}^Wix#k7JtKZE}Nwy`5=qS!Hbot& z|Br;OurS}s=IAd-SRihuUmoSdVt=TpW4}q{poEgo71 zmirGtg|xCw$o#zu*;LS^IPc>e{4#-8V@yHt5seE_Qfn;1HD|?x(B7M1oGT&T2&e#@ zXj~zoE#@}>PBQMrg2S6UVJgyKJRxCN{2>fD)p%FJsF(;R^rjp6IM%@4R(y^T@n#u3 z<>2n2c^=?VMyG_XcnsOEceF7b%OmgkJY@sUH8x6WvDkx5&ucV(DPf7Yj5^OZc1ai$ z^Qq)9h7RR;>r}Xai+rtW#n}sk{4{tQIM|FI`NVV6U^MMgybJzCU0YU6VUD~?^J0*aS3uO?=*QE znzrAMMABEdQBjMa>UH=xrgKG0 zD&XmU-2#zI2kP|e7Klej0CxGet&7DCNS3_SJ}ePYq#@oKV=6So4S6~3yfb`im3-&G zJJVPoskLGfyRg=8s9yYP7~omH8ujAG6!m?1LzhbwPO%c^q0_{T_5iMxh3PxW!qRel z#GTKO$l#D*8i8?7V&Vo=GO0h3ngtg}b9`_SXM%~EbiV&wQ$A)brylMZfHOy54AJyZ zHI76OccLUQc+owT+wd$AB>A|lJcg#Ls<_P~nh+yHNGgi)BInf!A@pJ;pCna>>WBEm zCpdqT;G}~qPN^yXfc{Q`P8V0|lwz8P{FYKss*GEIP<>P#g@T|t3x89pP$SCsN#O8D zp};%F!t){C1;)B5Tsj?;TC`Ljbc&C zfd7eABw>k|!d`r8@u>#-P!?m*XO`L)REgmn>Cb&wE1qE&_E`%gbG z42A!;?v!wvxS4+NrS+VIvqTE}yWjdy!a3rPtoxOf1{cONN1}uQ`fIC5!i8e^T)+d? zkrHC_>jCP)GbB6#w*MV!ryNc{II&REmV1A)ID&#h>pg9$vDHK?`}T~*0~)Rgms0y@ ztp*8gF%EIU`?J+5VMshqGd*WrCSh32;q2Mr!>Cv`2=IC9PD#xcd^O*D!Fpc8T=6AW zrx&fyBy>d{cC_A0)(~`p>+xhHJl@MbEEdPj27JXTm(&t59-Z=DwdP0|6YB_Hvrdt) zO7Q-c_qtE56~&0g-W%2>l3Fi*fvMvC#kxhp25~&Q@TT>cgwy1U1KwNKZV6|JWt^se zwKAo5&Jm?Z552!xbrLp;zq7wPt$7kI6gSYNcKLM|iz?RLZJjNtCy3b`%UW$;SlCPljoXzOi8p+-8^~C`EfIYj3?jL;PAZ4^eW$nAyHrf z7MPdKq7kFQ!y@1n%Eug-5Cu5^MLx_Cw=*z~lJ6BWKe~d{VpHA0aK*1Vdq&Gg`Z*qz z9QZM&Isq;bXI21?HMziW23*NFS>nT5@g=6MS8DcRbIGtdm6FTkI|Nvi#SnDVD>vVj z)LG)~0APjriG*{+)Ck~2^E3$?VV9*~H@R)Q80PTv-)Q#)8MRpCxzIG~ohpxd)%cwj z;LBbxmweyZYYV7OX@d8qyp;jo&Vuzu@_7YsRUm#~-pTQcL%dtS4MBV0Ud#ZTTx;G> zap8Jv0zBvzT-d!clLbX&Sbqy6>4w> zv4zd^&SJe;PJ0mOn(lLm=E&Q1mDj4vkr3iUlYbzHwbFGm#7p{c?VXINC5P+X|EcMxEPdB3FEN(0B&Afz-Hzg{#Ghih^j$DK)|Gt%YBu<+~bDq1F3Q*vRdS``IxFzQNBbjGlr_clVl|f z&HLyW(hQPHL*95fzlB`gYy9Y?erdw1l|O`lv`!lv_A1REp~AS`Tj_th^yj(^# zSKL$v_;LdNxE%1+1k9`jd@TVFKMwHq1l+~w`$in1ZwJsf@0uuXM0k-PAAyu7mtHiu zL29ar7a6Vw2UWIXig}FJLw#tAOEKrY?4U}1LZTY>@p61>ScDh|hxsrn9->Kx`!>iH zuaKJS!(1_K6yS)UItF&dlZXnQ2tFXyC=l0kxfdon@i6-ZCxEBY%qHU?swWV;vT%th6CuRL>M&G@GF zRmsGki(-bV+DfMHPY7X-s_1;w4Q=J3KpC0&YQKDtY7!*ouBsN3H<0EhNK9N6Nj{ZI zML}Pgpfi(I7V=3O6C`G}YAj`keEJ;;I@4Swnxy!G_mrgb**50AiY^ZTBvWFTq+n>W zN3wHZm=`N{IZOxt0q0QAl_i)m$Lmj#rEHF=a){eiB}BTCY>t*j{Y42*X3^^m*M5?meV`wipmR5yME8gAv;>{|*+b|d?!F=9@&prixk*g&b`ARl zrfmr(?tQ=cMDfd#&S}NXu%i3@{}iNjotxtRVi`jqHjL7Aooj|{7bPXQR@UHFSk>@v z&`eH{x=7;F%8E{is;{8{haL&8TgfGdO9l=J<>>p?`6=izJR~M7(6P9mPO2b-1S>%5 zwgeM**@`IUO#X4`1qnK{t`L(n75=0oIqbfs zw}5W%O6QM2uZ1}K2t?g#xpdn0WLyRra?EGI^%XvnkflYY4Mx^kJ>vUF7@TJ+!6tTt zilx{Yj+C-`q(Y{%$pvy1vYof!Y1MfOg`6`mp4A>D^TFrv(LnhhNR;WEnFdtwsze1& z26CzDLWPR8$h{aOdwk08*!Y(znl@hkz$hEPzXB+AD>OFp4QCipnnI>?6B-zwu24{m zaGeR)q?*S<$W|nZHR)H%YML_+dewv!GMrN#pbWAx=UnY@UCB+X)K8Fp>? z1PWY*M7p;63nehCt95AtnOg2u$TRKQ((i$B=oW03Yw?f=-UC{FhE`icVVb=e`qb7@ zQe-@aBYQ&VSCq=f_=ND2U_*-I@MhM8OhpSj4`aM1 zMELWY$fz+*$Q57CDLA?%Bpvl>T-#q_BQ!B{H!iWD;cvSB3I2xo2POZ;SELY@3{T7{ zUj&`l(!^ovu{EXPM4>cPzXdaK}bA`GzU74>%dXd z#!!@_|5d^cF^86j>gpJLwKi;9mZt3w)bBa;G{X*x-Q~?G8a0$TUP%CPs{lF zq*F&l|E=H_UA{nF|0SmvU;2_~`}O;&D&L)S7@q3CVraxK+v&yE*nnTJ1y$Em@D8J1 zd=mUNUV{HW4oV)J(qCf9k_j{WOH5hv4y;^%K*un$7ZOrXErv(jn_z)Cj`$am7#P2af>vMFj9D)3M4Y3fhtA3dOBQkgebus2j z{czt%cm=g@1aPjt6t1LRK}9I4AL0Lsz-xx!+avYD=YP`>r3i@iBYnIRucX!kyFPx~ z5RXvHJRQI633+&D@LbCG^aV>K4vH5L!0PjTqrD##IhdXG1wP&z6c{tDzR;KVNl-jG zAGpZZe_v4ifb(aR&%Zw?&cbA`FP6`9;6dyZ@g4_#w2!x>h+&u&^<#XzEk#^(B=A@t zKb0ctT;LL4znv-KPjr%T@&2TU7TT-S|B<0RDdGT~CgwX0@N1dC<$8S!`?oIzxfA`B zpAbVue+r59h-(D)w(}ykjGwi*|JTZ4>0W1<>-Fg5xl)uH%#X}I37sx z1gdVh|D4`5u>+H+E?2$^!*dS4OH(((hjT>zBtSKKy!Et%kx>mE-gg(5B4w&mW5?$% zzl3S)@_aQ;7|EYnsPlZ-Bz{x|YQFzeW{da$epXlD!)4-pBn5SaIWX|T z;!V_Bxr~g`-)o|k@FwbC(EYk%ofeXBqRuA&IDN0A<4sgX!n#uZGl}s=H)CO4nUC>i z>PU=AUCf`FckA-WoVxKk!?6q<_6X2x{NKKKK!?>&MN=x5=7OxohNA>h5C!QvSLTC? z^H88_aGeRsA?1D?HELxIuGa?@FObDtD`hcT#kG>bC0jA`M;PLp=yMWuF5-&Lc!;W7 z6C|$Mae==~lydb}733koR8)$mNzY0qZk#il{v*@JU`p4y*eEHyLbDt}Z219{-m?=7 zTrxnaLP5G*m{mQ$c&;oy6Mt1P#E^R#3Y4I&2~xklR2od@CYXMiVB!@>T$qC9EeQrL zfT{srfyBHzXg&@QeQ=sg4By6e(ByChO?C>;_%-7YkC|K~62SlLWYTG3iNDrQYNPth z>Ns&Gt>h*LYrXuLkx8o*&6X?Zq;`cuGIg7@TBTB9nYv9{qw=Gu!=&c_@b=#ESrps< z_|EP=$wQteoAy8+Ff5^k0BJyk0D%OElq3{G4+w-bA_<8h2-2@$Z& zsHmvuMaAAb_Fk^__kN$*4e z8J^TR=b)w$D`pEymxbJjm1_m{k_Fj_)p|jeDGRa@YuR^PF*K#4-1;0rc@7`Pj`+tG zDVOhXi8W$_)}_EXxg*fodnB*WDJ=pzSL;$NH}*%IukTxz$Qz3zF4Qd=j}GG1HuV(K z!eTU#rZRAAgG;vw^sd3_sPKn&RyO7+R`GL>b-rdo0cw5}lXqipBd8%o&2^rXl`Br_ zh+1w$R?5w(Sn`j!_-mwP{WaneCfR#A{n6G-A2p@-z#fYpPZ>HIo0SU-PpL*{--Lir zID$#C@0bKM((7zzA?NiXwv5*%?=i1fnF7&wMF3x z%cX`isPH4?$-`5wPXYf z?VKXZHOg{c9{@B_qdcdL)7>PkL%xynVh%2L3U_B=HgX=~O!i0$CSq1_fFk$y6J*OJ zM&aXyf`SfrL>KPUDC`YaPH18NpedvAPYU0un^yP~LoDtuP!7u0Ld0~&>$XW*cP&s~Dbc}bnbg~#(6MV$t=@;@4->m}?#^f5Ry zox>B5_kvzRXE}2^0KKStuf(Z45$Gjao6jUa7z1=jqjKl^VxX6G?R+LlD}@wIA`SIp za%T`iiq`PkpNBN|KjAl)T^D0N!M?G9NF)@scGMREI`Yv(gZHaa0$F3)UeEW@%#D07UV|?Te%H=i5 z_aUG=bY9RIi{2l3Cx<03t1m}~jl4^vc;_uR`N+F3lyZ&{Jd9=7$enip=46iSt{y@~ z?z`PU>!G}w+&);;kL>9|+r1k%PDb|fV9@;s>*}qvB4KwqE+a-}sH;SNqI*X=U>}b; z;_@iGk(nNhx|c)&`+6|VO$h?_^I*C=2rfOczXyBa-6||RMrNtwpki>1 z5x;tB;gM+i0SHsb`T_r>?7+G{Qq*r!J#5J6Ueq6cBR2fK7%1y&LHg4iMcEp~;PywG zQIzu(1n?@ao+y_hV9{us{EK&ix)wk{@7aJc_I&(mHJGipUyB+Y?V`LbAmKdWdZTDS zUsTt9X@A-gNufFkqWgv2bNe$O({of zqD3PqAi1e(g;7-Om66G-Xw*n#a4M4qjXtJ9W4s1AHbzU495=ubI1FR1=mhG?J1;m@ z1`=XlL|upgAjaFp9eFrda+Oh>>fJ*zg3SnH#nBSbQ+`K`?KLXy8>F3IA$e3hlXTig z(7sWQMz*sv1t>uyI4zcfqY^a=JF6U^B#jcC$|Rs0!?g)+Y5qjzI>Q@+={;pzX*yr@0I}# zi9eZ~QHkK`1>FR3cK|0}9v&E$A5PKYMQ8=}z;O=v)m)T*6xRgk>>o<-D6&F|6^2Cu z^HBB^5VUu)cF6+uPhqA8J|zX|luJ6`27LPP2Bc*pVfqMfBVlq=bB&QcQm-C*IURBH zD!oXbeUX{mgkuSdn^A`67DPTDCpM>yK4F9mJN?7Ukj`j9z%ep5hLM}`JnYZIi>^jS ztb#5v_P?2AkEGm)i<02zjF&)=gSAIz`W>~uH@-;aA?}gC1uS@E!Jb|R9`y9PphWH+ zBIz%5t_5kAAZm<}#c@jh7;ubP`0!##cSx?e7?rX&FNODysn^JK{tb^Gvq&S`X`2bu zpizv|+85|#je^crMC~#7wgjcbIfpv|Ezv0CEYAjN)+p?hV1^rmv&G37?;IWrv{WO< zxe`7wrcI*+Cjp^*%<@0c0&ZcFndUiYEH0U1q~!O)C@gt>OCuW56Vb8c4P6j#FpdIx zQzPXRVr-VYy#%6pgPDq!yrc7MQMBY;jRK-*$$J{bIQ8UwU!zztOvwjYN>B__@}Wj? zPG?LRB_C-Nb^_3=IvqvJJ!tCI zPV}JV{(x)$l1ZN7Z1?wkz{y^2jC(Kqwq&XYW8L!+hD)Y-5Lzrp@5Pk#Hm_{gBEvkU zgZg+7hq;}AqJ2H+Y0=Mvmb-5#a{HU!z%qK2_rdrqnP;Qnmh!gj&E z=@-@Qg5RG7SmQz4okpA2dNAOY(QE2F7~?*}*4BG4*64jRnroNDSW}=y#%tp-LNhEV zrZU#YW9($Sj`3h+YzlxWg9p0?jNY9P5$qDjx{M`m!Zfp)8Qn8kVi;B( zIIw&KN@NVd0x2frV}&r6F(DU?Hu`*BhU^pKc2dMSr4;cdZmOt^b%-yf5quhP?1V&C zkTMlc5FT6e6VlEo%nxJh5brRk4JQI+$2Ks7%fVEPhOsAW#M3MuVc{7usAlYvPAw=* zL1SAq17`H#xR~)ECu2k9xF8~)h;-1-aUJvm-gZvQ0Sf6n8y}g$+&wN#S;32-eyV&5 zD&9^Vz$4@xZVpWy__Zf!CxU(IAdO6;qn(S0Yi(_A&;^&4|GT^ z@LM(sYNrVcn06qMQ< zU6(o;21PxIsn_s0BH0R;y4im+#eoaedTwN(#x5~ zj(C+e<^|JScya1$8f7_e(#)^#kOt>DA2RO^@BKIDN^16|?)zfrl?0%-wV{fg@ih9! zQ_%^$w7Qd8f1**jv!w)xXUrgPic?FO+#(4y&3P50AoUB4W;tAK`e?2LVeM#vv%TLD zgs)%G&|m6ui=5)JBdF1-7<>e^I5%QB?sK*||H3Sk`jsxX!r3tC2wLrY+QUb3YDXMR zD6Dd((WMx>seDt);2|E#3tJbrL!8F^)U+eHo0P-Xds4sA%y{VX4mI*19=h-xSRdk{ z%iS2XKEy+pi@F1Tr)%OXlhqa-nU%FafC#8q!(6TRdB#a>l8_!hIDKb zeo}hD8o|^(+mM#i##8s|)5i6Enbb#_!Nqrsy_W1$F`ByXBeLHJJyM_0zKh!=^ra`s z#Bg^OoBq^xL;yar4JnSHFvp^QBa{-bD<>HNkR6qTHp?2Sj}f^5Yg6b;5?&<*U+{XY zT*vD*=)X`+c*5zm$aGxTZ^DLl1t4p}Mn5T6V5)9g*T%m z6V9O=1ZzaP(iDF5D0yi^y-^xLo{)o!;OV6uSs>Vq^=ettaCkuQ`Wz&a9|1MS-p;&! zaPzVVKVTUQO-Hih8rR79=i}ZsRvP2d2k0u?q@TQ z>>$xK_z>2t<#8+z6zs` zQDL;Ff|fVNlZP*0mXB*~FEaj^A`|=~`5{zVsw)jTk06$nmz^Q1haH{~SzfMDB8@QR zpA>fkVoW)oEy^o-#~w_{^XqDi@;ROnjE-&P*~u$l zZLvm!zSMka2G<~;3M9N$A)`WD&QUudfyY<>%pMg2g5q}s0YJx=x*?F z4<@?jVIT$fc`)ME9}oDH2czz6ct!9z?~S}P_eA(=@MZ7N=5%>;B>0MVv~s4qHj3O= z%~2bueO5QzzX`r!P85{q@=dznTc*AO&UbmcHu$!w@7K=4kZeUGQ>bd<#3;X1CCiG5 zo&9A+07GkH7d^Ca)Z6zMfZ<71PmpmCrkP2#dPL%|Fb8O{Mz-@he0-AkP$DRIg(o%X zXcIPi8k4&ON5PXOccGk=lh6~1Q>O3(ht5|?*a_}^smE|Wp9oZ;RYB$J;ewGVvog?; z4!_-Y=v2mL@DVr*8J@)+8dS8)MLI<1&DDlU9T zgkYLM?5ViuzcRjThcB^KY|?A9pu?|TRa~ss#9=1`fu!ORU(NF<<6|~P+nm)C=bttT%aHGTl2%3eON0o@`7n zd=c&7ZP(V?rN;CTdj%yrEm%%YAE{9k*AY3@pF=<@Uq8yJfv;dU+S0{FPA%6I`1%?m z-`1R6Jcmvm3+3G7H}OKmhMar7CMM&SP0oG#0Mwv!JpxkBgWBX_8Ob>h9gn`JtIkFs z$a&a*F!50~&>r2X>CTITfgaT&)17+QDd#ag?0PwWjRAUGqb$cQ1A20_G%4Tt5bmF| z|G2fRp&)trDMrpSI?c<$evI61r(GS4xixeC-_7Ha#MbR9~9(l`zO+J^^vn(+re-akANySYh*j0 zV`%5x+7%Ix)9(_hd7BrSoZXnVb8gr3SD42_=G>v1nkY}Ne1x|u5Rh~3VqLfsYRHTC z+W^FOVvVkcIzin)@O||oh;o2M@B{CNDZ?#97z=(VS%_Bdd+6xkN8ZA9W1MTk&w?L& z+j};~;p4)mVyvw5gcsp72iP<%cv!6h&3&T}xIdE}3W!ebn?Enz$V^Sfuy%7O0m}zP+PLy{sgMGcD8X`v5d#2;l$tpO= zJZ=NZj^lir@6ES{`#d^6c)SN~_aFIyL*zqEwA)xXP;i)hrwJp;J+%UGgvsxC@@=V) zI5`)4_4aZ*vGHR)nCV_*0gm&^X1QmPxzx+mr%eRQOm957Tj&du+7AGjL9I?SIW_Q2 z);(-*g{faBZE?Heo=I@3se|u|ZVmYCaHTYk*M#mkD!D*xEFTxR3=>*1_xvYS2QETdN+4}fw z(;dT6}$9I=G%vYKEW2C!Hw?aih(mr28YoM1$* zb|hAk6qyI%h@0b(?!j+a7Y6&u$E@W=z+ivx!`6n|iB6GiFWE>3#OJn?0dqVUbT2Id z%(d4`ZrFW*8V&Gr@ePCmz(MvEk{fZ~)UbFj(QiEO+}Tz-jjLB0109%Mmuy{zzcHd)5HJO8aMlJOpAq zQn6Ff@{p=VGAuuwbNvVB4WQixtoxulGMnr_AcVY6OafdYH&q$jk}z)uo4wayBkm&{r!DfNl<(zl z?hDvz^KB5UX>~ka>cLERNhxyMJecRc!ZEYVg9YvjjIql-SnS@!Xtu(G<6Um439j_u z6t|UXtoGn6w+H8@H6C2x_Q66fxXy!%^oPO!Ev++qwz$vcAa|QR3XR2ysqP8sfH!+^ z1^R(sW{;2wT{;|0J>JJ)js|bHx6(XZ-~@NHzXx0}9q>TtGyghnZ2|tsvMu#F<~Yma)luO?-u1uJzycsTiR}2uUbG z67*cpUoI;2qKRLD_Fr%MNjP{>7D3mtOcHWa>M-ImXUymKnw=7;J!3(qv!%;rr~I z{Nytz?=igqo{039lFRG)NQZ$!`HQ&=;cLi^Lkoi)QPYem-I2s0Kltse_%NanDLvZQ zIJ{~zV}?2#w2Yky^+v|`2)KBC3O!?Hyoz{eW$eKKvoltO&`%i=*dZpP1KJUr@$yL2 zk+Bf!cgPqG1>=mA?5S9T%}o9U;^ZLnnJHJpoiVzSYnRj*Gb0*lQ_t+^o0|79XLizN z3CpJ!W~NdEm*=@C@1uy5g4xVRQM8JBr`&}gnK-LY{yC_0RS6DZ$YjG%sdMHupuT#I zZaa}&pnkkpBe%mkz>fCp{*zhkHe7?u&e9!Df;l zI!_BP9tZT~CxUDzJqGA0ofmZOfXQa>*9f0)#B?$HX^j${$Adu6XcTdpGl8DfDC*2W zRGxi6qco>8oM-lP8l^j_aH84IYt+lR0~ac@|D#c+gT@-O4{DUa-1#|x=gIb9Zi*g~VQ%_dNC#`&X@LP{48U3@HFe9xz?lLTP3#JAE9aX7WJh#e9#y)6CB2z4k?R!A?#FU?1YhI2Tf(4qj%6$W?py! z>(D!BD*Nsbl*s8F4Q2<2<%fHq(B|hsNVx`4B)@VH3rbL~%!e(hr_+lzK7N ztQ?_7b-Ik|%AyHU4r30Zy0TbvW+u15V@FSxtgK{se#rt!=b;s}g>E35s~gBB_`7*7 z0~POyf~&`J$c$7DR&0gK4M>$klxIKpU;P0K)b5MLfbPxdfWy@L0uv$NL6k|E45y4# zUdwiC^KUuE{MTJ6T6yN*dcPnR{vCz&6v|;G9u{T_SyS;(%4-Gegq5_Q?u1odC*V^d z7@Vv1*wkODtz4`34h5YX*$L}3XV__i7gqkmMn|&~#Oxci`6Alv8~sk;OL3KFXtSqj zv!AKWp03S)mgel`$hbM1!v@bjr4!CQsuRv%BN^<30<=Omko~S3*Z~$rR%Z}&7VFSi z916(F2LVG5zp<5|MAmeY`Lt5Vjq=;dOn%QOGO3GXE(bw(H;pY;^tX6zXwRbMbr!AT zd%_k_Qy3cZD<58q(4bBIh&CW@I@2NcXye+>dl=xAkKO||E>Oh#AJg6+b~0|u;*<<|On~k)opFhgf2Y(Y0 zc}B{T1iIiKR7|_zpU1f1U#qnP%O1MQzc;u0FB`1Cn{^N=-3?5k13pAJz&1aCkc7-I z<0dGNz+O184j^(_xfuUPq&TNueiZWUXrQI@@5)C2ij~2v3{cM`fI=YWfZ_nS&e3?<%ZGQP1 z+VeTIkIFw<$YaRr5sTGLu(DO9T!LmUnFUpsON2&fbk_v|S9rIn@ENh&hl+W~icbQe zG+s~=qkf8X@lg7n{hPRV-#=LbfL9WmnjF8q<#@do*w<;OxbuX-)YBg}7KAhzM?- z_@|&WUENe&UAiOHP1Du&au%UlYr006Mr0YB82YnvoZ^Dtl!p=G)2!JuF7;bc$?axT z=j$+v&SwUvA#S;~s`QrIL|x@VU1da9S*x(heqB`|Suh)}0#J&VJhP?$KhypmP(^y|)Ty z*m(fM+qz%Zp6Gl|DG$ySts|M-2x2|Naxyb~pZ>CN~;z{0*$LA}RW8f;mdP={4xt|Lf3yq1fxydZ$QW!O8 zeR-Jn5}SO*N?t zxNj1IT^ru5GMmy!PeEC5iQ{S}A4o zyVbVj8P);C2!Urj-S|01>v^RI#v=D!hS7tHyL#o_<4+;edO@v6VJz-V_aLqFl813u z^&rRUA$6wY^R6n(zwBY`;^BP=>s57y&bQo~IPhNgUIX54xkDY`H>9tvp0`*oKec7O z>ETCZy9NAieLAjuTS8 z1=0r|sf&;%u}eSnNS#S?r_KQBBQZDL;vON=_GbwEN(P6%^~);16)(b8D$BhO7sb{OUVR5GcL_(&k7~0R@sQ<8 zxcb@8$8Fqh$p1w=31i%L@54Z{ewF7_R?pXLw=Z4mH<@9ro^RRir&u~!e=0uN!=nM) zy@`JMm;b_fz`c^4@VEc2a=^WTV?cSg&hHGkLrw%Xy<6400`5>cf#v1jA4va}`UK=5 z2!cM|fe)n5wn2*VNa!?>`q1{V9toWW(x%BE1w9fv4WtX%mJS{Xod(i6nmf)Tq0@E; z+%9ypuz9ywXm7y%U>tC~r{TT;q8g)8q_39!z%! zQspI9S1H@eO+uWvTCDrgaz>jf2A@;J5IDOveJ_2t)#5ZK6aJ#~-UC2c>QOM`FG`LMv1yQyVq=8^lpLgWIks7sW3~QG)#CPi z8bRlK*Gdc8vuF@s;3}kh{07|;t#_?A0bFjSu-+3z*#UbvVBYtj?f%M^f8fEO+-9&o z^tuvHMQu!D5$mv(c`YQ#%JMVcCtNo!|2M+{fivbWptVDX)& z9pvt?A2kVs?u;>jcX%-D&H&lEv;Cg9=)SZ4fkKeW;(I)p=H5qlxK}F0wirF1+$UoP z-htT$D?=Gy*vaJn#i{%O@7{Z!w%CJSJ^AkCxGifvO*Lu*S{n3b@~ci(GDrwVw7=ZghF0)q2LJ1MsQF ze1_3y?FU6?eg}>|hR+LNbC7jcfKAaBx!XHg)No4~9d-uzWQ8N1udrGV1oY;Hpf>eG z0lkh1YUA$q%7(>24+s7ul_k2Lc0ticyiA;&NzL|p5GQ9c_tC)1!ki}0(yhn6+;rWH zeF43nm3RM5@Yxqb`KOW4E82(|l;B88j7_iXa}Kn&P1o3p3y)7QRE&&|(ZMR?#d5SJ zqkcN7G`h_1f$zL3v;33mv7Y9WPBf=C3Fm6(dANx=lYYP_?9Ojk zGMKX%h-BCG1w#O5vm|$2JJ+ItW+jVqdyzApaIP+kUDv~4LGvVC7Q3$JBaEB#bXn}W z{th9~oUhAb*L7!19%hv;yHz>ArT{L~WwGmeAGNC1Ww$HmPjr=8^D~TswTN;?BXXOy zn)y!UBzFX?(~@^7=gWA&MLPF>!8`_U*8yF|m+m6Os7uvx=5lrzc!Z0Rq|Zz;LDGEd9*s9>;Z@c`e(6`0AWQt8URK z$$6WOaGgfUP7zjr=2neTv{zo=TNIASXS2;4bdb$=&M5%rzqD5t$ZI3!jXL5^!Jwdv zM=nQ?U=8stERnJd>g_k*WaFLgh@$3O6GR=u;f!m(ttVVtH{%_xK+svn0QjDNkAlky z^L@RVh&Wt5m>&!m<;FXlsLc=cJYDWw+zsd>`T}2m;9A1`WQK6ga#kY#o1Zocn(GvG z0y?bG0*A{C^YgWmS0f*LHowqlk+YQ!_0?sP*XZo0i+rt7i`)t|zr929+T>QK`JI-z zLXN61e|kppR?ATp=Fe{d$uQ(mV&*UECc=$M&I>c;gfJO~JR;1LBf?}DHl+jp*;SY^ z40)E9`S*eaEQ?1KJYCE*6wjfMM-@CZ%+$w($?+~cHq6xLgvp*7?rt+JIlqf9K*#}J zrmZ%MJRI+G0P~j_RQXaJPKx4D24)AvCd=_IJZ;7d%VA-1GSnd~0Zd16)|Ndwd5ORY z9>&Q~dob6Si5}jo+*w_LlRUhScOL$Lqu9qoKL2ES8Vjnil~I=KNxcAKKZZHF{Dspf z5OfwzE?For7wM2<=lPV@c0RTt%u2wwv7O59(}KN~)79-+>^*%bhF9ty5JHOG=*v0S z&dlCC!W=&OsF@F>7<=$2hD=x-io}8%5_5~lFufP#o*<`ORD^|^%2|iBvkp;E<&H)s zCysT+KzZJ~>CRyU4K+Zcpz~OFpn)2NjXryFxJ9VH%vn z$;sKKAdQQJBQ8A=xS)<^qAe!}@ zmh*4Q**=s6PDMuX_xLd@l(K$9PSIx^#1$e`)H0{am3$Eok2I%=&PDI{lr&`*@o-0T zx}wjIYQTC!N*V>*(9oEW)@|_3G#NJJ#e}#YZ)i2X$`f9J!eYIcFk}DlwuMHF!}C>) z5j;!Y`aK{wDXc0K7DYhev|1#$jsK8fVHA80pNTzHH|!j6>TWxg-8PKd7h+G<-CNWF zX*~3Xc-(%VowTtpVritlkv=BdT>K%H7-N0bZ^$|o z6l45Lu(q12n@YYm{MF%a3wS4RL?Dy)ITN(fim|}cE#_SXTviOHUVy|R{DEG6BJgcU zbD%LWj=!9tFJDWiWNfZCp2NTY1=mD+Ei&o0Ux7B^%0gl0p-cw&N~QL}QhN%q)ILON zA4E(CPz6?hu%8G#sj0fvP($U~w}$zAc&~;DUQRqD06bjqxxkaJ9tuy!K1!pBo9k*Uzi zG6p|#{GqwZKL9?2^5w4~aTtkd$wzT?m|30;s7x^QM4~qm_%D`sfya-bH~gZVi&hU8bN)@!!uBUw#q) z*@>dsF58j23xDc6^)hlRe0;23$Z@~s`oG!5XYuUv5^6ZsF4Rlxl4QiP=_8hwquLDp zlC5e1Wh7%ph6FJkb28+va}jsLD}5T}sK(kQhUzPE#F+ITI>|PrXwe!BrC;#xsdxEN zVw+eIZ(JFrBH?DS+9+ZfcN)(p7AxN(R$fCa-gc{a+cm)AZ)ZXvj zdH7QgszwyA@Ns*$oXCMoj(p8^4=bU|E`Sgjyz7w=kM+5{p1Fk#^w@WgR5uqw7E#b% z^(L$H@v+sBqfvA9f-$7Jzy0b`V!Y~nF0Z;Q(51R5NFd;FJ+dA`UZbGLRQZR%HRO2} ziL;n^7Ky8w*n`B~OzcGB2_!1~f|cKZ@)jugPd2KubHuqqSOXwE>rgSoFSHfi;x#a) z#A3_h-57AZuZRrZkr)J;9&j~sRl@fewJX%x3`A>*#Z~I$rr2g;3E}mE9|RWHsE1&< z#tG0yLUs!(yπ+C7jZuJJmUjj~SAdo|Qqk3Y5EF3$vx2_l2*Oh2P?rz-y&*hL2Z zlLoR1XYeLx-ZIbY5<-n6}%*iz_XYy!|Np(UjGKxHhfuz)APhK zoL-UP^d+#^tRpId%@#mQu^D^wAb@&V&DiPL>~Am|CpNOVu-*ausdv;>%)JD(u86DU zXCX11i8V;@(Q}2*TDb+3Dp0&3^%{!vWf=9Y+5-_4K5qAMnG4BrSaXSgucK^E0+%8o z!^!9H{QEXCa5x>5s&sF$anf61BbF8|p41Z+iXhLx+h{eMG4q#1bDfWl&58o+J(ED-CF3zI1Ru*_D1C zu?(92qRSRy88lgfcN0tFvZZlv0*gb;hazx@CNx+aA{|P83!pOX`g>qwuH?Q3voVDs zbM?6wA{lXCqHMazr$~s4_*|Zg7-2BbMS3BD>bjsWc0))x_|;Uq z3mRTt4q5^EijgQ|A|Hu)Ok^T)3KA85naWw9Tm(vG4H7$$nA(Cwz&eZ4d0CeQJMn#F z6}6v&nlsaH#udiJGs-*R-{&YZgv76u>2p^02PG6w{VLc+CD5&M9i;MGQe~9+9;kdX zU!~igyqO|zBp5_q8xj>hm&iLyj zQ9WYG2;;*rwMWvU8fs3(L}+~ty^(J5)5fd@TobFeEXARd?;s#S&#xZvhtFFU=M>(v z*2Cu=(JBsnr80is70reai+1mcb_8Fl@B7( zIT7ysBob3!#E+UPW1NN0rsBJ;GS!*M$*g=QGQ~Un4BtEV>r&#K>=g0N zs1Zv~82?=XBy85xDqUnZ{@z1@^$)^Lc-se=ysZ&V!n7&Z-kTL2up6-M_AN4v4g{8N zXF+uPUErC|8!LqnxRn;$s%A_BHp<82cM8~Xox)}HtQ&D_T zH+jjm0knzDSV`}fT?N+z>KOlw$%W4zV0~rrtn7nOGp1jV45Z+zo-|d6^`>Dw@ zW-P=@-@T23y6=LhIf6g+vYCzC3LhWacjSm_u4Aq%796?W@>#sj`yDm3UssH;8;2UY z=!)30LAwPt3Yidy+vSK* zM-Q-09jU^CJ*@pH#Y*?$?|4vyk9aq`p5oejI{9X;7y!0ymLg9vTwy7wE5WA~*d`Xb z6tqcLvE3{dxeG`;*e&8HhrYMsZnYjRg3s`q-$YjSp zPAnrKETQ59Vi^hX5-N;T;0JkiZ-i4uBFWv5DUq2>qR>Hir4?iBMOXl`BnuzUgR3L7{))5TmB<5Z$n}}Z#|QX zcXLh}uFC%nyq6qTBk>9nvlk#|-km`69>P!6llb8$aAvOnz4Cb=-pO9bo86SN3DnqY zs#^ie*Wl+bWXgY281mCF)_7Y+Wt*o_ABO!%XCxT;Gm$WA^5DHZXjAx$(ItDyzuCOm z=P&g6r;uOni18GN_wc7~G5-U$3Lm$J7g_L<<0H)#g%u^l)KC}~yep895aV-sA?6Y? zFvRe@8n3!Ax-yDCb-Otdf+~D`Y<1*F(_Cly)ji`^_l{qk&*fG3t6yDO7gi_3cnXBP zMkCy9iox=bB?c=I9=Q~uNBOfi$AwJk^c5i{8?k$l9?^mG=^Q=BsKUqmMduuedn0-5 zG;&9yUcJyf>8OR~JiX9-mf?B6=8>h|0-fgiLsd!I7|(AosCBv;4p!8Wg;Ol9W*PpodL!R-W*w1rr-S}(Of1*{|W>7wz+z%nQ(7=vPtg2i4&L%&6( z-_l}dTjf6hCt|f*{wWeYk(kZ9U6p?W4F;+V!3@)wNJXNRiJnMY!$d9;`;ZXtp?7BC zPt{s85ah*szCxyWk4p2r$LI38vkU0rJ*Obyc~2UIkPU)XLr{f}k9ZGnm9q(d;7^@o zUCrvaoIHa*v6Q;^_) zGEmP3(`D44*;)Y&Dtz3os8mFbD>au?R83i|=prPfGM~dU^D|^%tzUbU>01?rV-QQ! zA*J3%U2;?D5GOWV{bYdtx~b@x5%ggfgyA=y@Mn+LW%d{bnw}lrl-XexuwF>M2Zh`iuS%EC+w^LEnIPnQ6u?e}G@uxm8TbTPIXqQPYdvH5)b}{!u z^9tlv`1n}skmG*Mb<9HZs2lq}i)WtgsG)tKDK~M(@8LN9%9Qm2EwCG%d;n}`J?Rh8 zuVhaBFKBvB{YtEoiU=}&4Qv0#{Bs&-vEA$RocgWIsmCK6i&T0 zsBRJUTB!Ct1&ulV9-P6sH*WTN(ErE8OYLS~33?qTUOnql#GN3;UNeIe?m?M*k!eif zv(@*IyPp*-Q~%kI!tWtnc?B{yL!I*TkT{4$J#{hA*J1pryQ{$|D}hhQL~VXYqQYnR zA4-wjo+m4UgdP~DToL#sj$RS;L?-`R$T}k^`zzJESL!Q3p42xHiP?#^XMm|(d8j$E z_F#$GnaGivs=+5~50Z;PJ-VjlUQHN$TnrtCDSpMDIz`n#je58k;=6mY7}|kE88z~` z{Ke4od{U0VExjj!5OYZ5J;7hO8qZJ#7O!;q7Bh+4jzq6pw^jQ^9ZlyX8 zb7{arThN7kzP=jyvjEjOpS$MQp_1aUd@qgI3P(IvNlUy?EJj8ft1Z z78eIG(3_S3fQ|@bTrBh^g_YZah3Y!Vh&>bkEMAKs)_EYyD%Ere79E{CSlzk6Q*!(E zW$?)ICtZFGqv@2PxYfSX{7}o-gMXSoe_ z|0gL{J_IZt#ro>GKOe>29Q@Oecnxzgq>bq*V?nq;Hm`XCY2jaefd$6&&&Pw~aXan+ z%M>Fs_Aqj%x3H)8+1-VlPckEO^G;mCDZT3&*Na60P7ogMxQjhtqG$%&{G>fs$S7&V z{!j<<4lZtJ206xCj&Tv+FYZGD>_+{6_=WEQA8YRa z?E#Dbuif6nZV&E@{r{uiTaM~Q-A@KjQ8kS_0$AFslWNh{G>p)D7U{`~6IOo=2Gfq+ zJ0HWYH_TaxKbt>_G&5Cb%h$PCfK11%G?HZVpl*9Yxq89ep88L@qd^+7j3q7QbwF@ zJ<<d<`)k|?~(!(d99|sKBf8sYuX+w3ucuH2W zLr{N*b1i_BC&6ilPEovkk5r&9j7S(H6)A?9%t#L8nvrv9+Q=~cvXPU(n($aPnBt#> zS+nAXt^p;~0@k=;Oj4oG(B!z`^dr11Vp!Dd0%VCraJc>-=si1ba-N0yy2EFT$UiAC zG9CS}TIbI-?E2$j1xOl1L%=<04g%6N+?%_Tk7} zcuRcb5R`BtkD*jTWFvADBQGMI6nPWr+9(^*cx}x$ z0X+YTKL@Sq6?gZ~Aa!b~ZZYC^QVDuOYCcrx6&F?mY}|4r`F7)KR z6^PDY{zV>sFA#l``dp?y5dMz>(OK003NQa~Ai9qA-{9dd1JNM${g;QoMLv6FyBZ_) z{}{kKv}hTPBi#ZereRpoI)dXcK6{gu9mh6#ooDgs1a%hN30w>!oxg|j1u=28Ce@2R zhCvfoXD*D@z19)qBd*?T1+;p88;ZVI3%tmrPhy9DIC?c(ezM8PVfEY;j*eo>o6WO@ z|FUrOE4Fl{DeCmRG92ARd8<6UIUMDuNaI#}cxyPCM7-9Me`7fM8QpW8Nky%m+r!Zg zRBye>g#q^DhofC6{~sRzt}xmZK`T;sz<+{qIc5ZUMCq1sxss+M&Z8sdNfEr2f)e!Q z)ODyREw02I%Mu2M+6iVk(kv0BH;y$c1lmTzeaJ>AC#!WB)zMgDQ`4|0jMfsY466&$ zr~4Q&s2^mZEJ??ytMQxGfVM!33z3ffC(IX)Yycs)Qx%dO;dn;uy(kmzB-Fi3MwyHs z1dS8Jw`B(rMG9cn@a>O61oRDkhE56Z*eb{l{RESS@6dU{&`Q>DCrkj&aHs(C!*^*E zAIfHxci$@IaL;@sY#rWt0I+LjxVw4{6-AemrHArrin3ggULFia&xVHK z-byPHj`k(YQ1^=b#ApvTrH{uPiMFz~Obx(Ckb{Gw}L z9eNwJJHHZHcpokF6Y6vRdlG8ni!h;k76ATn59IJgn9u;Q1=lk-2{rO4&`S z%i$7V`49 z<0Bk!2q*02-=?CClppWOyHiEqMK?Q%9^R#*H!?rTD}TR=7SmqIUisZB`Ubqy>Ez|_ zRnZ}|QmU7~PetEn`KTvvKkBDxj`Q#V6^+7Yoiz1=SmU6IhS;8N*jmf>A5zg~+PR0~ zK;p}7(e>27w};AI48R{!&HnVEsAj3_O`Y z5LD4FtUu4=zs!ujLi-h|S4F=o&FC*|pN}`2(MREtPO-XhgzD`ag%!OUx@W z9HPX~T~IKgc!Z!xr=>MU!l(%XqM<~zEn)OlNXNk$>5suO31bRjIC&jCJ$*dlL_&!s z;BEBu^v~gY2`6X*UPez(?+^VF#%co2pGi-Djzz|40?waFM?*eB90}NLLVOT?8H}Ge zhs~J@&iF~oq;9O-;05uMuNGt*-PNDaf_Z6dQyL4Wu}2|@g>^o;kIJWI(!SSB{KRrR zTW2Rm9zr^_1O`g%$TdG=kP%M{lcIGJ%aj`Z&dM(jMeaMmk^*1b4UoXvW#Wgj4PWDfBzlYh{wLG?8fOYP6YAuoItz zCbaEErbNNJ;mHZhbneC^oE-u_X3A{Z&9Ei`zX05W-Su~@5x)@y!U-$5n<6xTU42?t zX{+aZD+>hKp?m0GtL6y`qBB?pIn!uQzXg=iU9nSG?3k>clEqT9j>$?RM6>H5CSZ>Q z2-s9G_C?q@spm2wtirFZk|8@ydYvioUV(q&ZH)IwQorwzmLZeWpDeUiE_x>^YqKCb z#ARzzwnj0XxLqSD=VTN@?{wlfW0P_z0>i0iDsK63{T>?+Z%FF>2gm{21W~KOY;n#s zQKOfgls5{b-h51!G=OomH@_L1H1K3iMRL$9NE-32b1@u}3P=xqw*az-7J90#K~E$N zV~6QgRSQ^RC^dc>8WBwzNdcYs&Df-3uS};U%bJX&QST!IWpsl^AJd>QUV}nsz%i3# zTr)nrLbIGeJ^5-~zJAX3s)#nB<|_VT$F}MDj2l8A?K%;PuJ#(nV%DE>)3m@FzyXc-RefuofjL zV1EkpS%ZQjREn^YT=%^+#0X)dt&v=>Rkv|RC8Z;$4lH0( zQhCV%yBo2&FlS1Xh2wt(d#^|wxBZ0XpkE{LOtN>zq2D5oMt10(Dxd_7f}wHbOw=eG z>Wh{|k~B&TrNefSWQ`)BzECuh!d(J5YALh|Q6Uo1C@nM+ibpzXl#W(&QJZiBio*__ zP$GUC1P7g-T;7EafZ6HY+iNA)l1_#;w5>xCw-kvnha2%_XjQs1U^fdELZCB{vj|(o zX~P-x7BV=~aoTY573NZU@g-Q5AAspN#R}6z0`pKd76cs|Si59_>LPudq6R)CAL;l;m=p*2 zo{O|hH_iw>-C%e(*BH)7y~6Glx`7QS(o=k9Cw#HjDc*!KoQV=Xfo)-P%ILTmCb69l zxjv0dg{vEp?J$IjJb*M;7Y`vLh9CS1*iSOa9!Xe9mVo^%2mzZHK?&=%$hSdBIDf9> zekQpg6YrtE4FBmUBOkANu7-q^jyT4`$aoPw(5Z==ML?efdVis3UIz)C7Ak(2PN|r5 z{F8AZM8pkbS*0?s$LNjgVDWMj1*uXqc*Gmhy#bbaDhj0TG}mYuv++;n*Jx9;LNOws zSRuy4H6TNeUNCBM<0fGhJ?=+R1mzojcfvxQ15bm3r^IM$%yuM&>m8pf$>=*7P3fHU zjd0B%7r&DsTs9tPh^&4_-xC&qt5Zi%0#<)={RpnUQ%OzjFI1zQT19Gflu%!e^?92~ z?aZA~0qd4_>KanJGzoQGJM}zLkJ}*BY3Z&?Wdvq0QpLXh1r1l&n z)IS2g4(lkP*94)y&`!O8)ZX)jdQ&^~8d5WO?o7a1)lR*c)IR44bxJ$+J5n?G9iV{K zyPf(sseSJg>TkBMLp&U=bHC?=`k!{{aisSDP^dSyQ~Q#d^J9DGDT_cIxJIbU+o{27 zPzPNq)be&}CsOlo7Hao)YA;fc-y_tYO<#wBqz-;rsL!@j=drdSUkG(;J9P?q3sh&e zcv(Aj9;ri9g<9H9Z6tLV&!-4j-P)-uNgX~$s6Q%ShpR9zb}pPP)Ti62Pmy;-vrxCR zQ(q=^0!~Jtb7mxw-0?*{4bj2zK#eKo6tu_XuvCPv{Ivz&edw+%k4dh&(1P`oVB43jDu=p&$0zH241w zd&k7Oe%ls6msnmwVk-x9K{Vtl*7z9X!BoFH@u*V47I+3_sG8P>Q)^q7<}O>hFn4Kf zYeQ9|(Xgbtaam1mZezoeWhn%3qe zwb{B@RcrMk(3*06X;n*`+T|dfU0=Hd)m7&%Y-nq4S^9sZ~6yg@nDY@TjW&LXtlKtqs#LE09z)>hTbZ&*^-3<3t| zlIA7ZRc*~p4b{Lf5?(%P59RI(e)d2*%^M?8e5y`N&52 zYdfu_b}5pmprv_f!;1Mw5&WbSYH0K1H8j=gR9(x`wyHJ)7H(~>u3fscxmCl)hNT|= z(v}9;zIw41Jb#(5?=fU8P`56-v3W^72vBZ$m0xR9Q@di&rlqRhtG20WC3;gAU(#Gt z+f=o5u|`eH+GZqx%f@w8Z9qlICv@Oyp+QUnow$#sFjL*&0R(tftxXGe9TB~XrR%Exe)_T%fS{s_@ z9|aq{{;RHPsan|3*wA*GCmC&QS=8L>E73r#v#J{CD$wYZWzB6>I$3kd!p6n(SNO^- z^I59#7KY}iZuMPdN!`-<_4lunIewT+&6w9#9tTC19L4t%Jp5lOg3dxya9mQ_{L?~nn2 z42*$O8>(yDsuucPR=sE_axt{haJ^D)n`~u4scd{7!DDt80)T z0|povoLFgM4nm(`q58g3DcQLLUbQ;p@ZTS-ckLY8wEn#^$5z(cfzkoi+|pbS9v8yC zKq=C@SJokOUmyqj6I4u2%vRg7HmzcTZ|%C=>;W5cb8Xw&46eWu5Z@9;JEk-yudKel zzASq{R=Jd{i@Dy~w&oRzU%!UM&#)-|_tg}ChSe^9Lp{X33#y2_N-{*8NI5-bt5qdJ zE*2p_niO*W8VdQ*JXXlJzL2y34?=dXdj$nw5FvM%IW&U?yF}svk+|!K#Etc5T0gBV zwa!;L_&3KoSN}V}I$M=mf2=K?xS_26p^f#qd0BbZZ$?fT8nF#Bq!BNO7~ASpiZ
s_NzJ@CK~`Pu2@&PAusEv?A!_EXw#=gXqZl`@52+lFC9_O6SDvp18rfX>AVry=-D`HX2=)ox8zn_ERbc%{tw0*3a$D%A1Je zA|DjJUlhIXjjij?wmu_z-+M&wdQZvgHe5f^OImSTbjmhktjkw!VM7B{bCWn}dpbAR z)3e!Efzl1R?0`#GcpdPu)IcxF-C8EnN@J{t*46dR&(330f;~3cG1f23AIyEI>~&Od zW^hYz#0?;QvpksY(asHG&%vP5^7`BfWw~X+QP!VpgZn#Mr{&}vZ>`M9@0**eEsYTp zT&*>hUn_Dt|Fs%R2Wl$Y@##wJv$M7Y#3t`cL#~rXA?-E9x@Ijq_34<>`T_k1Sf`a{ zqsQwH`yi3&RXvR%40H?NFi{QOm39bejX2Qg=T zw)Lcu1Ajo_x1}97OVoH3Y0G-Wpt>*FbrUz_)_ebhpu7EG@#K+UQJg`iA~m&$^hOsJ<=gLs6#Lt{Yb6ysmpyEFB|G1lPWORj{xuy9|7{b|Bx& zr?Skg9atXehufR~ll9Ho2Xo8H^0E*Fb8>XWTGrKQ*9)hy^nEdPWo2Wf3rk~~te01B z$<5a7{$@4vuahfQ8-VJx$$~C7Rvg>u3x|lPjVCVw#=LStYJ?0G5|3M6O*#bX1D*bx9sTww- zhP<*x=*9bdcX;%OJ8T4fmrviEa^R83|K2ZjW=zh>S$WrO*kCQIqp6c}@^nQp*XLRX)&|o#Io4EKe>-9WuQy=#ysSNWS!fl+oF^iG7m;U( z$ls5Mtlx0`hBM1_i%*Z)fc`Bj+v|%V%FoT_SoyJRpmqD|VBy661IBTL-`jzWd`8^; z-VUehG~7Kn$8sKo3vR~z)txMlBVr3g`U_P$u|7Mmj1jSaldeU6t!LM60oQ_3?Y6(E zI-oNpI1Oj=1bTlFQ==$zWKJ%+a1wgadO+pCCCl>a(a?=+nfaZf?Ji=PvWcyPx()6B z<(6+On`lkQv4-UEw}5fRw8o>5B(|&-LcRb-8%b<7>-cY($Mo46C*_858D}ADZy-?Sso8 ztxhZ-4mYl)Esq}M|Dj#wL{B#KUjGmJ!q#1m_R|edb|(>?(mo^q=FLub{?gP}(ztK6{r}t6Xy$*d5L?;dm-x_pcoF;YRlCEZ~ zAj<%N=V1hZLX81U9B<>V472qQ9r?}(M(p@+9L{PF9dUKpMdh(O-6rhE9Y!9^Ws0I| z`R6(RV0FOGmvle;>at79FCMmLxcTF~E8)Hcw0jqquNihx@g8S+4ZSyp58-b((r_v6 zS06g&>ar`!FCTW<@U;hAdf+7oT|8pV!L^4@t1w@fqfUc`y}RP-vbE)x4!dOd#Rsf8 z@WO*ukFZ()^v3;nrkkI!SC?I0e%Y|K!!JGHk^?V3Xw8TV4_bloEW@Ir}AjRM)D=Q-9Yf&$qa%Mga2Fac?0+M;@~F(2jS^`KAAz*`6n4E z$CIDO`1ynpQ|n0MZxDf_`DwnK7#PK zo*nM;IX=X?7``G|FT;J*%NbVZf~VLagfs!6*d~rq6Tv_aLhcQDNDj$|{@&}kfg|6T zj8bshCkCDHZ2LM!O$48dV-Q|QKSKj#f^mDykn%jIpRy=UM0y!gbm&B12S&D+W-Q5q zds&2;4*nNjfE572iM$^nY{tPVMQ+7W7A+MkBf|;aPLx{i=}2ctfmiHggk#vXV~XPnlh?!B=)Bg%~!nM5QtPMnVoNyPiR zaNxU=POq8MnOvdCClZyD5BS|i!tcfnXz^|n@6N#UkU*S)?;hjyM0t!x+T8|%TRbKT z**IM8HK$mL6hl6<_}(~)`Mh4nIT~quHvS^s_2A-&7MlEeWTeiI+?o)whWE!>el#owcsn8B zD|FWiG`(?h%&@5Nik+-7&vA;)z`a@=$avx|j$RiPp*wK7$DA67rS@!`cnxrR#O}t4 zHwYhV%vS?(hn<$ZY!Tj49u+Fdv84|$!R6XR7=bvu|EX_@@ccV)Ao%H|M>lRE!fhnQ zcJsFle#)XaYk8lKKz?;2rQ^CocSbD{tq{}@`85W<_)U~w);4wLRZNT!CYsGDSZ_1Ka|)A&E;T+p4mtDi@vNOrukx z4EO_a8DJU?L!L3sNxvPZDR1w>VLBk_x8ve67Edg;r>|SI1nk0rl1O-&zb^JV8gA$^ z<97V+3Anrf$FOLCN~QmCkIQLR>=qN%eww_y)k0|?Mp~+0xA1VV!hALmdUyPy9q?*9 zWES7O8%~qqwdCEK;BY$*w3{VTxzxQVmHD1ma8N3f?5`*5Iq#1gX-RT8z}ty>{s!*S z+3Gn@K4=%H=R9%G@h8w0LqFwF@ATl8c~~=8j(y|~{R|CoFWiP9tB2N!Qukt=V7Z-!gLQ(e_VbY>ZB}p}8@`Et z^EeV(3!P?|Q*0hsgUfa9i(nv$TC|@q=!1(j7zL81Fr1GHujTzmaNxC1>2@MO-lcO{ zbY}5xoQXSdXP4b=Aokj6oa>2@`2xN;5pviu6In0{ces>epDf@b({V8FB+YcmxbuD; zjzp5tX}&qdNmg`f2ueNPH%p#+lQZAxJuLzs@pjrKGZ)y*Lmng0~Za^Ku&w)+v%^=wzMZ{pWGuX@a*CPjh3> z(dM*(;35_zJmDVW@*cryq}^>G++!>_7|h!^(0e>0M4JIr<6y+dIzJyna;w2%(Wf`Z ziV;08#erB7yq{2hdAH5(o=I@u$+GCIaq#3G{L|E7`Ecz5gIZn8S z1s6*<^29@n8^dOJ=CkF|a-+W?mKwddRltFW5`H&MhxPA8X|cG+QQ87uKg4lhblxMZ z<2-jSv7~tfPCIZQOk$6nHZyKV;D9UP&%_mM1k&JeONRzxv7Ihh58URb#AZKz1n|e> z>|BZvdp&UCRy%E6jp(n%fmagO*lFXsBM~SLxDwCUX=BLdJK*UN^VmdiCsx{0fOptw zQ}9?oELK~D&LSAqVbOKF&ky$-C++el0NA+A4j684 zecnPpLqp_#sYAb+ZWrN5elx4tm6kT2HgaqXa-{8{l*=4r|+ZG8`eG=T{79VR)l$4Qh9rlTLad zI58q4%vS@!a1xQB=U#JKNci3O4Tr;Ny4_tg1GvjiUjg>`X?O`e(FY6#s{s1IDLr|J zi}&@oh@rX1MMaN`g2&N%HdzpZ8?=4Jf%5tz$-p5Q{D$$m#IMgknA9a~^!Lmj7Rdm3-Hd z{k)5AOK~98_Kn`ejcaj>AHuH>8I(+k5PX~);eps8JQX{H*Q`UZwy|r}M3m%4@DqaP zE9w95MTK>!)@!YiBiN|HP}cm9_ZzI9H4wa=sB&pIb@^Sw@5YVU-+z`Hx!#T=sT77? zSCOvVpY{7V_9eg8yL;vmfKMkr zZmjN7aH_+Bpb39CuC06FG{PQeAe!xT5wX-=iB)#GfLMov8d><`X0D1F zF(hid+^Q$Y$NhX1$+-gvX+j8zejmY+kim4?WlpgSrqfI2)JQOpgsdBl%jxFSK=|GG zTNyfoV?vSdaGxOp^vxYs`FSL_+QWI=iQ)YM4n&aX#ckxmBLICSGK4#i4*!68B(Am7 zv$+xMYV&yZdSHW{HV~WbG#1Hx&lVgMAf!LEFuW+)z7OK|b{vQjvC0BkK%bA>X#?T0 zi^~HyFkNd=T1+r@Hul7mf<3jE;9Jc-BoFtC9fbq$BBt5tBH}c6odGnsYj`HYCBubA z6Aj-u)U`yN3SP^j8T)ulesb_v@-VlA<*WDWSo-qdwLF>{zbCkrJkE4t+|7}h$7J2F zkMgK?WAMQ9@SPz9*XM$dQtdAI`QO4|5`++v$q}Cad+*?`viy=nkBCm!;3$t)#v*hL zzHcoK7%5kg*W3AuRpE2)z%`3%^7VB4<`94Mk1>g^J_2mS5&tDat$-`u5Qq9vyQbIcp1_ab;Yg)0TQ7wbdRku{t}h0biAPhjyFykobARLf_Rm{WB&u@;T3aEBkrns7?_8*qj(J-OCoBSR3Vyx^K^Gh zswJK7!{r=YrcyqCk+G+jvyyJT*)*KeNvC}FJbLRXag*bDNk^`1g2#)KZf(9g&}P}h zFSaF6@OjfdKJD$CEED_f&!#6&g5Pf@9XsUsy`*DTPkTE&K9O|8swX(@gp;5B8fW_K zS8?iJ`#(6dc-q^CBNtnHdb*QIrqih)SkoDohbV7UTEnnq*|E+(aUfdz-u~N`qC-v1JmDDh|a{oJKb!dXLK&E zhIqKao$@{Hh49S1a^l+1=%=`7>+8?8bt()_NW@~!e5RutYsnCiCOBY*Y^tpX3)cn_ zO3Ofo%1?3uY*YbrVLH>=-+}e8`CK$BzC;*(E2FOXnk(_5+i zvQaM_G#5L%qIixZU{Afc1~~dLpKR;*v^^Vo9alr9Y~^pnUB2zi>R3M7iR9IQr;EaN>)Mqi@m?=QguG8g;y``fXWyDw7+C zK0`NbB9)RGgX-c_+*s=UC$OMnVY016PWAQl6ryv?ZAB_xpq#R5as!-)IK5ipWDg%Z z4!$TCvCKR=9T)w$imq_i=q=sF>Vjp_i60xjv$-s9&vsEN z7NVI$98gT=$%zkm>3yscxo=|sX`V^!{u1XbG5+SRDdEaq{TBq1<~yS~Q?*h%)!u`e zRIprq4UTp@S#&;dihQ;ey3E&~5vIjEJZkCt!l}X4-o)L~Y!88SCg0YV?e$is60U6O zv1l414qFx^Uv%%shTM$Kn!!ei>-T+ma8wE9ENdm;v$K(8*jXWD)n9mxSUq= zkOOpyF0aK2qP_xE8VUJDUec!poTwvz#tn1pZplHA^d;l=>|BU5WSZT#4;+2Exl|^c z+G-LZN1um>_Llrg$Wj%jfBi5@Pd|l~H+sGE=s!_@Y{P|Ut2uXJVLGF`ZI%K}#B|n7 zB||cbPoEJ&PxySBk>JOo>O!1)Rd~D^VuTX@8Js{6WGI$@h4VsNdshov2>wFKGOfCg z_^U`O(DXsiiXOtbyAMXEETkvMlIWA+43D+w^cOu}g~%bhqqA{`3-l9T!=0dui}|C2TKv+M@WWp|dbl;=67A6yHvDUcOunSe zZ{pHg;@|3;>*SMfnVEKfbdQcY%P$n&i=ZCVbhSg}t3ol3u8uEjTe{k#&&QYZ+uNht z;;ThHed*|HxWtMeJeptG9Ua~t0&2q5cZye?2=<4#wA}~LfD}^gxv0J)IAG5`I`EeW zB(Kb4bPIee(=!m`*j@Z5MVFSozLu5vl~F6-EnUc^G|r*Rq1mN!gtj2tp2c<`**H|h zu@y?@sc?Zm^deHl=Hb|LW5*!+`-@Jlu8o2P%pZ)tihG&CwoEUZBJZ}KF`(-7SKQH8 z^h-D4??fazIgr;+l)4n`-S$_p6!5)2$Cim)9rU`KZ173nZ(U+>1HOE?(Kn( zNs^9$59`p^xs z4PK(V!?kDH!sQmY%K9<=@a$VsAVU0=1T=lA{#?4pwXtP%S(zW8mJ{8~i);tWD^wa> zpnGW>SD3>8_2AIil1q14G`E=(djW`#d3q{%k|P4z1t$d4(#E0_9Xo*H!eDj%30&i9 z02}hO#;17d!-M8-V!ESvjysE1+MQlxJ*&uSTymof%5YSRJlxP;{D_`1wp#`s*+D<1 z^O?~2YkXo4T^y*+MiQr`kRvrOr*%S#*nDES{&l+u7QZ&qSS{Dn3RX)*OEh z$9*^4hz?qX&KR{ZZz$HxK?Y$1mFN<Z?N-{BG7D-1@r<0g`kSrf|1aF_$oJh#RDs!zdzvCEohj~>RQ#ZTn}1~xeOra>M- z-RO%>!ySZhph`UR;5En)ORn>;)mh>$jX16{d5iyT24Q>CBs~4L=!qs6 zYdkWLA^B+8<-vROvCq0Z>+C@XwkQ>&Lef1*(rDQA3E#1ljF!kbcA@-Aqb#9PUpVw$ zbl*A;B;lL;9z}nayG6xiess?b?iU{iH9UGumq_2}seg-aAu*%PH|la_E}PCryZtiV zH;`JEJKX z>}#=j1+M#AEVyH5(L_b-TGD>OHD^Ub1%Fb;%n8gtH&jeOqQ-^_{&YEHPA64VNno75upedWl{-&`;P8=WjmH(Ufj(5SlbpY{Jci)_P}r zX<93P9Kr8WYvs=@_?2m`TvJihT2CAiZc=OIMz-#?iCQc7o-GPBZpvM>7jW}*vlnpJ z)}Sx4x__xFnRfxnY9BXi(fv`2+fc@&C+=@Rncakg zv(Y&>`wkp;;Rt{K+kHM0q12AW!KvTjZ#qi%3>*zOnsJ1`Z8+zg;>U4t5_0(C57{^1 zXvV?$xZ#h#*nTCBbvV}J2!EVi$=RCIa7@P${+6KJrdf`0a0XxayC3J9ad74qXW@mv z|7-WHL&E3Q*cCX&;h2CU{LOeTW*gyXz|o8&{BcfHGmfP=(m28&r@Dk$7;n5UxcW~L z@6WyND1?J!DGtu52!EUfP>Ev(j%pm?@A=Uve>h&pu?I)^_pP|DYFAO~FWFOFxvz&=;2B)y%nVE!eO$W$N~v`UMrUDk{fM z!7f(W6oyZ&g+#xYePq~`VGGUVxM5>D%475iy^w)!=qM@dW0>o)PEOtonRpp{s`-8l zBEod*Paqgtu1gJ%(EIo!1Njx%g7s?J`+9JNT_I@~Mjr{PKl-y6XtJ;AhheQFmq}Of zvuOG74OyXXa>U6#fgQ{gHb9K(8&hZ0G}hPDrJ94^GIGQA^9Hk(Ac?BPs37)o7|*=8E`?< z%+%ca=9*|?IRg6SbR-$O={Ns`q^{mENHB$j=0}0I|trzY)4mcc_(tAE5jahHy^fcGCnLZ zhM3Q`BJ(?u;oKhWgnuhx6Y-h zg=VD&6rY|p*vYazEp4!@bYjqm1|@W-?E8n>1JcX0GMYzisV*8@qkL+4TTd?vv~-3r zcI@La%;Bn8&2tylq^j!Y*PHdTXzoNZ19fg(-u#wx+TillF)yi`t4KM5Pun?3nC@I`qjf0mVWfwn4@ftI zhWW$52BMzp$#-Qky(|y?T^QVKv?`aXp4-@b76#Ju-Q2gebUY<9*qep-R1V`;kdCb@ z3m8A$$54Q{VKP9@Q?;Q6b$MY`<6M(CmP_fL?v`xM-izdmJ3%w+<|FP+^Jh2DZ9KEY zq63>>?>;@Bp?ZGlAiB2&UeqDlF=&O9=!ba~C5atr*k8=tl83DhrV}gp_#&g{38V(f zbO)`fW=RbLW{`ks6I=<)T7Ql*#>S*!m9lhWu6W9~A|p5&-3jYdly70pW6RJNrL5KI zg9*#VQ8Y-#Q7}{|Siq4&iNR;gs=%-S9+N2p7D$>P(MRWw#67tjre>fDTPGCt!0IZk zXpC!~T`P{q`AADF?oc?qL{WfwxJkPOri*m8^2nqWFbks5%%J^4axTS;=?z;_qbbm!5SmPH7VRA=&LvT$K&tpOkyeVUmcErP(nFe+ z$WB-xeJp{aLNFUrtkJ>%n`p}lB!@LzR><0+S=d-HW@q7diHZhU<`@$U;kH|=-`mGx z9fYshE3D$vW6}i1=x5u^C#O}Rj;C5P*cBSRSd+sM1~Mq#X}^kx6b50jHj_~{WzA_E za`=#Bu~{^)s_~4}yt(zEcN#jZNMKHz;l_K`06`VXb#+@UvC&o(TA0_oO^`_R76}!w z+aly6!x1Lwuq1~@tQ8hFTB=#GtyUvet_mStb3KJ@`%1iXMW&A}Laqm+D3Oc?7+yuX zAp=x)+j0YK`4y21wgRLSw#R3vu{D-;&4Z3-3ZU8XVH-F5o1NcgT%ozeynq~=R@DS6 zj3|eFj4I>~GCoXZ(UgsRXHS0@^cQbu`g1URr&ArhsOc-a85NF$B?lkvK7LBqVw~~} zOfQESJKrgJ0<}oNwDq;+BS@ppo-W7{7fM!|(E=un^)^F<)_)g@J|ciBLSZNkk5ix6 z{?(`E*VoOhuZdiC&z;{ezYfZ#L^#8gtY^arjnq_$e6$?7z;Xa%dk0!m{1`zlj}ceu zLC{4rnQmxbE=BPvCi;E+#Rj3FBV&Ny#TISMj7QP>4pjt|HQQsgsXf~VLC|fDzw6K_ zz56kjS=F(<)EOlXIQg8nJlh5~_Rzo4QmIH%_^<@#m>}s?Ujg+iZt~~NuU=4B6Kklb z1aqPSnrc@-t-ZDwb3O-#i+v`Hwdm-Bv}L+5FC*3ON>b6d$S3e&7+XWNMQJp3D%3o; zlTldMJQ#`+Gv-1p4H>9r&2P_Jry*f_wk%~~&Y2i$H66sh7jeY6daFqn8$+Z%(3v$G zCG`X@KHt|CcNQQ$O*c04x^=-;<{=uOK4$S7QI^t>R3Y0D;WR3)HP3^oK3B%kB`}Q) z<9}AAy#s`z-P(kS9GyYD+wc{YMVrKu9Iy^wtm0|C5RP`mOx&aUKRT)vuw1ebv6VT2VR=` zTit~Tz=qLAlM=&2Rsy|wZbjSIN4>sNUUU(4pf_Fg71f<^53SQ4%3xsM?28cfjKMfc`N4i{oQjz zuN*Rit*||r&80ICE%+&sVA&`RQCREh-a0IE`41JiEou#MDb7EpuG5E}zDhN!P+K=j z1=0ikCKP-$ES#F8;b)Y#zMk_?3{dDid06_9(VBA0{xd2}n3HB|pqCMAfL65hL3*R< zXl0bV^T}$DhOA`rM{Q&C+<7&P%<>u-Q5u_}y+e`b&!s?bMz^CY)z5zYw8({unWQ9& zP;Go}owvCCD2wRwT3dv&oM%QBAho+z;%9RTJ!mvAJJ}{5YQmriEwnQ1GFzXIozwmt zC%t;%icHHJU{?)l1IDY`+4fVvm2PCMXD&kp8TH-_F;+oMEI?&d#qWfXrGS`W05zn( zl~ZUMEdw1vwX(@$8plRWZf#4$2oU_EPGWLFrll`JzXTQ!SU9Kv zdxDZ_mB2jEngZj;c}Pkqe^$bM0$*ZMTG7@}KOc5180KnWXF%b0X~P*ZY~X@v1H!2@ z3yrYAK3z)+T{7sZC^n1_teVpx2GA=UK*^AOqSmut=KhMX~VW$3!cNWuH$9P0uxZc8j}F zL|}139xzqAFpAE~fIc3+33AcPv)x0ABLU0=$@~528=|@Mrj~UR^{BvV44K&vs}QCj zv|}PC%t?c(7W7&mmMwiyWTkOtFz_CSY!b?Itru!SRvlC1W?PC$_ZEUEVA};X3I*C*S?ig1x15XQf|;=k)!KT;aXQn8Ft>hTRo&cb7SMUL zA~AK5rnF)srJ=z{O-l?RZ+}(T2f_#>ClUvD+)+YlTt7Vm^@*WSS*+c zFpK$`G3z>8N0DO!@CY*t$3IH?I(4u)GjwZ`IZcKiYZ?-tfDywihb(&D1mF#R656ED zBDq%Pwj!&x)WOZ15tg554gqEqFkSXLHyj_u#?M+d%o;%-IGdutKo3UE17w(&qrN=) zI5P5h)7FD-Up%l8s&isaU&Gw$=Cc~m$wP@_>e(k3F!d9!N~>^*u}i{+fUGr@G| zV-Pax#*_HY>+-1(IbiCo&ybF~U-{cs&}2B0RGOgH@OkcCBL#-(tTgeeU%!Z&tD4TJt7(p< ztZVT;o7czUT%ATheH_EYSGzeG5rS$9Z8(eySsjTxO5TJdx__3&h#6&o$$2vy@B@(_ z(BExPk|s>E{InyXvAPILBq||~tVp1C=K6w8%l-q3E?Z4hAZ8cjw;5d2xYAT^U~A65NQkOK_T>KS^#CiL{nkly~;9WMhm`jv(CZ3PC%P=3*g z$ymR@)GM3g*93_=!Bps0swAw6eK4hBJ>752UZnl~(MO01U5Hra$j^qpGqg+Amr$v(R%d?0S(Y4yl% zL;&xiiH5_9u`wlGfF%V|EQ=A*G#780Eb&O$2nKaD^l19CT(g(&%tGzqKm;WglG-G< zjj%(K6zzv7eq6Z0eDHoQ@&+q@`disQ?rMQqp86HLl&!PbaLtt=EdX7H36x|w=7AVO2rPVMb$MGM2kF_@(vn|!%T5E<3 z4Ss5FuC6U=G<(Fk=nHW0$Fd(S3i1Hof)*F$7<0g32WI?T zNB3^6chFgA@YM<31bWG2)=#JdEIB3Xk05k%{TSD#K?M5AvMh=V7WtyWa%h>0V^J&n z2M4@vv8nV3K}1-BU^qRr!rtCfvY|GhT%zxl==i`A$-blw3PMI&S5lo8syE0}^aYkf zYSTjLQS>^`yulAX!f?QjlaGYE@kebK-$+T7Y8jwFmMet|g)2KaEKz0vDi$lBaobkt z;~aHUBz>tWyEB|gfWEztFGT2$Q8Ktu)fy&rXklSsY!RWvy#BZyFRE~wT49CW#YL6$ zKn$~+cxB@)6Q3ej7}kKO0>&4^Jz%8>Vl3nI~Cqm!NA9LPzMHm9e z8+aRt##@-|ek&=sT;1r+qC01&UTl%QJ&J$ng#7MhkXdF7)CiX^3`eP<6~t%em=Z?a z1bJsFAQn-!btXG1OeE?VX755JvN2H;ASFwMp}2W}o5qWH3JDFU-cYW{M@=*-#7+K+ zW=pRr=KH(|yYvbJ7J9l5xi&6z2B zCew?}0ptpXrL5KB_#%fK;EfXjii>#7R@t5%pV$ z!oCJqDz!z|`ab;UD@APSdx-$^d_|w$y6~{QLH7xZY`vX8uikWmSc5R@v`?Xz9h?0| z#HLAWHCiTzFka>}Rhp{K@E1Uvj(cq!*Fqk6 z>sBTeSHmPN z2iws|4O(xXBLr5fkqeoEyP>vmNE#1u!k^h~F^EWCZjQrbCM+?7DFq5z=!|iQr!$9A z!_>0^kJnq-^#b0gqku}Xh;DU-`g*K~cwOa~0v(`slRCPv8s=2nYrm7n6cO#*hbxq!y z^b2ilQh_p^g$*v$4~l5aSV_UifH^I&cB;z5K7^(d5)Y~qiiMT~nT)ZOcKOV5w`H(` zvChhB%*h9^0qG0TV5%3%?i(s+J37SBgsIp;S%Q|-3iWoD6}$d0Cy==twU#(8G^->E z8ls0(ngo?vr_h$dDO){`LP4e^1Qr&z!s3nbQ>$Op*D)YP%>^GD%urTjQurZ1$S&BF z%o<a1(+KFbMey6QPAnT0gTI0Rv;2U9Fz zOjwqMmc)z=N+Y|dgKPkxD_h46DaC#`ODneYuu^U18#!OJvGf!=JZ_ke>htizN=~Yu z$TrMsWq$_)Lv8(0iy0o#-m+D;_Am^&`8XRY9rD6wk9mhOHhP$H3i(NOoa-#T>9#>z z)NO0oGSsSNj*c~jgi;z$TtPn;db&3w=tkJYI+?_MTz=VkCecfF34#=acF>;-eQHW0 zn2Y=~P+XaGQO>#$GQc$d{~@05gMe!UaB)bE;t7 zrp&aiHZ*Jw`9N-A`UEz=@N&5nA`sR}_Ma;?HTH*JVFrXqxLm^8jwroI|hM{CEu<>7d^HN7&#axoWloHQrgxw30<%tP6O zT_BGMKHN|xw9}@AVahDO&`Ob1YJI*b5uD9Iom6gYajgYcFU?2WX_@e%4wcXr=32!= zN}@I~l_T^fxOTHGbbv$CW%ghwm5{?2V}cRh3Nzj*9TE+?mDgm~s$?va#{9&huf9xy zV!XJG3Nqb|IFMA`E8SXwG=oW=%dg`(gw{|;5?81;u&SUt#DZ!BQofJyD4?iNZ79GT12QWBOq@Q-V)7h~ zB8MAHn>JOxxD5hwCSFC1cyTqr&}EFMlt>KU(kX9-3r)Cg&r5YQYj0?+*oMb_k9k!M z4IEGQO*quLxG7hb0hV*_Dnr`{d*v`3vjyO61pS_z? z4OgNeH3iygB2&!Asbxr_-Omb(^*JD5ij@cEOY~x(hGCV)3cNjI!!@Dvk`Od%TA3~b z)}Z=8I!4|y*hXg_?Q5Dgng zBI8jO%9o)2w)AzF;fqZ_i%4%rUvIQx9;SN4V-XxHR6hqI0X=Km2Z8z+-;00Ng~)p^ zFm?9)dY`D8!n%=pO;7{8t+9S>(4WQ9t-j^#ke~K#7c!kdxOm&((LuKmaqM6<- zdv@qnLoje|SFzQOo9lRcO_fMhuliKO{HCV4T))RIw4^GN7Qw=Is(ngWf|1PzvrQlrI1DPXO} z8(gYkrhUN_FHUA;56Bx7s3_Q*gi0iL$%Hmp%wSGH3Zsc=fKW9}2H5;0=>FK_2I3!j zhWAn^-)#9rP%GA-10GrUpuyN*rSGFe7T6dfD(3yNzTC_jj! zh;3Oa3lKudt~hU+8OXFJG^CKrP+vOG!;o#kXV3YdEmp^1BJdz29StBT7U)fDs4R?_ z<0DHpiZ#j42?ltRY1wLPy>Dr)6sKT@Mk#pMv8q-eLaco~cL=GcvC^8o?omQQ7dVFptj(Ar?!%D1>++;X%| z_n5Td6kuBfWYxwSgs^s~SeB}5W>+n!YlZ;{%~a?LvXI+^RhCAKktcS5iqQE$kJpQ| z=|LuPQSPl)!>*Ba`D_cJe1VP+tFgX%twlZONMO7zAuB(pma{T*(Fs&hnmgJ}J3zB$ zs}dH}C)Xud#EOPDUwg@BOLf?G62bb#-pQ$Ubb>MP3BxW-VN#CpCP;H1jWVU8I5_P& zw*QUo(D0%2Wjd40M)At^T20vvM!tsmjm=m|F=uWQmR3`bRVS6E78}?t^eoHdtPO@p zScz)qEgxDm2prBEN5KzmZ*kb(-W{83JQt*S`FBwL@H4cQ6a`j|t*UBZFc@sj7qYF` zd8a_BpI@zIF-1pUh-(16Z;8SW8ylw1%K!nP5AhO~Z?OQg z+)Hgpju=Tk`vf7zm7QlZviGUdr_wU;1{1Ry%Y*^b(!o2V$QRRIOyz-CE?Jmot0HNo zz`-HCt{!w!(RP{n7ioljFKGfvLx0CM1KhrndQE#?CNMWD=GtMaK;pq1Xgk4LB}n#z zhbV{eibllqgcIG^Xi@wY>tH;)nA0GXn~4P;X39kJ@sq5B874`Zbu5FCZ?qaPkl26@ zS|n>-y1Me2%rb7Y?NQ~2r6!n(CpD27o!nr+2P(WY@f__jENj#cm8+P#uJ z9yv0A#f<%6s?;hkEZNX6VV$>Fb8=BovDg7tSKlqAPz-X|%GY*-V2e$YHkxd-wtORs z8)Z##{if$sHVs3mO?fe8%6ionA6bl8lx=fVXBh*3?KR zz*Taa0eD2NSjqQcW{8A%+iYk%Tz-M{=IAQrf5rw3SkSdH)W=C7M_owz*tZXs(Hs`< zzs?a?Sb@DHh8YE(Wn7WxeIKMf=dNmQKiV~TMBfBv57S_*2wLe014a3LwvtC&u@sdP z)6LGQLXq#>XRZ;~xpP<@Be7IdLUOXb!3@uIv@)AvZ=Q`pSU5+!l9fVl?5VC$m8Bkv zPN3HnT3MhcK;7U*6r8}X;%W11g3e3{;tG}{{VUshv2j{rk5*Bn1tbsr^ zLYua%JxgOc)l;iXKK(^C&Ij(WG#$-nY=4BA3Q`P7zNT8`yPP)2)`a^l0%i5aX?5yOVp9v}c8{o7l)HoZr z_YQ_@5w-@0;UQX<_pMc&bDTqoX$nK9`BaCSV&Wazk>;E`=fmAaC2s;o$g$^d*#E;T zv9BzHd}exh!LYH^q6m+d0B|)+*fN=s@jQj9#78j+lT-eJ(E|Fqw?=Ufz;`U9s@uz6 z6MEUUDFU@xJO}ZCl!~jDS|ppBj?&}vi)fs(qUgJ&_=G|Z`(s^0VjKxJS15k$fJ&V* z;{i)PN7uEqK4h9H)ur~3d>4ijA*Wuy zoJ^fcp+KRwdri0Ddz0=Ert$ngGlh4yS;6CgA?Hb1gKpD57u26oKYvj@!b1u`k?ip$L4*lskOWd*^Vmd^L{ZE5VOPlw=Y6ISbdX~ z9@#=$Ya)4?7Bti}Mw}4KT}n`NIfBQ%Dy)T<{lup?bGHnLFii8a9v;3Rt{xbir;XG` z(m5JKgAlTiBYUYXhUk-Q2ZAXgWOY25%w|HM|BUqzmcLA0tVEG|$q|U|Dx2hBVp3f> zH*=VObnj@)Rz>5?`N)TmQF=^saN7z7qfw$^)M^BC(YFsj;*;kb5!6!4Y*=zvCHg0M9$-i@X*4SgzXbRQcD zy|0dn2DQ(sIK%?`2<&lF{BhqV+KWB^Sp^{Cf~pIXIy)EmbPjTbxsxy>nRUr!2=!yF z1LO-diPxsmDvwxZ*|)I~~;IWOlH8Wu8{*6?(Pg z&V*z=^|eB)_fTByqP_3TVjFnW3v{lzF%?XY=z*J!842loBzK#^B@=I8pV$kDTL+nH zVu@+Jinh`L4j1M$sQ8$w>1>IeTTQH($mSO&hkVRpOM#8v7v^8LA^M6ur???NYbj;k z#dtinv6T*rNClf8v=fL0S76aL#ydYSn@vdWJB$&wH?tW^NMQIFA3a64ew@$#va zJ_bp9feRn%AFu~w_&oj@6t=S_?OF?LB)!JCG&LimM%0QrK)q`e#T}&~KCFGG+|r^# z)B$d>#e&~%1B$YYdws#Y9v2EGeNa=)h!NM)uhH{+5@um5C8% zs{XzO9&J|~&P7)bZ^Cf&5W}vz#IQHodKpBFwl}t2));d@LMy!fc zVj)><*q*VX5sflvNOWvG##$Y!w#a;+Tn^o!)5Q|sUR3-!`-OR;^>&(y$__K8qGWPd zq=w{xMTs-Ww9`6A@-1p{_E82><5H}=Gh(Y#6yK6;GTQ_eKbvg;YM(cL8e3~+zlMD< z{yqYY7&e@S(vD2W?B#Y0ATw?pRL6Lqtt<(BEDXkBw!F0q+&&C_12e)|0-7DMW$=G8$k8xRzLSa(B|K=FvDK&I!wQZeIXgaNSVXCnyk%?ZEZ@Pg`gCNCx z2Ydw-Q#KE8I7u2!z>qKK}{nFm+0DF3n?>VL&#;Z5YVKs*(M4-9sH#O%v-R{&$-VEyOyX( zo^9wa`%D2J9PvSDOznmArmjwNj8<*lHsVc=%qu3@ua_au|J6Sw>MaU_s(| zi>+9p9n*59z)5uIr6<}{t|PF1I+{(BM;O{RtA^<*)*?xK)6^dJbq+sP;$y0|hRYlM z`B3v%;G2erF`ao;i=*sZ8VIQB+cxKxsqE>YRKmbR3lBco zlp3?W#KuO~o)bn~>j5DLESN+in_iBV2^EVA3v8rFgCM4q6f=M}XsJQotv02Rai;9V zXdR|2asq^vXiFv^kGCEXGTGYdAUl(mb_{{Z%ug$zOQg~tNP;~8vd@(TYRM>t>~K=l zX8)Xc$Q8_s3y$Um{CS)7qQEzCI@xq@+0+>C->Q-pB*#x=$L#nTSf5en8o0N;dq21F)YI9^78fzM= zY-oXfJnrRY#gOv|8)q#D20|1u?(~m+GpgO**40B%%~vBFP8A-K&L#>=$L}FF@cB^k zP|2vOm?^ELjjR4pUf4^ebs?S>;JUPT_c5Kp$M#vGAgiJ4V6`udX6U$?oeML5UCg5q zGy5ZD3C(Bm&szC!p>e+(R&ofbHk11tvFSz8P%Gox6VZUj36?fR1j&g;h)?8+dfdEAhND^WAp+dzpkvw_rwFiYGrIWg6YtFG8{i&y2$vL3Zr zDH-v0muytnF@C$iHXT!Mx1@uX_#H_ULu`e{NiEjqX*~&bU>oA6L6Xz-N)}<+6943! zNcHmh_0%v*=4SZD33v@9LFwk5np^KtahF%MeMa4EQyCgz zi-Vg!eo&k`1k;ygRmr4*gbhb4Ba;RIMjzJ5q>6zSjX9)IClq>4fC!TyVg<~Eo-eH3 z?|xYPa@MJ0OW(cRzP zgk2TvlTjyFTcC&AoPCt%{fw3(Jzd+|@6UDF4xI5orsb%$QYD3I)_g0j-eolz!GwYK zZ&qi{RHXWZF&g&%@jjY1pq^km&*adanK+q1$CucG+QHs+~EEb-e?2Ey= z5L!#K93*F`TIpgbD2;JY?Ab@K&onDk>Eb#Y>hi4)Q6sz!_IBD-7L$^!;wXr0;p{uD zlKK}zKcn*P(HvqR@r1A9!T?n~m${}Pmd*wA`4*hd8z%2T0fFx!(>SyZ9MZ{~=VBCt z#_3vxRVU~i@MwiwbAwqf(8Wb+L2HH~0!ktjV4S(l2H9sHW4Xoxjd@DYuF(8gf7K-@ z!$>v-`)S?X@=8r0p;RVjD|pMtc2FN_q9QJRv?xMA`t`G;d+CGlPIg$kSBRHx#X&{lU|Ucf4p^WeVW4ih6|Ulu&liRWTb1R1hdl2rwwP-Vm4eH@*0oc`+%Cm~OV9F!70# zQ8{g7!K&)yi6vJhi7|OHIt5|LsP<(@K3b9jlS@)yGE)E*#XFgkPr;RyU+)!I=hr%b z@d7}UWizEDw~F)LKq8#VlBidfM7^>k>Xjw=SXq*fl_mLDS@IQ?C0|il@)eb*pwYC2 zxI=d(A6lGCyF;i^%)mtbKz=Wrx6jmEmwPrU01sA|eQuttXvp!z-p`3-nNpGvQ%VwI zN=ZUYsf2W*h0$u5wVBCqN|ItqNm5KHNs1|_pk$P66o430Cfoes;)(;4o7SerZWtCq zM=@DCrj|s1YDx5`mP8-sr$lt8mgM8qlE_aznJu_=iQ-WnL@_x(371KmG776rSVT|5 z)n)5ua)M@PTN&@ zc!Tc%=l5xgg>7e_?zJmgKF_3Nmpki3a8Td64lZWw<#>Wq=oy%A+8hRHW6#{8jAzE6t@Z{tj#P-F3`G_x*VH(LpWFVS z7$UgD93Go9X3v!rno>Jh$v7~cFOK=*BGybTbFJGA*OHxS!X)ERHmo;=9tAcaVDskb zhBUBcT~o|h;(7u1sKG;+y}-3;2)1BO(}npm=S2_^xv9mr%b zbSvCMrcNnoUZzY5nIFo6Di7@}9Mba<9(#3ZW1LJu|Cx@HI(xb^C!r*^^_*0VPBVYW zG=EY{--$3xCQ9nf_1q%k^Pu^2KZELWkdv=3x^z(pH0w$VUaR5{~m z7PipJDp$!5Q)6p8o4Sb6T^M@pNw=k&%{H-elMN@QM)~-<`$1k(hJ_ZQXuyl+%$jv- z#n>hr;OtvjG3SI6D(WC%D<(~tIC1=h$tPA${HT68>YwmhH6A}})sksx%|>NoaC*SW zCssuV9&%9Ch_Zvr-#z?@viFo7Ic!wf`^t_g|G@BZWzl%l4@$`K(wfKTF?M8~gz>0s z=3SNlPnchz}?<`+Y3E7-6~(gqlg-_a$JKD)NAphl$JH{#J@Pyn*p@FL2{{Yl$1m zEv6NeI0YAf2p=7d=h_0Qw*DDtVNXQ4N84lR7uUT!fA{Pk{o~K5@h2L?&m30bJp5)F z!wA0w$)BmiPaDR6g+G)Y4)0i;C&OFy*RrS< zZVZn<=@`Pp5AK%4uTX*Co`YNX3-M#Tli_Vcc=)+K3y(kX7{Z%{bH+FP{N%a{{Ei*2 z!(Rxm5f1Rz`x)KXToFZE-OXHrzj|CH-}^k?`x4yv9ZZk#-hah;^1Xu}fsbwF2j5K;Ff&vwztY6{xl=s`wkr8z4-0ulJ~Cu8}Gf%{l(u)e|&HFdCc(M zO>j%TcSqvA{3*%s-f!U?-w~(tT7eHYhBe}^9vMK|-s`U{Udiff)vlKb5! zAZ+|bXZYhi9zPdD{@#lR@Uy4!UwH4ca7lj0ZhS`t+?am+iOBFBFXNoyhV96@NPR9^@9%j3qikz>tuM(BfOBm{7K3X-aGLu zlOcR>bjtqAa|Qe*%h4G43-98q!}+oBmxxY8fA_%c8dvzcm`dn>8f7D+}duJ?BqRhVT{*4G%x|+#E7d z{utAyA>rMI@HWAX`Bs4=gx5JFyrmy2i%uH@5BkGx`%B{_`MuQx<V<93i|F zL&CeMr7SwrgRuW0y!?>xp8tG#Tn_m95FUTMIy}PwUO{-<62Dy{&K7-$XC4Y_gA)wJup{MU`NHS6lMI(+xcEqhJC?-#N|51BBk}xnaR!NSt99KBGTc=p zp1YDnxVMoAcPoi-ckBM^Aj925BHTB`y(GeABGP>n$Z%(n2)BVmxSiy$qi7rX!zg-Q zd_$~2hVXthcr@O-Sl0y-*XzkAATvpXyG`67zCr#3vKS33{Z)|gHw`@cL4*r3{*T%}h*$8;SQn zqU*=S?cxrRznRVVk3yTl_e~&?u4_r8=X&veaR-U?e4Rx44Ikm}A3@^%BgMl>ynign z@S915zgm1md`TREx?$-{!e6CWEjE*gR~L!*uO;#R4dkOJU*zvmUhqyne>nLIltc2T zQFK4~IMRds0lpJT7u{>g@1Z=A-;bgKiF95|BAss|5#C)O)A?Q!-+8~dnM9adbiGyF zCO#rQE^Zfhh&#pSNrbaY*Q4o`_oZnGF;yda{++QjVlJNHk34gmu_?re{%=Zn7 z_mYUmE|BT^3dnf8PU1WFh;NXH$6j4W@WcDV#Svly$ne&X2yY$TajYlde}i~0IQkKk z6YywoH?QG;FNyCs;@y6K0?6kpNjyJIoK7M>OF{ZCkUzwGNQ846`6J{jxgG5ziTr#? z_v@e}GoG7Bez&-X{22}?-E^NpqLC?(ui(4Hmq^?%KshESyw}-9BHSx=y@5nNY$uTq zuaHkeeje%9V@O=DCh^=365)*+1^x!|0%ZDBg8bfTB+_F#iS(EuR_lH(xjTyLfs7x^5@1Gx+3 zUEB*Ejq3;o1HN}SiT92WN0NB&;kupx@_mcR=kPt`lPD+RF1f!!{siHm)4*~#jfDRO z67F4cUnBPoAm6`<#QSd(?;!F1yL5f8c)z$=9C0+l-HCK2@t$Uo;VmW+-V(9E`=}o~ zN%-5N>k;UT(0#NxjYK(2iv{xMDCgvh2oHuB-tQH!CI18Q*7f}){A~wWK6j9a&rTBY zd0yNl_Yuf~(Jw>3k=szeNW^bC`8%{zU^!%Ao!CG=gzqE~-eM7_(dg$<{=lR09FoVL z1ES-h+u7f5kl)SFt{D#RlhIa>AFs#Co$=)LG;xN=_|l#6Bo~WI z#ZIwT928fJYsG8D_2MS+4)I=bvj{}TLwB^lt&Zb|IT?Tcu{@0+pY`u9|E_&p)7RWQD!|N%5!RF7Y_VAO0tbwc-NtY%wGDik}iM5w8x{=3agxY>6W!~@jCi4Vjd-(or}&8Yw76URgZQ@i&fy+DWeDFhO`I(@i>=~v z@pAD7ag%tL_&f2>;sFPE_(zDxh?B%dF(ob&SBU>6eo?$n{15RFafi4|d{z9bIQKx0 zN3-}Vu?+npe*dB3Xz_S)nmAi*6??_=#Vf@d#XH0Y#D_)p$N0Y8;(v=}Bi!BkVYvT6 zU5^((Cf13c6weh`ifhID#ckpaakscf{Fj6My~l`?#aUvL*e2%1OT^EMcZpAlzYt#& z-xd#pEa&%sP&`TegqRY0#0$i0#Es(D#D~PE#9xT7iEoRCv7g5GiYJMm5a)|2u}8c> zyhhw8eocHxd`kR<_?q~(co+n?y
@tQXG_bK?2p)#5GUJ>rAnli~~FtKwVYq3`tf zen1>Aeq5{<&k=Lt`Qp{$E#f`mgW{9o3*xKdTjHT;%lO?N5XXxj7wg4y#GH7(c#C+C z_@MZt_=5PVcmVp5eBXz}X=1h5Af6+3iz~%1iT8;QiBE_>6MrZENgRH-zxRFOapF{Q zme?rvi5H4jiZ_dQi4TcSiqDF>#n;3)#e<<3@cWMxj}KPVn6o*+&XPZmEeo-Q_s3&ka3tJo>_h@TQK6fYI8 z64!~e4=~>Mh+D)*#h1n5&=MrtFB8{`w~G&m4~zdP{!u&t3M$|G z9`RUlidZ8q5Hn)Gc(Hhc_$Bch;=|&H-|O$8orCZDgg9SJi9O;4;x*z%@oVBk;#1-; z#6O9{UJvv{qzLA*nJK;&2w!~2Q2OMF!vHp=fGCLS%GAf77D7R{c5 z@LF}fT>P|nrT7)`8{+rHpNKDrw3{$~?}Pn=JWiy&gx5302JsxROFU1!Ok6MCEt5yyy=#hK!n;!?3kJYT$8yhXf6d{BH+d_jCwd`mp?LmrQhh$oA4 z#6@Ch~>xl``;y2h$o337w3sf#AV`n;$$-E*CEluM#(i zcZd&&+r*!WzYu>fz9}C65s$}Iv07{tmx?*@GVycb9pbmdN5!9s2aNUb-z9!fJW)JN zoGUI8Gh$x6P`pOGS-eyHmiR;QKgHeR>*8Bt<3~MS=ZM|nO7T+h2Ju#Lv$#$CiMUJr zqxin#J^bUuO0iMANW4b8S-evmeS$wfR-7tUi%numTqdp*FBShy{GxcT_@MZ>_?-Bf z_@;R9IDLmWNt`BrT&xz)5SNRq#r5Ks#rwtW;@jdoPW1PU7w3x2;!-gut`e^hKPP@k z{JQvE@hS1=;=9ND`#vC!6HgUu#f4&8>=RduSBo3OuZo++ABa1|Ux}}aZ;2yM^7tGj zjuoeh)ncRAA}$xt7q1dGhJyg0N#9PIG7r!fR7k?qXD*ja*S>^9}zj(ZOidZWy65GXo@e1*C;$7lqahv#K@#o^p z;-AHTnd$L3Nvsyn6qkxU;`!oL;s)_f@!R5$#GT@A#XpG$%<}ghAs!=6605`pF(u~2 zPm5QIH;G>r9~OTi{!)Bhd|N!U+T(GwI8HoGJY76X>=ajsmxworw~1dDzbF1!+$Fvy zz9qi1#^W(sJV88FoGYfq<>G4b8u1qKZgGqFnE0IdviOF0&}@JId&OhLN^zFhD7J`~ zir0&q#0SOa#s3oD6i3YQ_Z=x7Cr%No#U`;!9274WuM@u`{z!aAd{O*^SXS%rJxn}W zJV87~oFgs}+r%rxo5fqjd&P&uH^c+x`umO$j}a${Rbqpf5_95n;%~$~BImZSKmIQ9 zXz`=sG;yA|MC=zY6mJx77atHG7I%oz8UDU^ilfC7#8bt&;$pEw91t%S*NL}^|1N%4 zd`8?Y{y{9S(|3y%;z{Di#d+cqahZ6Yc$v6fyj^@id|2Ee{#yKRv232lW0E*aTp%tN z&lj%}H;8wN-xVLP_wb%>avsy{d_vqQ{#txXJY<3U8zmkmR*Eyl2JsxROZ=30sd$5U zt9YNdReW50PJBuHlX&z(kI$*%Y;lR$A?C#k#cRZy#XH5v#hv1t;z5i2J?{~Z5hsZs z7wg1NiXCFVc#(LWxKX@Y{Eqk|@fq<&@eg9zVvo;Z;?d#>;wfUSxJYal`^7cl_2L)B z`^2r{Q{oHa@5R01JI?a>yk8tEP8F-grD9H8C0;JB7r!jtFMdzlF1{fCUfe6b<7|(| zQQ}9%)5LjVN?a~pB;Fu?N&JTRu=t|*NAZA9s$7W2ic`cIaeW zzlet{(f5hRi>HdGi)V}Hisy-!i#Lj26~8S$Dn2LvPW+2_$iM3S;_>3C;_2eq;&tLJ z;@#pF@iFl^@n!K1@t|}3eeV^I6=#W!VvE=-t`@HqH;MO(TgC0->*9+`{e2@^oJWWs z7C$c5iD!$Q;()kD{H(Z1yhq$3J}T}MeS&+L*f(S&%~F- zKZ^%s{Jm?$Ys4GHFNybxTf|4jo#JoAJz{yghx;z^Sg}%^B{qsJVy}3Cc(r)5c$c_E zd_>$Mav?tTtwY7p;(T$Vc&GR+@u%XEo&Nl>;@M(GTrOT9UM1cnentGI_^|j>@t5MC z#PY1-D~=XV6X%Ev#5Qrcc!7A8c-*-j-XyVJJXahLKO?RcuNLnVzbQT}?h;=S-x3dA z=I?utc#Jqv{De49{G^x_SBMvj*Na~eza~B@J}15;{z)9(@#izvQ#8<`t5#PDopMSsjQE`TNhPX&fi}(pqd+%!T zYH@@3RdKWU196A=y7-njvd_aiN*pUr6|2QYajBRSSBaO4>%}jN_lw^Xw~H@`uZVvU zN8~*|M~cUZ)nb#_Dq`1YPY>}L@fPuJaf|qv_%rdp#5cuv6g<55izkSuiD!tdB6hd2 z_g^4hA%0%GNBp+iU$w) z`;Qcl6K9BZ;v%t491z!tH;G>nzbQT}{#5)Q@t_s{-uH;(#8bsuaiN$NKP6r!ZW13B zw~Igfe|6mle9U+J$MK7V+B5bnsZlGk>=rd*RZ6TUt!K6#<<>C5qiU2JXf)cpIN$_Mt}q6|fdI!Zz3q`(PrD#HqLj3w~|% zTL!CQ5H`n-*c-pX@wgIy#GmmDW?=SV#(0JCee}hT@l*T)qj3n1$GP|e{)mV0G+x68 z=rP=wM}91eHLwx3!R{D|1MwT2h0Aa=9>Cx5D*lUaFy9DcKGm@yw#6RUA1B~^T!TCD z7rcbG@g?RNX^dAIt7AiKi#@PEeuWcoKCZ!?_zPab+xQamj55Y=guxh!VHl6Ya565y zRNRTj@B(JyQ_L~i7`G_;pg+FG++&P(C9xU?VG9h!2u#2cI29M+I^2!N@e=-n&oSpW z#ypB+Wo(4O*cmNo!;v@*Q}GHG9&7Yp4nM?t*b+lA94F#DT#38!FT9IyG0!;GgDtTg zcEoPj3oY0W<8c5E!I3x~XW>TNizo0B-oiJSd%Q8v5?C1nu_=aN5A2IcI0~oXB3z3* z@hG0h>-Zmfd~3|70G7q-SRY$qG!DX9xC}SrRs0v{)cxA9UHo(@{4g2B%9D_4) z8K&Vuyo)bT|ADu@Z<7P_Vqq+SA4)&O0jF*gi@fW;+ zH}NrgPBr!`gypd&HpJH06^G#j{0@J>$LKN5=s!P}#TwWU+h8U>Mz86{{@&<^A7LBp zhJ7#zN8l7(fNO9&9>%lyH$FtK8OA&cVmYjV4KNtLz$lEvB>W0T;$%$0)wm50;TgP! z|Do4RV}3=kGS|tdcE)MA1UKS-{0;xY2k0@^=)VxY zj{(>UKgSpxjx%rt{)mV09NxeunBzNR++tW6gRmub!9F+uzroqK0)NCqcn)vjD=aY2 z7{4M0VlZ~YI9!X{@erQH>-Z2o=5t)J9M;4}*cLy>C``t&I2)H^8vca8V+KCK=_$rM z7U4SFjmPma-oj`2-U7}OR>RLR3X^dx&c@}KhCkuI_y+SWG{z}|)iD^mVjoPx(KrK_ z;zrzuzv30Vi=K;&aSLL3tcC3`3X^dx&c@|<3@>9Q-or=u0zDQR{4$Buv3IxC4)3I^M)5n0<*cA8)LLe%KU4(2TJ-6er?*T#eiDJl;f)rN+1guq@WX zk1+&$VKffLaX1^7;U?UNC-E{qz}J}Tdt*Mu@dNb7rq}_$!2UQ0$Kovf9yj7%Jb{<+ z7Cy!7%Q!Ds3H`7shM*baa2QU(MYtaK;;;B8{)=z1z;a_A4ObYp!p<0hU*d3_h|_T) zuEs-n2Cw0Le1k=PFvhKgZLkm8a6Hb$MYslc;Su~B|3&>DKZ@aI>YHLKRoZo;zAN^i-a>sGIgvb! zJWiE)OvJgAFIT1Cjg)V}?bM&Z-&JY%2l*QLF8Lw(H91?V(LSFl>n)2FDX&TPBR3{D zBez#`n@n9)nfK>vDU+$6D*Yu=o{ZxtpH7~QOK}Bm!(DhpmHvLii8gyALiu7$#SM4> z58-vZg^yI}r}#Qi=2=OVajIZ-Rq8*+=Bl*oKn^9F$rf@PIgvaPC#kZY*{X~)PnGqo zR%M(t%D3S`Jc1YT3cf~<^+tbrRq3a;D)a1yU*aHD#vO_yRB8V$^|Q$H$jiyA$y>-f z$Ul>hk-g~Ny`%snjX4@b?GHzZ~$_uJeUV-vz=!bQwZ$fUX%6=WN2b%Fq zOu{j$j5itQP(B}5P`(~_P`(F`;YqxT8Td$*{$FE`jmG?PV^LM=%V9OjYhr!Mn_*iF z#V;^im38;QILarga=vF$J{MD{-+)_GX}6F3Gx-$xEcq(=I{7~NG1;_9`jPXROO^TL zQ|0`XRb`!3D6funDQ`k3FhictMr@GRTkcIptoPjrO@z zY3EHYN%kREBL}FmuEwg2+f7dDTbx1pLh@2vhnw&q9>FuJ zjQa=Pp!^?vO!*ruohI#Noq^aMyQ3Aq#KE`(SE;h@wYX80@qfl+s`P)Be35*e{1{(Q zo_&k4e{NOwD@ra!{($@;Igs3d+(MP}@u@2F>Zr>32v=oZ(UiwiKAiILI34HXGF+uf zKby$ARq1~}p1|MmZ@h_5RT*FZhnZ?FRrb$^B`AL%Yf$csO(<`T9kB=YR;51+#!x;0 zN2qdKzNLOLuAqKBrcu5P_fvj^d>qeGeuaDupHTi5y|x<1=SQhzaadDNn&4DBpm)Dc_GLC_hKOh&L$r z+#&tTc`KmGe2ZXlRmQE3zN)lqNNz%IOAaCTQ007CROv5LEoCwdR;9mhROx53D)rNG zHua0BUrpYQdni9jK1sfe_f+Zcp;}6QcFK>8msgeYf>;JCpdSWdXY7s^Rr*O#OUvtH z%17cis?^WJMQUkzok`w-dnrFg{*`=@{3rPz^1tL4YckHEd_JzAd_8VeOUwO=`k(MH^_TFfD(!BQ?~`AW^-E>6 zK94Hn7bKU%YLwR^*H`6wYo^NaXsOEa=%&j47FGI-r#=yrsUJc8MDjFp3V8`RmAngo zR%N`Ss*HDu@@uM$cZ>SF_<(xPJyI|8%B4!XLaOvr6iZTHk@}kChS-Giw&W0U4^{7X zs`M9$iK>h@Rh9APQl5f~sZYc0sQNCD}tpYqm}ccr`s<^3s7#KF{mjbm|wD&x&pW&X=>9rc@V z4<5iXn2wpM?Ee5?Q2qvU?KkQRV_DTh{(rDo6YJn7*b2L<(tmG^qC5tZDIb9oDW9s! z`cf!gj^|XlelpQ?z{q*A1p1&aHpbSfhso3)KT~CXR_v!r|4HOAI1A@dznr|9yhWAk zYmX}ZA5dlfCspbHJYJ^!I{6+xMbl44`&?L9mHvuhWy)(~J<1zlE6PK#2jyn$k8wBx z$KWhg=DUdeJ#NOWxCam5S-gO^RO#m-`3Yt_Xq4wcZ&lV;0(~g=BL`tq%G+R9%6nj6 z?2kin1WrF+7^`kexr-&1A3!sO!Q571YY z>!iLa{WVtQI%%)U{#_~Wf&D2@A`ikbI3DNYBHV)q@PsP;UsYv(cPPJ)kEqXi$Y_^O zm3Ae_Wyv+M9_5Y6!Q}SjZsae>k*ciwOI6mLq{_NSs4}lyfL zMwR|=freNl2L@(1J($${h+*a^E)Z&qdeNQ_ox9;0y%eROz=Bxh?jfJdzx($~p#8 zJ{-qTK2MeL7Liv{zmf7Sl>bcm8OqZ!lkx}ng7P<*`=~L`B3MF|@$@^M)Y=$;^{}Zb z>uW>)6njw~Nsh)ORjz}PY9aai1m#mzS^r{H`dfvYsozTdVak7_{4C{vQT`7;P-UFg zYBu@a#bbuqRp~#!D)lAF<;az>rYiddVFPTb%Kq(D*}t>uX)<-kFQ^ZvelSkQ<+usY z;VsnfOwoP|U>U52LHG%VU@wfu!8jIYsB*kllGD`uCewEEA^e^4^W+Tjb8?R3vR@wg zy+D^tj0RNBvGy`~4W}V8siqnN>~R!#`f3)qi`UO z!5O#`({LZ2#Jl($-}}p$M^UVVb?{?M#|$)GGxjTkRWSe?U=#cT))Ju!}0Mo8!qt$g{~y$*JUR6Ubka$B}1}7m`<#)5!bC$H?c%SIKwCPsrJ>8}rSpmX`NZ$Q8-8$o0t0 z$)A!xCtJwzX~FJ;J8$$sRI$id`L zaxZc}aw2&+c^-KMc>{Sj9>YKIAAE*+GL89_#LDQe?v?jVvx^?`eouZen_TY&L{Is< ziAgLf*O4mqHORi?=Hy^@CN_zJ688YLI=&?Z_eIWbzPl3VAVk z8+jM`GWjamB*$FG^HOEJs^l7~v}r4~6hfT2sw!;uKV+8iYSR9HYa2!s=`M3yI;A-5C zyYV0%!Si?t|G|6s0^eYEo|kfA2`qy?SQTrdKQ_ab*d9N_-e|#SjK|?P8mHkbT#f5+ z3vS0lcntrJSv#<4g7=ix$JuI84{ zPm+JcpYbT3QVYrVpp&m+Cf>pS@F|+!GuG*aMX)%Q$4cmrb@3x?hM!?)?1lF4eU{_V zpB#r@<47EjlQ0Dr;}5t7cirLaQocC6EW;7#xpNReAhMAuq<2n2MWmEAGRCcpA^+O}vdJd4aC$^};+@ z0DZ73*26~F7CT@s4971q35VctoPslOJ}yH0_mj)~Hj#JW9z21+;RXByGcXgM;VaCO z&scu}tbjgP9c$x9*bG}^d+dzeu{T;U5tDH&PQVmgjA^(HkK-v!$IEyJ@8eT^iMjRn zX*r(xu{f4SAFPUXu_1nft*`@j!f@<^acILKI2@OKh*o{k1#!3$$Vs#$zH5#Su6aXX5wx z1OA9R@F?29PhQq>hMbN!@ixA|H<&|yG1v9y#*$bTKfr2O4;x`y?0{yBz+@bPqi`&y z;9}f>X?O&W<5jeOU%kxx4*5Pl!&jJB&WWzCAeP5U=!Zer7@J}UhGGQv#W=L#C>)EE zaXK!+<(P^aa4-IZ$M7Wnfq!8p-ocmn7IPHl{9<{mgw?S&evF@BN9=-DjKX+K#IJA| zPR8l@9WKCB+<@D0Hy+1Rcpfj|KX?ycqel_WJ9=YTd>?%=09#>O?15%X#AF8%Xl0A#V7azbIBW`dVS}^Vps~RVNI-y4e=9fg}MS zQ8)wV;3E7U*Wh~Gi$CG-cn+`QEqsQr&{N)<)b+oI#jq4s#L5_m^|2|oz|Pnmd!q$y zI1q>7D4cZW%1!vM;bHt0PvbSbfp_r%nu;68!wZXGajb+@FbEr9 zQ*43lFa*0|5A27rn1q9HIF7~%I0a|pJY0oqF%7rjUi=A<;YmD;7w{@(;D7iO-(WWR z1B>3Ta$!C!gB7p}R>wxz1Uq0S?15&C#RMFLLvb{Y!#Ow~Q*i_C!-IGZFXBIV58q(6 zlE!+yu>@Ad8rTS%Uj%H7L3GX9D);Y3NFN@xC+-|8g9eG_zV7y=kPk-!iV?-U!#ZoZPxxe552Jx zR>2@_fK9OlhGI7~V+1DP033=Va2!s=`M3yI;A-56Tks$r!C&z-Uc@VS7ayQU8RIx) z$5L1hKfr1jgblD2w#9DP6TieH9E0O=E~emWT!#no2%f?-n1Px21YcmmvfNLx3|2s2 z48TU%1VbZH#e5Ta#$HZ z#0K~gw!qfd4SQk)_Qe4>7)Rh3oQZRBC8pwL+=|EX6sF^4%)m^1j<3XvPRkzyUZEN8mV|h%;~wF2tp{34g@hxF1j98N7^FF%$3LD>PLw zj!OY7f)%kc*2Fs41e;@9?0~&69Q$D`4#g2T9w*@fT!Jex6*uEnJcP&aH$01%@haZL z+xQTlVD|To7fEKa}_T#P^98r+0G z;%?lJr|=Bkz<=;1zQqC+jpI`UD`6F^hmEj3eufd)7YE{3I1#7fcenu8;U?UHd+;Rw zj+gN&KEx;Z2D4Q%)>RmbVL7abei(#JusL?Y&oK&Pa43$z@i++=;1b-3TkvN!oBTU@ z{0-0Ib-ac5@ez9Z82i76`Bix@v$X0d|K0+tV0Dx~Z8*H>OBe_XEs#pVkF#zjfBMioN7=oeL4SQlFMq@lCVlocFaX1mD;!IqO%Wx&8;x^oc z`|u#1!ZVnTmoXFX;C+0ACb>`AuW!tWj?X)lAeX@k=!3o(fc3Bu24g!6!BFgt7L3Gb zOvWKN97m($^HDR&b1?;1Vk&OHG~9;=@dzHrbi9mLF$3@8BYcLhFsD3**sotKh~8KM zeXuIpKW8ZC$o+FwO{i~fHpgIed|s;?xhM8U3&vw2CgTuv z|J>G8%4gzYT!t%Expq=YE)Trf_Xr%85n+B{A2p(dxzQ$O_Mw0WBJ z+3nrtX_7wxI&GdN`Qy3M=4p~Yt~za=CV4`3+B{7KosvmrBY&K6+B{A2M+>LT(16NKX2CE#AqMjl>d|V zn#YNb^`<)2>+#v;l(Xxxmpp{_-jeId-?)#HeI$Fy-7u%q`t)zd#%7GKe=Bz6KxwDh z{`!#h&2*~Q@fSPg*3w>c1u570c9*qJFBC^#AT*!Dz4VnL66flJ=TcijMaB zo}Q!Le*B&C5^1+f@-k`QXs_?FIk)faly%;k?XO>$zrGjZ+}@G&5$G3buUk*~$tGEk zXRsF7HzPZe{NK{t9672>pWpPiv=5MFY?{^b+!r|Gt#0xAl=(b8flLtH^CV#hOb>t}nOqlB-H?A-DCAYkghGz2&w(lW1-! zIYw^lDb(Cq@>sd8mz-vcWWA5;Bfn;wS!z5Qaz8FJe~ zUL!eJ)}YTk+Mj-YzK3MTe2z-iYt)hT^|e-KTXGZ0dW^JvCGp)>)YL-ibvq(IdOkWy*4xo!*Y-tBVYD~KD`L{m z*X!mbKOS;aUE7y3B}u*3>E@`hDHoEgzsorGFE6>goC8O$DY=bP zZYVj)DYura*My^eSINIPWvk>TPT3~;eVLP^y?#Ewol~A7d7x8XAbF`%UL*O0Q`XPv z>uX#`e}^UOzb$a&vvT`Wr~J3v9^{lC$ZdV?=xF~|ZvX0(^T~6eewN=+Ut019^5e+W z^~__6n!mNpAnyY*NtFSzO zHFm4lbLZH!|2}RxNwVYlsE|DVO?0bY;FdSLEx&ck1?5~jHl3e-{@<}_ z_H)Zk-Ey#7)_)J+*mQsWcL9z~^DwtO$1SgS%e&n23Adc#mY=v~{k*?p)A5VAW&NDL zW7B&5e7|GU9O9NOZh5doPKb+(ag^Asv00rMwc$z8{biKs==IF$dC~HW}iuMIaV@GwkbS2YBjCK?Zkcq}6m|Z5K$F5I;)#_-I zV2!qh*|MUJooG#niHge_Mh?@vE+eAj-ZhSkx5hg9VJuxuEol^Mt>x#avL%KkBqqf> zVpMEY)|9Quay!amP7Di=wwlc5K1s0=W^=7N^#gzpA9VBPL-`|(kwWM3Q4;tOu5+Y(UX!qNBoWLAtDWDaa)Sx}*S?qzCKWevWk+ed-Z^SLaxvy)MvY^gum|SuF!y z<`U>Kmq3@f1iH+{e&XKs;xd;&m$}$4x~!G~E^`TRnM;7nTmoF?65ukI0GGK0xEvSz zrTA_07k`(z_`A%--(@cTF2}`wugIF2Tr*B1__@r* zex+x%^mCbupUYhQT;}5EGMB7-gZ(OS+z*nXt#Wsfha`)Q3CKkn6V^8>BG4pPzF8jX z&6b1#`ov*MvW1&%)`Y0AXmfmALZaCg*C$aPgJr+O$S9j$Mbew3Fl$(NlsPGOU{tKd z91$OHj!%$#g#DhX-G#@+MVk^62budsN5%8JVUAC-McNDdCs_MPO0ZqRv%s+y=vPid1#Oo+Gi+_E>W?4?MK6yhCbeCi4LzbN-#%;MeAYEbEJjF zLk5q}{beHZG!+pk&#%$ZaS_gk(Gq2o=d4(3gt1&(Qh1EaBPk)=eklI;BxFKief2~c zhd9a-HNd$$Tar!Bq$ysWs$$~h1j(TGa}s8;$Vo5?BjS?eoZ08j(`AgUFQ-SJ$n2*l zUKW_x-#!cbDGN)o$P0l)t9?I<)p1^ACiWvYFf1zZ%Oq=()f_2LWzJLLyx5;*?cEu# z6U+%#X>Ut3ULxpZ`bR}a+gI*bT#~L%j;Nd)Idcg~^1v)lcV=6()f#V(i#5r?a$8f3 z{rH+~QG?~#UoT!=j^pChvucfvh_hJD;aRK68q4`wt>ZlZ_=LD{W7S;wSxeVRQ|5F) aoJtd{wxpPM_Xo#vbRzbN;)! diff --git a/sw/ext/ardrone2_drivers/usbserial.ko b/sw/ext/ardrone2_drivers/usbserial.ko deleted file mode 100644 index cae655f71b0382e98fb6ddf2f890f9fedfd0b9d4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 510128 zcmeFa3wTu3xj(%3%${TuhRu)}h7gCHO%jp-flMGkB!Ec(MMWG10k0$^0iq!pb5XRk z4iFVBC<-cVsiZB(QluIxT27BvthD8{+Jn{$wR)P1qZqAXy_B|8{=eVaYbTQ!Tl+nI z{@?RG&o_^gz29|t*Lz>@x(wbjf8n{Rsw&P$Rq~WRNKuv?^{~oQBpT!?XDibcy>!w$ zO1Q04Q%bwEus^Pax5wM@Rg}fu=$kV2OhKm}d+LO$v~}}2So{65J?eF*eKGNtwskHH z?~aEq*%nu18x1&TDZAsdeE3?s;4HH5sVW79g#1fqX_l!5&h+|L(&1c3As3QP;Uci zm;oAujX(~|LCZkBECBum7=OVRjGvGC`i!=IdTEp6!$x%KrO$5qc%S!g825(*_}=v; z#$AeWKT5Po=v~+(_)p}WHWdxO6kiVh6l-g*EztfF?UFw9ive_Ok#?Dk{|=x zrpM~D&C}8*F91EX$yNCN{qJYaIJ$@oq6_*!DRfb4(O*CBBiX3GKYw#Q!!AB!_4!j97vYj|f&@qU<(I@gG2 zyYqdqxa;KDPFcTqc_h|F8IYz}__eE%rEQ~+-U@Kz+?O|+|dsDC9vZj{wFsSnze z&@JT1c<02J1mAg$a`v}!+$4eT`%RM-l_r&(^ zLB}1?F~^D}v_Fn^F|>bjK>H(T-!9v4PH5kbcAL?D%YgQ~&^{*H?@VaF8SQqW{Z#|n zH=}(-wm+QEz5?wIqkaB>_6yP8lI@Qqv@b@xBWQmba!%wo8|_cR|H*H4LVF+DSEK!N z1KOX4J`cf!)ylwg4Y#WsDNGB<+ZK9qp(YPxgiGd+HKwkA9GtE7IqkeDMrz z4WESw%KUsoKHrtkav#j#m`PYrLF!3@3ehOiFJ`q4ReCmIu_q;J@dBL zIvigIA0+QUEplle<{HQ59iQ2$Y!f{0Rcyc6DWB`)b2FY!pHp%yHDddRm-7;Q#TDMv z?F}DBe!2}ZvByltn3SO%10dJ%OONjkKl5X6_{ig+XCLI;(sNP zWeVV9zTNR-QlFDCmJ>%8MjnX!0qdo=b}{ZaF`RVJ7D%7d_8-MltZ=#!LDG>k^eB=0 zFgCs?fBVV8@aD9~@IDjda1Dbs-brcWe|WdvlWC;r*!X8$CK=Oky5TBxM7;O9_X4 z@%J#!dl>IMLCv6 z^SvD3hH}-nsRQ$KmpUTW!S#ryY(UIdEbMu+?3ahJw6MFYDg41()EUPJhXZlSZVl{M z91M1>^ zJQw2mcRVq__0EA@53(Qga;5}fD7_&Hn`~mn_58oEK0BL3!VuHv~;O9L> zQeV2n#dyrv$Z_~7f_@U$&YU|EZ8&`FB4NYCZOQq@8Y_JPxY9=0@03e#PJ}o<9qp4W z_%qs^f}TjH2A>RBj8B&e`LeD9bzWP+2=>r z_Rc56+Xe6YQD#^#i*mLfhWA~voocP@O0qU~2t3w(@jM^)F_f)cMd5qn8ph-rqS>N9 z+GFX~)~+?OFZ-mRJ;&p_BkN-6tJL#n%F^y<5LakZ;bU97oOLdBN!<>G0+!*u5#Jl| z-GJ{Fd>_L1AihuG`%8R5A)dq<#+`oE%kCd#$&1MyId@bd1_fSvd( z^cCJoAMI9RZEnsdBj;@H+Fh`{Q-$8{&DhkbD23gBh3q4RJL77s4Rfq*^Z$5`Sl%7t zxKgKFUj&3)bOg}p)lkZ&90&Dhe0JfsclJx|%D zx8Ykof;UClFkr|6al^JH2S4Y#Q@7eVwPQ0AF%Z`#7S@sQsZK|pX^_8T3!L*QdmXaZ zA$wiQzBmf~w_%+NypWrS0qn29jvZTI9q2{Aa75UL#aI^oCUmf@`z*nu&AYNK(#6=u ze$M)VeUJT}^OfBuR``I>(J;s?8}D+i!~Wflcn8`9AeZdI+r>C;#z>UKB+Qt}cQv*d zG~X$6jOCrbN4#Wz>Zn@AT}NMzEb=VmDZaMO0AiZ6K7qN47)raH2^k)P!<@W$(mVSZ zzu;R|%+9k;&4wJ|8y@gYyJwE{Yw*PR6nabdR@@)=R-D_F6mIMET8|-zc=3}XlXfGP zU)uR6kwYNAfZww%WwW37q>WU$m6WzIyW?%c?0C1rt@P|f{V|{3y(YQ-@noSz|$?W4-dNL@e1;92Oj2N zs@!&|6R5ZAQ!?Qy*gaW34}$$Z}%{T6WE-r@GW z8h2T*#@#*@IsYZyhLBCFy^a9R#N2jP%I^5bqmfU9w+dU+!nO{FjD-#)_1`+hHD~D3|!Lb`Y_^O7KqyLr{qPV+8*pTU#|r7Q1(1Q`vsrj|<~`fL{~yko%0Kqmf&7s!FX&=S z5`KsNe2xWwq|@ z2%bam91eT|srUD0^w~LctXaVO`Y5bJab|SZtGI99w44K(T;OY2k`Fzem#6!e0iz8Zg|eRtqWi9 z*VcUu&kpo^5^av6%}aoN6 z17o?uuVJs}7q%?Wb{pDypvORrvbS|louno2jyI`FkIVO(hyx1dw4Kn`hEdp~2yE!o ztQ~Rphz;E_--hnPSZC%%H(`CbDLzZt6kizI6pvz0sIFoY_I9YhD?49=zhzgzZorEd zvZuUpe%V7C$wRyyx?$VfIGo4#fAMr{)fAiO<&ZJ?XB&Avj-1ctl|IgOg4fy#+lq9zeF5LuNxS3I1mDMd`QAGS-$w@WyseLC z#sc#EOPT+qRA3(5_U$-%I3)86di+*AWka7H*MY``(4)&bE@W~re7tkL z^$XyJ-AbD$FU@Gjm`6S87$Z@S%RR{T$xjFPK@3!|w?o@rhrH{qw_*2(QU2y#*sDSA z+j&=atmCfkL%w^U&yDeL$42OLV|*d@>Y~1l(C5Z@2zkC6aSlG{Ru3<9`JZc3nTu2( z-Wb0M?cjGkw0q%K(6J7?^;T?+4?)a*7V;o{-U`yl-0O0#?Nf@1`uvu2#$F9^G9cqE z@<*%>p|i!^XM?|T^jkAPW!)O8TX$=ek|e>V#_YDl8>wy1FtfiVWxu6?R-Xg1V$a#C>Z+hXy@~ zJu=@0m)o~Npm$DxjEM9z1rRf_y_G53YO83heV z5yWa~tEA&J)^uEZEXQ~!x{rD>inq{Vzbzdf6s17Vu2M zndfuSClL8&yc)E1RNUGn_6@M#LcDth>{ZM|za7|1*@OL+6WGHMaTh+$J~8Z92)#l! zF365{$a0pQ;2iHm43M-iE^z+j8j<~&vvZz%oi>d=z5B(?3n>?gN5i^G0nBwb+wDKL zwd>^F_F5a|3fGArpaVY(&9sB$AN80u4;n+x=r+E<9N5FnODYG}ZQ075C=r(!ohY$Ca z)Kbj<&;!@Nj?BScibu-M+4sSDJNKMUaNsoPGEdqhaH(Fbv%SFKg)V`khiwicf&DeU zo8ed$Xz%P9ihhy4^W6pL>zva&_Xot@JovzPx*z+bPZxF_Ve z-@~}PU(|10;303kCsPc1i*0(})hgg)kv8s|_xP~3c8H3){Q6j@T6VHed7rK9kT+@RyRp>>m^9S3XBAd;rMOqweqzfn!BfY*@x!1i&x*y3BU?HbbU@FP!82RBjc}V9JG`Yk8ji)o zhhy=&(wOaY*qepfrF6)B;Spau6kaPdt{~ z*4ca*=aY!VZY_qpV%!_YzOowY_FCXwiFM~8w`5)zR^&Wdx+(6QukoyLpd7@xkCX$? zd?*L{$$IG*j_sww$oQdL{>=SR=trr5exm*L-!5o^zed{p9?Svz0qc?N$ZxTpja=5D zqP!h@Hp&0QJ}{J!2W7DY?|Xq~e{4s5Ph>}YRup+oTmNxA7UC!9=KUY?;Kg35ZtZ0L zfVrm4?G11C==d@wq%5r?K!Iz&3Jmncyw-N*IQOrN+ z$Meeo&M|$M=O`QQ8SPZ~9ue`#2U^8=fYs90AMKUxFocN1Ye|c&bIy+ptV6g@Z~}7T znUAKlshZN^=eeU#`r+%yxxoWsJ=fK3stK5aTv$@8 zp)=TiMVmhhwogCeoty~rSdKZCGDjKb?ZFwIq6B^<8LP^&&QL)&x_oFGW7zd z*V-;}9u;wNfH|0M2Jyd>ftCkF98!UE)l;x1jJt&_CXmD=;}Ea;~Q@rbcGkNF$&wY;$jG$P;gqAya4 z6vv-uI5qKq6`F9WUrtRJSd6sJ9T6YsQp2+Wc1YA|p= z{5>%Stbxpg|5x;vcMKA{hJTQB=K_D&t|uRu&4WS;k8&x(6n|4a`Mv9NXIej;z5_!;)_q03%+67;bZ zjsKhR7iT)|Xj|vuso0;x*^XL@_=ht|?$J0rlHNU7$L{gto0Vwy%fz`&EBZQZUn6g5 zw;t`*qYwFd8T9yL%uAPd{}%N;w|4aRIN*5+{W(@K`V|95Y2sM1HtdrrJ)EPJivII6 z?>AA`Tt_a!m+Qe)MR_ghOU}hdux5AYe;DIGiS_ystXq#@y-NBY!nlVph6n4U2cnb1iolPjMMbVlkiE# zUh`6#G2pDn6MXz26qk&N{&_qn;dvpx zU&A*s1_Ou4!`e{Jd+SR|@p}oxs&?z8&OGG#ydV7|>sj0pc?r6G7W*~G@$eKfvvdCR z=g@|0V&1QI%DMhzU&6F`-jUhD!9X8Bk7GRMT|SJ*{%n_c7n^Ovpo49gBRMup-Eu7v z!gwK!=d6z?8z1J@g46bT+L?DwfOp>W>i{nPc1GZ-u;*RkdJedr1Fq);E_?4~;JQP@ z9+?xbupN=|Wa)j#C6{!%ORL-WgztNNyQZ}xl>P+se~-VEYpf;MFH%zWBhKliSf4PT zf=_6rD?8Aq1FZFcr|vI1?_`7aME-f7o%>b+&>aBXw(O8+4489~;3`i;&b&L=n{Uax z;tF^m|3`r92=MUUm-G7}-WPEAMP8UP&^HdDZ$Cc}d^1m8BGxhcDc=F}m|lu|0NiUV zt?Kx)_Wou0jt<~EL-O4bj$ls>xfSli1$?IJg)yoGIJU4iiqEx;O!xj)|ZJY|Du7sgpN+c|p=%q2UbkuIg8 ztuwW>!<`OVc*lc#_t3vTh&ayQOA&8JI2hL=*nfm}OHqfs z9JH}dZ|sY1#d;Lh59-NV%4`BQ8uz8(dF7P^Owojs+63iGgS%;$T&%C-~EeS6*;R0JOSpS}OX*v9*@3&X9j zsffJOV$Y|8?M*=qVtxo9<~eqv$otRCh22r$3vY|3@tzH7ssIcbhhuNhU(@$Ox3Hz| zJyNz=ppm+yO&mjPrrx=JRKNoktm%&2I6qTnL(!LVt0ph#!#i;7LmenS?up?}pJktI z9V$`qTa2x7HPF^sigFjuRBos^^Ohdj8ox1m<}I%Oy}&8P1g(?>-x-V3I3HoH_Z7(h z5)j^wXBhs#91~~NU2VW8`17rd->^KE<^XB}Oi z4PV@i{mXPG-{9Rl+W5Q?yW`x4C%(Cm*XeHD5d_}iO5EQ+d{@`<=w0#f^;oZj??OJ> z*1ZHzH=YNl|E80?J%Ohe&mAZquKf7Kyo$Tx+9kX3zW)T_1re6-Kk?Ko1@p%PC!%O~ z|7^??%9axb_zXxZu{P|LmzFz*(YNDaS*!YZ;9wvLasI+`_`k~E~$5f zgdWP-srNwcj7c$BAC*tINssf6xvqzE^J%wz|0++m;r&|XH6ipTK5s%B#xgNKiAaRq z6U3x%z`Bzu&dQr|i0PT8+ zmw5PTs%fmPtXomFrn0eVMQ#0xl`X4Q)igTA&9x0xYny7C`@yUG;FXOvmDf3yE%nW7 z8XKCM>uQ{mfiSQ&*Ey9pHr6)RtY~a#Slh3}0oGL3uWpGt5NKG@T+_I=wxP)>s;X;f z>K&;eT2rq?8ycHeG}hGBRHCA#Y2^yZoG8Dsq47GUx~8eQvEe3Jp)}Ssw=~u}kkh)c zp=w3bnuZ(u2CAv7?<1wQzNxvgt}bza>e{BNhWh%Ns%E7M5&>H_uEaLc#)g$Ow#*a% zLYOO7HP#H)qqe>lCyM_sd@LAsb*C3s36NWi7HV@Vl;ee$FO4MJIhXAV+3FjT;>t6O0CH`LTuH#90W zH?xmGv9@MyL*q@dgdPlGBX)?-!}@_3U)tOE#-f#tYiA3Cn>mkWXVuhKuB@x6wi+6( z`i5qO_02a$Yh;_14GnclU2RoOeN)Zs^CAoB)m4qPQ3R{{*_SOYw-$?-X3cA?y`iSj zs%mJgQ7T)S*EBTFKCiK6wRK@*L*<%D3!t>MmG$}7YLt~;$Fj*)4QunQHOSyVlxFlUO0|$=QvozvU`IB-PO@JoS0!|s)YqvGQ*U9uRkgO-3a=YC zxoBO=V7>A&oVD_%=9;{w@n|r8PJ%kCYoMswCd>l0^{XwLB+%K5X91XKZm=4_c4KXI zjn%xS#-ig|Al0%-CEQp^JF#x8ZC)dqNN=zj>T4$dLtMh7|6Rz$*%guxXHy}c;rMuj?1~&dhuF=nf znp&d5rJcqITB{IZ6MP6$S#xcbX`}yQA=IT%yCVM1^hKLGsiV$Dwd3WQiS8BAX0S_3(blDhsDN zeFQ5FEzMTLD$AbDQj{D!mQ0#MOe@y5G}o+4=wUNrA+57kRn}q>%eQLQ)ixt!^$v!F z!wFxFHP<3(gdS|-dYi0jXsJgaL~>x&)+01wMy!rD)YjYKSQ4GkNRarCTA?e#Vhck4 zKf~A8@?S$rOTy$=hslrzBxDW3n`$tVAtT1PpkP&HRSlTz)k$RGq$yLwQ>`_~eyAaP z9&c!Da+CoXH1{&!1m#sTBS=)yd3Ltw3@PGzeSe33L8G@LEvUJ%vc3uH#HM_qAQ9Kmpf{7XAQj5Jx@J{vz3{VMm-;-fy_i?@ zW5P~Ez9dbw)d57=Q^G%{syEqTmXnyUtgWqwJ+H(<5_yoQ>}3GzL|R*8>s00yw$u>k znwxJz%7Rdoh|Gz%G$j#idvVQgY{W2$^}@((bjX$(>S2E^cJSyw0SNm{?6|T8hG=KJ zcHrp^x|Ma3EQYDXNkrfP#mLL;#A?L=1cS8)g5LHr#0iW09AXD4xptDQf%vDB9$SVp zMFPF}bE*3mA?M1SsD;BLwn2{llsIVCD(U#bl(kneLNvAMeVeFW1{{+gNjb3wBR96NW{K-j@>yuI*NJ zwOC7AYigTQ2C#~NVbMv^{kodQ`kFd9pNc3-iY8BHbndSJ#PL2?WB5diUY8XE+PwA} zQ9|`3$b&Y5$sf{?ig)r5?07jPUoaumH{94SRe-xUthF5XX4V2)2A@mVwX(Un5_ywY zk@R)y^AUx9z5-dy%9=){zUIaiwFntg=ZM8~ub!>wnwy$xu{+>IWh~p8YU(kk(QIJ+ zpO@HmYdO_b<&CQzFP(Eh8)Rn4`b1_T0)(?i*0;K%jGR)(hx?Z`wXE&8Z_w0&RdBsX zznqSJSyp0KX082t3Mn)-tb%I|x`RU3>pvE@1*_|7R@fVl36#q6rkk1?uNS+SiQ`IL z+q)8&CjZHv%jcIVgCTRm!av+O5=J^$Z?UCh@0IlJjC_9YMC_GJ5Pxyc8_zWC&F#Tn zaN?&N`}&EWy8v7;pp56ni65M?iO1<8jAYtO*XRrNG4$J2o@~KH0CdlW-^0`Jn zWAe%UZ2f?`p}k#cW!KNYuMp+QqK*A7hfs(D`|#rHl;PY};ePo4jSt8Fi|35}Px(Ne zk|iBl zmVIJhrm<|(H*Ne2o&Nu(|5O6FKO}q>ceIorV4wF0p6%`JvE$;oKgQpzw72hzos!S> z&@tP6ET45aRNU`A5YypvEMJG`!^sC?X*h&qznFOLjUAIPe;d=@zCU(KJRgZIK#<_R z@(w)Ne;y9z2(Onhb{s;peTR7Ni=}1T@B;DN7dtGU+2dHg zFSZBIAAryN92_=+|9QFa3*app&-(qbL*ltN7KSrXK6w-Eeuwd-e8Q9Lb_XZp`KT5< zj33&P?l6AfPQD`Yxf4(Fzq82hzik?y?Xf4tb6?Ci-Nv^EPnI8%@Xi@Fd`LX^#Y&3- z@At$k{P?l`2U<)6tzcb&`jqn)U8a1a^`S|PpG_!EYENErw|;0|;o4s}m4P;;vZiun zt)h}Q&x}cBN>WO4nXV3TrD_3nq&mu-rjAzAU8a_=D(B6eJJZTr+|bfkRnvHrb>75@ z)cT2sP>*hrc>si<(gRWy0pWU%`Gp{DuZ+zxD%nf;-)@N-N?LeBQiCxjRL%K)!B z*TmSi1J>t!?E1amQsp%=q0xlMY1gki-zDp*xky69Rq<{&=NQWlDTygdLTdQC{x!Yn z;o<-6*F&ali|~trgcQw56VE)=uee_hI1RspP3XeY(Umu0tD+j4Y}fa%i?%c?Cx6zj zc|z8y|GZy~oq3)M<`S@T>1(e@g&b=k0b9t6jwnjj!~NR!%R9f>zs^Z7oulV*`}=iu zsuQT&G*r44L4mE#%aL^Wm zq|dP@25l*_;{o}2W`7fNgl8wx3!fYmPp=*BAG|)nf}a_@g?*Xe%;1$anc}8`{?kDT z7;s*ql)!)z49#J}-q#VvR)N1Rg&unhy59JMe(kZB)4Ru_oU`w9bqV}D+TT*xlSidu z3^+N)pw~|Vj!Pd>205Hv^nItaZyCbQmgxH*AGwt81#v3{-xVvk*}1~r;ARtLDcs49 z8k%|`V0Fa>igGO`BjABM3>Suy+|>p5?x9QUyF!G{}9vRaGl-sd>|Y?ic6=V z>UsFfLYR$903?)w>h4Q7dRzEo#ucjb32wr>{qI6LSUdLVv9Qu#v<26gX z?i_>HY|&tH0ba-PHA$mf^{z!Im>}?s21UM!;&u0QyiOs>`lS%yh}6gVdM`vYV&wD0 z{y`>QN0C_lMqn6`emP(N1VxX?fblB&=@h(X4tG&?t{-QhLb{2?3C z4Pz9bF*f8iw!kd>CjKo_wDcLzLrVS(8%r7pW-HK``6muBBpa1ke-TX;;~mJvpM4fw zmqQdR0F-B=(G`Ex52*zV)*7+%k?swr!pPb$GXeQ%hUkV7h8*1CO`_yDLN&5n|707|1yX;3EibP?>JQtHPYFB?_g0fMq8w@Y0}taFJPYHDsv&-h z0v|O6cIF@dG+&v=`wPdSmEvCr)#dq9p9he-s$TK?yYU8M($yhbYKyCz(y^RdM{<2j*)pbxY=b) z91C!~4Q_!^y@+m?0Ff}d4CSnQAzq9Vz7}Pp-hzBb7QRDb{9_@cEhEpqmE&Jsj`Ep& z#rTQ_NV(6!k*W9%jIm|pIqkhoOP!{n=ZCZE{NJL=#(seq=mZRB<>m+JZ8;cb8SPBcnr#4Pg+?h6@r8Z6n5jLQwHqKDoLgKD0 zZ)#();vQ$$_);6sR@^x@5J+vRQ{1^Wke0eCs<1Vr5 z78*5dIm;)oM2w$A0L`{(sW7%6cDd(J>#i*Lgat^LhdZmyWd!E|ETs{;v)bJT{lq`}%jmmwE$2cOnRuKCTm@VLX;6Xz0@V)nq;gU@K=g^D!uXez*;Y0m%!*fbfP zg3k(NgHQA2s{kI6pwB!#3*av_TS5VIEsQ<*8wsYFw+%@EL*|f~37}=tyMzBDQDvJe zSbI#n6r4a!8MxFId_gOQxw^8#8Mt#5d{J8liou_1;vd~qf}NU3BeIUF=H{~iza>z) zvz}AUXTfjqZSCu6Y=2BO?*MPXkF|FoSa;S-s<|cr_!Di`WWukj8Ee-n!9QzLatNMO z&BvkkUif3x{0k}lt6CeMq)%cbTtHv{|zLpv!!fyk<-INms_o<|ZXL!Sjqz)e)C@>_XH}^88Z3M_uNu zQoxgC`}bUC2UQXF>?KlVHm`({ z_rk4i^9M^3;LUFHuJiw!8tfh_TT0G6sB8 zc9Z8}Y&N>H_Ik`089Kh|c|+g>T*%O{LDuj0m~IRhyw&3u_yKREd*1GON3?&^W4?*p zJh;X4fq)Nt%pcLbzAx!N;xTXHc>6qm6ZJ(Ucm1P;cO;pg(w#o= zqzd`(OfvV)1?)+Z?wo|wkkfvE(>HQb4cuvKp>hi^BFqj~LdW2mT5`r*6ph6lW+mC8 zwntrqh?+e1eKc15B{@i_le6p4#CROIlgHT!ykg8i=j0rsV?yoU4)Y8okKe(DZxo<_fhIET?`G3wx&WfBH0@~w%pc$aW=F%I*XBjk}Mw$D4Wfg?45yI zj~+*{P?EX_L3H$(IjBt1=Hc&Xv4X6^n^*iHO0g~AB|0?Xzp&yzdND{DJ>_0BGyax} zUQ@{<oY#lKc5@~I zp)2POxQ8p}R=m4&7J&*4dlVEmsyQH*_HE`6e% z|7mIK5pW=Zw4YjhdegeZGmu)>*rKFgVw23ZC<)U47fL$ou_+iuzYmYIZ7s8qI zLucQ~p>%W)&EzZjUIXNz5_@1|=EU|*RM`oRlB+}eTIk~0h-o=_2wY0eAI>JPA6>}5 z(^2Be`8xu(J7+j@SS=@G9{T1?g65KPzBL=RpA*DvrRPisuS0U?!pBo`jxNN$O->`6 z*PHY6QW#RsS+H{>X9ToAJm;QFEZuVMhFV7CyoJz_nll8w{5jmF59Dy)V`R?FL4=T; z1E6G-lKXp9YoU$xB=N{pk{EWAxNCsOmD79)i5rV!YX=dW=NSuQK^N>gOzQqNOV^`QE}u+Do;BO!zaxG4x$xf)ff}R7bk^k zTqMt|AB&+@xf(zrwZ=>?wAytGK;)l8%_>CQ&>9zQ5($^r+*=CxS{LIF)+b)`90PEJ z>pszbhu6G=CVaEYmi$hydHqtrUy<-Guj$787FsXiHm^CKn){l>zsGAfg#q8mFFrrKzmelCWBL66ub($GIjdu|T%qezQR*X6rpeg4M&1i*FnsWZoj9U-@ z&FSofIAG8;%(H13+(I;A7v{|I0t$dNZiM)E<{;{s^UsD)8FX3mTs!d%+ri~Igkg*t2v4(MRZsa0gv4(vc z%7Yjc{S|1%8b*Xe)$ii3GkxBVcmE%e+Ih#0W@>1Bg6K3>Z2zO5QH+|gXVCiSjiT++> zlZ}T$(m#+K2?^_e@@!ON6K%LT^C>3}}nChFE1!(4#=Z0lmZ5k%0?PZ1J( zakozc_?L!4f~~4yTnO-V1Ms-BHmk<}AY$l$zgd7=RO7E_1N^L9^xdXrTo+YzRXutO z8}CrfoF%Ar$#Aq&HBXlT_DFb_YW|eClT;gdn`*v`DPK=kZR~qgb1}rL50&+MRrAiF zfW5MQziM8V4S1Nuhy9oagh$;c;e)Cb>>)pIrwKQ@e> z!9=cyWqWM8TrnB&IqE?{A2wayf+_XF*mSv`@+g(Ng52?hD zO_(iu0=(a4{uzqb=c$JUer(E|hajn+r#>fOY|7jX7t=44{2p?dTN&*xmiV4@nVrZ* z^lC9LW7EN9dJvQJ)v6sdu}Sj~9A3Xx zF0%kZSieE?bKC_FN`oKyqcEe0cl7n(#&{X?g7+-G(h*BxaNaRAU*_6xVq)@|Hl!OL zLiyed8}b^v=K&gPLq4Mt@xq&FFRlV2Z}pC|>(Wwj4;ML|4TTI7fz2yU%3N8N@$k8T zCf(%Xc-h7`iKT#h0@!IZf(X#wu-z};*bc|?7H$=EhKdQMY|m@8}Jn~03v=1M1zRWq9pAK zL>uh~c>P{Ni$V~L7A*4b$N0Lp<~ZJs7cpOZSJ{jx#*dM(dRN<|BMcs5kjkq12n|!K zDx*qPwY>$7(lLlpSptRsg(2vaT|EtP(%6iq*{dcBttiG-aMJ8rR!~PlOdQ$Q+K>)9 zKO-%7A*Ix^>zA@K5oJg12B_+Q$$7^aTUpf#>5m)UAuuV%3FJoOd^V&RnHHcCHiV<8 zyI>fBaRI`1w~_t21^aayCA%3x$YflaO}N*{p95&L4f#MSY4GPP1K;C9V={o4gNz&F zAf5}(#+kcpTTE@NyipmKVM9sEFg+)!3|&&O%bKIxnpcclVD337Hl!(f0aBoxp~S5J zWD(X*;tXV%mR`uUlcBO`%KK8N7Yze6)rMTkNG(18J~SHjJ6K5iBu?(ZWq>hm`i!5j zHy5Sp#g0mDgS^wvIRue${>pp@BrM3i*2MyI7POyxo$GRF4IXB`fPr%BTwM@0+L~vB z$=tOrdrJ11Is!m$y~}37XZ`^QavNN4K~T)K3or-eMqRe~hRiN#HurkjH`_c9uASQ` z`(~RLfXv(`k)Xkw%=-~)bDJfYZ@xPjV2kVa6~r7Cd3Ej$vbIRvFf?e`bpuX4Q%oC3lDW?o}j7G5-RQ zKX8zY) zfVE9Zk2?Jv) zlfKJts|asQ|F(@tH)hauAJnsm7Wtk&3IBFe`fY@bW8ggfcAl6poXDE=u1jkrw#psz0=(!T%Lz*!MDMtG9cAaiqN}_)A2SK9O_)!v|7d{n`&nSllq`&A0VHN|# zZ*3^e7*4idvZ0VMZYZFaZ3t(atE-jtS56Bo*~U7UQ~IlnAe__Y8-R}6P`>e|3g~x_ z2u8!k%dC5i$-XPA$asyE{oc0VQsZfuZu%Rxm`jZ-ivYzJ!c{1|6Quer8(L_rN6zk8(MC>I=? zfyp~{QRB0jeNeNpfJ*+O-EW=YzO)ZoZ(NY=KqATZku=d%B-y_x0r)<9GRaO|*?3(q zh$Q>;^1j+_su3y&_<`MchiY7Wb|1JCN9jZJx^g+t9@VHJ zjUS~6@QBNJf(rV?KCV3KGIYxJ6z3ggU*^O-fU3-{kZnCt2H45&kK>5X3)n5|Uq|*y z(BU$-Q;o^0DMowKWo{xZL*(Yj372_k5O9i`2Hm@}0N24Z(nBhp2Ad%+a~tAt z`WR=kf!Q5BBtR!bQc?^93@nDV<2{1+7(pu3@KYal%o+PuK|5qT$ zJAUITR2mOnqA24xIizxnYJ97+>g@rN@weKpL_Q19!T&c{g*JZk?d<$0cpiTT@gRg^ z#-HHlsaI-K?P_I0UCMCd zZ!qblm*aKh??v6u@z?)yGBh+{eGbgXsKrDw;j0Hx%(#6CCXNYTBU=>i>q&raIVS3K z;`_{5!#RV8W(SAW3biR3@}`+BlTZ*AaQN{NyUsjLOro)vGhojGBW4Fn@@c zVfEW5<2{9ahw1r++wnBIP?JA}_s~d42}GAamAB1k6vKS^GrHJl6hdl#@iy7$W!P!{ z*+foi?}BvlXR;Z$CZ4wdm5>HP-RA+CWw*pmD2!A25LJ1w9+2S8FU`j2HVI|@NGO*i z*!bp3e7FLYe_m5>mj(U0obPmba3}`7z#ddLZpDU3{)M*+(!EAEj3|Gh4f!a9$WEg3 zv&$uT1J#PL0fNlG>`nne2zvhIPqES1IViruzLTY-u2@yAE6XXb$3;7?uBi_H7r+`*?MC=ZkmOHemoEko@y67-r^16%M}3Hr=W zvjHBFV8DC;(|z!l5==8^!775!%j7d;-jfXQWpTWPC1OSkFH*eX3feQM`2*yS!B<_E z%q8{t8O^Je;A^g{1r#>pUVZv7w(; zv4YE4XFLVREx5u7LvLAtuB55cP0r5*bd?>HbYl~m7hLTq2*2)73a+tN3|?am(wu^7 zp4Blm(?L{0jXiXlu{!{0)nyA<7cwrz%v7+(<|Z!{|M-wn(C~n$3mg1@sux7g*na__rr%shXrXZqjIyA)d=a6DaT2O3XrV2-vX&T|F##3a zxIolVyiWi{?jKTMsNtm7!BI{HhEZ}}L^Cz#eoP;(oKXmZI7s;#jL8?CGGY=$Ti>XJ z66X6!Vc*K6{_XGifac3{ILj+n;*b$FH|<~u+@ zcn+H({-p90JA4jz7qJd7x)IF7r7=+#QZ&x91cY;8LzoZx>Cf>z{x{6;zv z{zBvy)4fv*fb})VbNVowd_`P~oo?7e>&79N&vf58XvS^aeX!N(BkVe#@eRC8_g^UL z0>~!V%1I=MIM51vgU!sxd+z>pSmyK(uf==LZx_=tPoPA_&bJ@hoU!`Xs1TZ+vBqBP zD8_U!G^3XM(D#0&1G?6R(ga;IuIof6?qrdY8Fkf||HV!g0@94NHkEnEhb}>@-{b4$ zA6N)!NYXf<|6QmjJYy?+8efHv%(&|*fyBN!Jmc=aK!S9J?TGI)w%N-V-QcPwpOC9Z?9LTN4>+0e=p*=x#jSA;aLizQ1XM>3(Z{EOYNq%sVq=7GiLoiOd`WfdC1-W;7s^+x+Bz6Edlp8T?;N(aHQz z0rbwyysWodmecJ)BFUZu=VrHWSb%co35fTQiGX|gUh$_G<>EpBsN}5S|M4Z*Eh{Nu zxuB+GmV=fiS~A-S5p1OBGcRf)Q)>~HW-i()C{T<@CZLOdBp{rzs9f{1E;@usw(HqCp`P;ba;p=Kwxh~V9<^D4-{Rf)2zkw{kuo$R%`Szlmwc0g5>s!yegY#>Xhc>@T?#!=-epOzAVEY!JNz#@Az)d6Z&bDF|#vii^`rWAG)>x9Z2Sov1BZMHi@bmM3p0{Oo zh6aB&cv*S2xc!+YhMKuCt8!Y-C;we#@!rY2Xkjkrsw1l8+~9y4xsTJC_~6o{J+7Ab?3<8J8RQeMqbRAeYBn0%+;p8%R>RE<#eaAxGPkm2-zWy21CUMGawp8p z$An*YxjjqiM$Tn`u6RU@;Wa3~GMS(IjLAy@U2Shr1`HRJSawYS|-ewU#0Dq}h(&awvkaH+y5M*J;{GRE-d2lrnE=z6^K?PST#R1*)au_I}xq?X76tczh(PeqxW{6~VvkznnD< z?+KJWW#1FP90}(ud)l4~EMqQddB#R*8TXC`^fOzV*~UBP0(#bl@{L)G0R6&tz9M7p z5I{$dp*N(PdgJv<*{|$%VAS9}gtF)8L%4ab!b4~%b~tTCd$0I&C*Dv+GfUEF|4CW{ zitH(n$`;K~dOzNWs#LgBvLEmGi5B_<7Gw2=_;>^*{y)OHi_5;ha3;jYdA4k?Ee*wZ zA2U|j4{QkW5h11QVK!r!dVs|4x254Vo(lr{p}pte<;tn-QJZ0(@q3!6gaXDz$$$=A zDvOG>bPp(?`ciJMLHPU(+=`;l+0U4Ym_JgM^H zzRBO$1wWLS6m#2TfPa#pX5Ipq3x1^9r`Ec;65bj7Sb|<9v)Upim+QZXX*YnN+hx;) zt4PQ(gPH_2^ZvyEJ+3!|hw4gZ5N?t&<|TQ=*s~Fc$=;Nl-JNg^2}ch&xu4+keB1f-}VxE5u}T z$x?u`UA%(NQ?K_iqX$dnxY_2N*#OU#V4nG1D(F1fH{bjN%qMt(thJ8^gBQx9#Uk@B z2mrxF@&K^dY=BV)FL7~AUG{P~YOb9CaIwo?HLT0Pzq%g0LNLeJVvZw` z6+*_i5UAQeyQmVva%bU&iul<@jm!So1#X-ygC_-73*`76f@xs}>*+T(^w0C`W)x#ou( zDy@0~j2kK^5U7G*aoN8kzzr1_y>FASba6xFPnbf3cezT0ypOufo2LQ3$HhQ^3!H9~ z|M$J%w;cVrvHk|ZZ^5)h3{sW!?<3lsc9*|RjfsnF=w@fs!<2U=(puRk^)LewRQ?z$p z@-qI6%&7b?Hi+{lp8Ayk6;6m+oIf$jmj8{U(%uaPq9{N8VH3eU>cmeV{_?-CL#?VN zyR-JI6CZ>pIwkl&SEJ+-St?Me@M;Xs;692E7udo-LZ!a)O$pT z$5mI=yl6JyBsoFAlM0c6mM2RXp0gMcr(9Q=Pa>^wnJ>dr%7@6iQLy~KQ{pKShUGs1 z%Pk)&??%D$XOP8!q<62&`UshD`AD@-b}s8ClI#>wc&A9>os34~m#pkkq zirKQai1Kq;?^`GeO7s+<%Q{MqN68|UMP>l*SDvQs5<+~$Wmb;_Y#)a~s4nx{7Xwb0 zLV~+}EdwxaZNrivRG0Z0vcd9@ybyNWW%9tee2i@WI*tetKFUoAceu=Mnoov=afDbk z7O=xhnk$;XK(aq0;jtyffMSa5CWW5^hg6+ZO?zAmO9Q zW*6z5DCz4+HZP!&&Mzlg*E>0$d=C=0vjjn^eGIb<|fm{we;$0gNqL z4TilC0YwCv;Y#49;UW!VQD7EWLQ1v_@0t8<>#X1e@#9wUYnk9g`9oJ+B?fE3N!r)o zZOl>r+YfNE1a;nxS_q z-baheh-AzuyZ;EcD*eUrdN-~Eb z@zI0Vh~FKXJ5dr`A@(JhP+f+=(FUR;u6 z#$>^Kf(_yq8BCFumI925-~aL^&wGvjijN8j`VIg3Ha>2pYk!O0dGLBj#HqxW>%10RD&I z&XpB4f6i3;``RU7)|J(4z6Xa2{y>83pa=d^JHSRz>4j*NSvZEd=?}Gbiiazx;3HB1 zin;c3fR9Sa>gH)Lz;-DQuX#IpIv@@qnO}Ybu`BqPzysl7DE7fJlS4;rCJSsw9mI7<;kC zAB#FS(LB5Bw0M&8@Y^%LW_sfG<#oa0XI&ERKKjBn`f|vbKRGpNJCvS~S34hN2{S z0p9tmP`vy3&R>M$Jp=Da8c%=&p(0UI$lCiLE7Z>B`^V$N`}uhH9~cUm6^z}2cjI># z;P@_+9teS?;vZI43bJg-7Dz!ho54>oz`b}&=G;0`FQ|J0z^KRa(0eTx-=pG_@mkLX zwKC>?47Nbc{U34R(R{N2=Pt+OS*~J!2NKSGK`tD0a~V41{vYDrJUpsmYaiX!y}Q#S zot-9WAV8>uB%}jj2oNF6Ap}T5fDi@)Ap|4@6i@_IL{uCP3Mk@mP*Kn$4#x@S2?bP8 zkDxdq&N$B=2b@Lk`>v{P@cRw-{&({{-Klr2RaL82RjnF!?dq2;jOh9GfUj7Xsk=-A zeAPY{&e5Nv8^m6-YoC1m%mBdsc1cpG4^jAa`;@r59*=P@cEHye{fx&Oi^c%H;X8n~ z$>+j+DL?k6&vfik-3^0I>@AN9iG1-cWa08C&v-5!^(zb`ohN}kMeFo42F+=>En}HZfod6 zXnwJ;eAmq(-l+6Gmhx*krYS3}H)+prd_1hlsi&@M2mGz?Um}l{(p^mNd#Mf1=Q7`# zNkJ@uUVS3G^$PVeGKa99zP~j%NX4N{&5ZQy0gYFe=4- zelusllBXjJ67UyEdYD6X%>fQtj5*WqG*igWmg&#KoM}lGaI$|VOfGXKG%+WZ=6^&K z#}Z`@hR9gN;vJY+VznAems6Pjyr=1b*nTr6reJ@f*M)q}?OldG*6Saq!*p~F^1yx7 zHG*944!G`K7d8|$^U{dlIy9hg^< zQBo7WI$aJ+?@+P)0P9LWFbV2)kvFk9nho#(3j(I8hV(3W4HaLViD_VVQYP68DO`7X~>y+1;)NuQQ*ttDV(EEX1#O|6wN2h*H`ug>=EcEuu!L? zxyO12h70Vjcjf^03e*WK)=QEAi>(?Zx{+I68OwCX z0APvSgn%7v9UKFAOyDjl0=md#zjy+2~oGA|q%oa5k>FbLChge%J z)%C*xhX&Zve0eMMTo!+raAj{{d@b;Bi&rTWc3p~=k zbB`YMN;>eUz$wUFdeBnLJ7S}4df2PDjM`KNrZkX$E3O~G6fst9)5qj{F`8LyOu%fB zedW_xbcSOCXGnU7e7YY!%lP;m2Yx*ettnO;IA0nzuDE!#H}DjDg#@m+7|r<8>>UQU zvf`;U;F$sQHVUq+_zoj`ti|GOd{Xnq7>uuMEcIwYU-Tdx z6h;k7n<18$v>7pmAjYF6cv6%QV81vb5VlgA6MXg*;Um@#gj3W9M^W|*g+0ck!6Ppa z{0xNlvIt`LF)WrcK6U&H{ETjBu(cIKd5}IGzbD~T3^V@RNykNiPDPpRLGs+VVz}|S zVedEe%8GLO5)S5kK2$NnKIf6=LlqTf%*gb3$f9DTNhQl$0&iF`%Ji%pZ$$^7(Po4w z^fqE*QBi47u{Wp`sLCKb*@5$_s76CUer57_t76PMf-0SiP5CI($RX{~4!w6#oRLF~ zVtB%cNz=$-=Dir#TMM&{EX#%%2jl4SnA8%ZWjx^_iBXa1OoC@eMzuD(8Rk^XsPuS( zd=qh0hS@5|u@9UqaY{!=9%r;(BXGNG>z73-$7}8flwnZFTL8y6x{W~*Z%F}ATSnqj zkbB|AMz`ZIz-Jr%;B`l5?iF5lbN3d3-R6V4t=`xfywq4c& zbb(c<(%24Vs?62Dv;o|yOf7{puPli@sZ2G6^=0g|PbpI~5#0t&Blfg1=FikYOp;=| zEX>hK^q0FWgwI1&#rDd9TFerhjQ$fbcd0z#Fm&>6faj^4AGgXQ7(*%-#I3SA9cW?P zDz`y{$`cLB^!|bat31h|94~;TQMt&VLhp0bW97*P6?>o50WCJD)VmmpS1vKuEORn8 zqf#;}&n}0Iw-J7&a-|V;ypK?ImFE}~@sMI|uG|$P{4a;R#UGyjoxVJZ07n>yU$OiqcYPCTj zuRS_=)f!t1PUsEvg{rkQd&XnPthVaX1t_uCip5?RuYxJ?3{{sIHGJL%s>qumk+JKY z%A#G)Y|-JpM=@)zy279wuPv4%Ract4O1+*QL8p;D)jf|&2&N!Ob33D2Z2LZ z1rdDcc?f2l3+>7(cYOpY)6IADz$Lqdbn|Bn!dx#MQJys@;B z;u5&T$~TSsww?Yhv^hvdjC*(+od_su+`~HtWqPmoM7($7YMxXE^j=)eJJ0|t4`Qx{ zc*Rcc+9)1(Rn{shpdX;*1lfm!GI|#pbY-35JN(=WCQ~+jM7}EXNTyiW7>kZ7UvzjGwBl-z! zmsRFk7}b|xf?SzrVWyq7FrP3RRD8xjCCrS5$%NS*q2~mIbMH+<0+lg!9^99Hygxvp z+JG?itj`AQs_qi#>JM`PyQvohhV;jNz#?@>U|5e}59zMbpb)#nDmdKA9+n%`f0P3D zRK>#0)W2W`QQ6C?ouyB#0W4Nygqx$kO#OrG5HZ*j?wrAyk%F zSgfbB>W;D2E79B7fBIXUOZ9tbaFqkBl7sckj(~&IQpu=H-^iLAs@4gtuoj~+!kn4K zjY&%xW706ff-$d8P-!0%flVzQ>;44)bMobjd_?^(2uWO&VU?7Sq8*Q<0@iN{R<{I; zA+R{J2)btoP+Do3gNgd5hUWCD)1FrruY0IXE+ z3OA}>WmBuN5KB4s<7)MnaI^GD_+L3jWlMj|(OsBtjj9%yub*eT9BUy@pVEs^$0H_@ zN(mo5r)GJKB-Q^Pk|_L=1pm&z^9jM{qzMNA6H+|hc~mMKQo?fN6Jw2tK9UgqH6h9n zQrQJJj;-K?0Ly98qF;+Qr~s%&m08x7$c=iH=SVty>V2>n+;i2tNEW+B z*?c}(d7khfj6F|u`XnAA>E*_H_=Kov5NP#f+TmpdHx~R+dkwE zJAEr+zz_2bx3yqce(q=GjMDK46Snewk7}d)M0gm*|6PT%IpyFedzKsI2^blAo zHrDr$z#P3CliJug-$;xo+{P$u1vuXKvTzIaz1;z8eSZk-u1}-Rb-sco3K#1+RC2O! zl)w_bt25xSR;yBdS`@I}*CO1(`X-n;HqCdAz%tv^wxB@f(k_P3sBXu<==&JJux_TA zOpByd%)4*$rgPAJ2!s?x>qu-wd^sUZBZVK%!Iw?*qXdfvi%0k?L8aYH>Jp2$#f8~3 zkZK#Sj0&{oQ9@iGiIDl?@uF}#S_|R~OvItd|Icw)l=y!8i4vzCiLzdd_C!eT#zbMx8U!xZ|%0)Fk+<=_B!>!~zg-O#!}>&SQ5tCx9nQv2%To&qR0dVcrls z&+aKZI)I6I?0oy0zpFp%1bBhZOlm`VCmKlX!gyEH5w`z-*sb1(9?%YOmEHI*)J<%( z7fIJ4W61zlHq8pmVHhihwfUeL*RC1l~IVjA%>=CH- z*m}#Y(No~>Vwc;LYxPB=0I%@9Cc=~SiwDp9VjJyt{7k)s9ek6G+pNb= z1-!wQXdbM#9#)I)K{?Sco$w}X2FZSO@$8mc#UN5j&vwLN=bST zVP-%1PJj%Su`u4?>M()Fli}5==47~eL!jC-^U!=b6H=YV4RLNr@CEwnh&>!AdqUN% z&2CPK9Kxu!dn0@G_KLOUD=F1(kUp^k;0uA}0>gSM&Gcem zlfa06Fa>a*g;9NM1n{N6cHw5~W)JY?z$XH;^!hTuR{|*unNg1JS_SxOph#f8K5sDK zYZex2UNjKf9~dRv?mEhj`+8uOz+(M7yXJww3V|h>Zz;syu-sC;of*9u*eKk=`b%^V z+*-UBRj&1u3M-I2q6SGoU=qyJJ?d^gt|)9$V>W``(}7Zm6@H?ab` zTUe?KN&$PiJi$a)S;Ulk*@xW~I)_cZx9c8HZl&JR1+b5sCa^~H2FBPx_dD+Z_?4ek|{TwlLPu3C^a8mz{_Sm(P-0)l}E~Z6fgxRd* z3&v$E-2VoFIK@FY_a5k<6H9hC0O;FlkxGhtr=;TO)wE$ao~XWyojlduE8LLLz_S{J zjRt8}IHIrY0pW;+QGIhCz}7b9Ouc|MO?SVMq_XT>gW3K~W$I+6AqO>eI-f99l0~q1jY;b*?a!6LZHyh<@I;_53XgWj zXc@0!Vc?F5)-ee>(J^i6B@$X=Ys@4dMpmD2te>=IGnVyF90B2lda+V_$Rp(Rip2W5 z_aj2@O4_@`Jp?s-cg#lk7`H#@#j{$LU>)GjK-kG0GY$I3RDgX<^IF1~FJM}#qc292 zi1{sa^=>vDS0p)xPT;5!2$-JCO(bR-bd%Blk{(BMz|@w(bY!1<6DDIhvHt}5WK*u# zj6EN$LiTL(KeaEmtZ*a&Gazi?W4*SL6MKbz?%^xoB)fxB+1fG zO*{s|F9*#O0@ppp0ACHRmOh-L@9YiuS^_=-+s0l`z_aNP4M zYj3#`J%NK(2MeS6(j35!)&`k6hE5gBvM@{kQ3%*6Xm;vy^eqzsb#RlYk*_z=IcHl~ zsDGsE&I#@oE*=_p1MD39L}0NV#!(>G=3AoIw*t(w8I|fYQQBCS;HJea;9&jvRKNlY z%QWx5j1>l-6K;i0O$Y26{6S!)zMZpyqF{#9Y7Oky8zxKo4n_>RgBhHQkvQm%X7DN` z9Q_cAqUG0kb*T8)7C^=v2iQ&fEpl`J}F|W@FzL_!P+n-LLU&JV)CF@C;qi zki%8{VjDJ#B0kwPE4=oy6V7RnS*OXGiGoOo(arlQoEI6sZ1HeAAk0_zAk;4*#MzP& zlH86KYDfri4rN}5ktJGDTqUHmQiPZ{r&1;*QT{Cy2>dN35rp4N@EHQ@ApS*Lp-IEw zyF`r1aL#2m6}TLtoTs(j_|oi z=KRj^WkD-KiE4^#ayXG3Cwy^gcZ5w_;6yLX1(r#P%|Kq)HSGyIWC=;m0gn=rIFcPL z4Vx?w$-5Bd^w3DMN@Oqt|EdI^%O+!KIby&l@pA?biV(?MOdTa;&mp`ee8%AF>d3Kx z_#uMd6MQbWj>Jd)9YHXSfJ?6*Q+is0h;a z8G+?b2yu;Qgc6Th2@Kt1y&LW8SfxmSrg$nDQ}wBv}Qz% zJaQ(bCY>h7>yQ4=-DydP83h6cit!5fGXtER0%nR54WO*?aTCP&VY z)MT17h=tfuacbIkI-k+XFWn~$<0JS_; zhUL(vG6aL=5OzmE3O|fw2Ksa-qp>ZX?u_lk_i?-rF#Q{=ry@vWzup5V+aTBLp9_>@ zP{>QhY;0_2gTmfVwLrN{nZ{l>0VuCoP;2iqOw`Bbj}w&dt;IZTY!`zHaVTdfR34Yq zZz(b#5ptYy^1GJId>7iwxKMl8Cxb64MaH)}gNgivN$B{L z%OslP-2lDDhYj+1RcSz}6l3Gz#kS);!}A=Mfz@D%y>MLU_s+P9Gv%u>ry@~qg{6G` z)@jBp@8<*k_a{NF*BV-wH)2+;S#1Vy};1_S*tK~U6t3p2%( zLk4Af+|5b(@nqp;d4n+bO8I$>pd4>E78ohN7|DDuSPk^+jlwJRR!jo=&7khy`ZA#3 zpAlZM$Bmnm!(Rz1@uH}{l)qY?PCZNYGiVwqjxvc3)|0VsmZB^y)9r(RJ_{>kg`MKJ zuu^wK3rle=tkJ8OX+Y&m%C-7o<{GrzNxCy^o|0r?y?z`}ZHRp{fDe5%g&ePYF0;Z}B0vBlB-<;y9M+7d?J!pxjGFzcb(f9Zk7hjzV z%a;sQ>}2RC^Fht69_u*UQraojsw~@5G851Kd7Vc}du3n4)7*?r>7ck{$^{iym?<6Y zQGg2Fm(3wdu{UxPh4;Cnbh5BUZ)Y`|x0i64lzx?EFfT80qcAocFvsRwuh(MlBBis1 z)3bStbV{y;Gxe>#!OgP=KbrL*+AiP17JUvpWJ(vsp3RF_`3hc2fy9-Ap6{~4V~WT2 z<*4)zD1J(zqHW}$=bICNd#LAykAt2u^r@7d>LtNAD$Q2|Q+ip9gP&6|l%^EhSJm!N z^6)REpW@qz@+w_V4Ss+7>e~H$=|JUVktK2N9UBFV&;j`n^E;IwZD>tauo@jU> zd7-rSB!j}@WNViir-%En;ACr0F`g{y(f!n(YEY)Q$J*0coxvQkJno>^E-Mj~BQCdg z`BXvq;yP#SXATxYS@>>-tNPM3Hk9-U$Bc}AB~@4U7^tF95= zV6PRdTYIt5rA#)aYS);3mkPNhsP+<5qDoW{=M>aaObd(AK!(Z}8IP(qft)`;2yF!4 zX%H}?EX+}&($1~uKqG_*)chzRyF6_IHAPW#!;`o&tD%m_w_I|-Cp!V{e&v0=d9~5DQ0|#1A7c=%Fz$+AX85z6Y|=avUH+UY34SOAbC>e}82!u~ zx%_#9!rpP^;O*gIeNNka=t$*z4a)S^v6L?ulw;oLei74hNEUkhEtv9sX2#szd!rT5 zOQ!ZJymD+6mA{OHAzA6|#jsKSia|BrTz)X6lkRsMUzND<39P2kZFy0`BM-M zx_S6cV$}uR&8%B`IKD14rd^Udd0weW==mUrqI*iJg(B?7*->*lo ztx(U;K`@iSj11IWWWpU^BDxntqnU8$*$A>8zd|3Ma2M0%EV3E>f5P2{7xHRQ`xCaZ zTVm(Sn}rISaF0Q$-X&<{6Yf1;;(54`xFg_w7X$VwoX}ZabvC9U7j_0MSJ|BOKdEn? zh4?+nV*v9l#Bo&S)kPUa!uq)(fCXx)q#w~!asgvjII7p8<4!2FFjGI?9B*%LY4WX|4H)1FAtK)S&3<~0Y#idSN&l`~doI(0rqFzh_7R?+l z|07Ol^*|)hr34UXIq+@NAlsbq5;fYmb;YNHgr7>B>(udwSe(vFmM(Vc`rK%!2=?{P z0Xbs|X568=QqsM4J&^VQ(`FrScM8xz>#302tq@6Ksu{P`;G}fjP$rPRaMm)XuFS@f z!K-d~doa*MOo7V(R-h5KK;9c@!*vxVUc{?FpQ{^5JJ9eP~kDApCkXoWrCx2IW9u zHt6V~p)w)ZN99&x850WS1nFFl_@rILU6^22#?k2RRwHX*~J} z^*)sm_n_g1`tY_tmWmhqh5B9v2D=+C_6wCfCJ44fsY3l;78LdPQcbA;XM!@tgNI6g z6U3)m9DLUSh2@JwbbP0RdSC+#-$sh5A0@`!?2`49^&qlxb%6?1V99{WgNcv7jNO~K!6LeQH$QsEg zACAN)7w{L2NRrQMYxEEVS%q9`)?`l-ds%ld3A1-( z_xTG!NKs77kh`KZh&BQQ6N3pKVZ|R0OcOq9h*=%sBkFPxLeIeEO_8Hh8GnsL@unO% z`2v)~PjWMd5SHV1bloX)4f1&nkef2kAlG{iesIe11_ixiV9hBf7!>kO%K^fzVN502 z`??*_i3X*3O}&6lG6;9Ip~FvEY*4D#x*BMSL7w-l4```DY2IT!fKIy-x?@;3{b>#~ zmj0CCWIWRaE+qAheixz;9eTs9ylEohKJ5`eZyBV#MmUz#cTPmo+<~E@sqY$|D~hJR zXHY;CO+9E(&>Kq0_YF!C!=!#-QVEG+Qa>~(*?WzW9~l(({t3NOKQ{3^Z(3)dPYg=) zIuU(pP{iwk$!6+j2DNr_&q%`DIkmOgh7xHhQMxirJb`7AGAvYje*s_{WecUdWdOFd zTvrcay6r3s=o#q3shJiA^?UFOsqHOH(){hd)D9Nn0<10=4qB!5QxpCX*P_2=S}jT~ zRC)nsxTymz^yyof&mar^dhfA-gDrG5>pgXdg#pcqPaSGuP_yP!hgq1U^QHopSqP=R zX+@Ld%HMHy-@nA*ixyee**0^i>%C}yG3O_*z?cD2xI(al1?{&^6%MLyfHoLm=O zJd`@a_h2I7roSgVGm-GiY(d8*5?)>kI6IN>S&e|r7P@*QZ9d1sfc}fErp3abevze} zYhjYpWfh9+rUw0=L5qS6Gy|vLu|m4pS5O#V!4|Y~f58I*2o)5JML%@9%!fyCQ$2t8 ziy-?r`k7PkBpRwJXd2EK&!brWf>|zO1j`Vk;3CZKf(5@QIKYB3^w|)e6k|wpk4+xK zB<@7APC-{RP*qS4|Kf8(Ut)|rHo^=-@1a?bsGWr%cKY$%UNO=Ne9T62S44J>aYsy1 z&w^I)B<2cE!8Sxv1?_rLp9e79_zOOg5`3IOeFkDo4i-EMyCfA{0G&ex51~k{3Q|Ym zhi#pV6g1(i`t<%6TYq1lagDeUCw79wuWZE8s zvb>QP#i#8xD93As);8@0gYvz9_5ym*ph9m>KF~gcx_eh91HEKWv9}WKW!lRIm3XOW z;nQ9*sMMQJ$yW^;?2SfsPkYUvGPD-jV+#r%<`=AeJO1Ui$INhZ!x@TVazRVO3PnB) zm%YeoI7>~voWPYIC}>!z%tR)nd8)YK9J@c-T{blv&Q(n!T%5gR&O)c*eAT6vaZ7OF z))J>-l?q)#Sf>AtUfOVxT6-yBg`R^Z-mqHc0^E6h5iY7>t!kE7*w8BV> zA#y#pn{!MGDA!pE?&o&(6l68+devQw5pudci?-uTZcno~Abx zz95xors)k`zY!Ec>*C~_6&#i?F0@c)4}^?W@FFD*eHl^Kj}0ZpQ(#(38y|B>(tvC^ zP`_iORfN24C{jcJ#e%}#9B9=rU?QwbFT(4j8wQ>zDC(V@12o9A^Gtb=(=gbeEZLuF z7-D*Lj`Zq=VHZifeCgEP zqI0e=ebfBXZ^Kz;ffDlevl7lWl40*|w8DmSTvRkG;bfZqJY&A7G5h)PO5iiHh6{|@ zvy9mQ{6PSSTVkid@8}B5Vb<6V}wScigbu7#CvSaCNzWmbj} z?;JX=UGet*Cz5N}-By}WrgtAkm4;_~3d-`%!~~<^xxcmd=l|B;?Pz37{lZbE-ZxN^ zz+D1O5jMd;sF-PjhyT_D|J-I8uq@OY{(4&wn;;8p?!JhCW~zZ9us(!4z##|-q=?H5 z({F7|Tu!o~|1i_=Au&1N6(qfDWrwvJgEQ72x<%+ypri)L6y*YT4H{vYJah{|e<$NwO~ zXV*T8e{>=~uyVg21((^dSWN`bhuIoVOT5tcI(&V@GW)hTeyHal`Y#$TMT2e`vcSnp zF=`By=v{D+;GT?d#)vG;pMw4GN7&ob3WB9vHE{ma2PO^ivj8Gg#Xnk$A7hcbGy3CkzpU z+r^pPM3WtUFPGU(GTG&OC$jn{8&rq`CuqdbpPAz!6-$wWDNt5$>QxDKrg2$Fb)HIv zP!k#4E#kgjaF*HEi zCwhVKgdyPPGct>sPzS;7hJc^X$Sisl4J^3B5IT@>avKnK8bWG;C*q#El(!viEclGM^z>OyXhxtgL6?icjCqsL zl7n9rUIlxJO}=I(uorI4Z*hX(#BahCTYgV5*b8S^kV1a|^HitPsc5bBDww101x-ua z?X0-JfrPYFbe>$T!_iZ09TQ3PY@LsRDp;hRl$2}rw^6`e>HwfW55MLuO|iGVtaG1F zOUvjZGh+O@H-0gRmBz@jxsv9%FC)y4;A|9=?Zy2J6n+xa?+`7w1&fqOaF|N@C$#=4 z7de-yRVAXelk4<#oU-63Y1RP^wYEJDqz#2QDOM^vn{3AgbYbhRWbP&_P;CP#UL>E)FI`s_-z%$~nGrNiE z>T3z}bsNG-cD`GvFJSAMV&me~d`v@wjTV+@{*p&z}BpH^E$F%x{wmakaWAi@8r+a+#E_MAnSR6MWf z5^#_vn-?zy_bSs9=INQ336=q8<`H z?y}y6mK=Q5Vq9)pz}~-KJ!ANO{U7$U1NO4rTmAZLn&=IwTz}rb{hGf77JSp<+x-Fa>*C4%PNm@uVDnNSIk~#^gE5`ERdzO?Xq#NlK4q8%2AXw9{Q6fG;uGnSxZTdLJC)Vnh5x@yRhRWOwzStmMP- zYn=o7W>&(V_Qu~00bR^K;Mfbxw+3{0GO&{ONKyWP?#xEuv;2nxIsc?Su8*D&ULH41 z2Xa=rAO$Q5l?Kuz+CFGWs5Fr3F+>HEED4nc61;~K3|SH?4Wy1VcPmRmrELr7ce;U; z;`>l6v?HMN#sG({hEE5e4c$<5QoX~`b`!*cF1=RJr5AQNrm~4zCm3`&th#g%@5HIv zi82$!CMov{bk9&Q)!$|#yc-`_2R-}K)sE&{tid#S*$V#K$-N)u&I+dc%P5H49WYF!P))?1%@@Ze1a|hmjp&M_k4nL z{htbqYN@7q7UI=Q&Vo*`FiRKGU(B~KNAGV0T##!C0H~_Ji*ry&ixs>MS}18`(KX= z_=%13JyDbu(1$MIpoOmfnk9eV!jNo11V6ALB&Ri9$(PnX_&u_S(>LOQ^rL?r(!x_re5a@z@g3$DD7WHYzf%?; z=PV80=GJdUhCD48yxlcZ6CPCvf_GUM*5`m6ygPBf zu;_lTeK9SnYuOF&w=he;&F1icWQu{;3_TA@H$&^dz~lrUlCH=Xqf5s__F;K!%-2G> zX%l?J=2N2k4hMYHa!d6lI-JL>%7b-o7;u|gj82SQx9lZzF`;xLHxO0mHY31%!lqQI zM`I2X-0qrJ_G(N;?Xa*`@1$qk>6&>pUdyFpe9|UduWu*?e99&@U5D!cpSEzOUe1c! zWnr`CZ=MIAv2dQ|?@|Y!wJI;r+=LB2=duCthUkykeE#FM6`lDz^K4_eTVU+s;MM?( zVk~k`;!VBB*b(my@U#?rytt%?1Gh&AL&nsP2F#QvWQ_ZmjT;sNZ3`4hW)Xc%7E*fL zGNU?!b-3NaOr1~ejzDh_&XU_of=^m*jw!}d0rR8M`Otd?8kqYvdP^5XFtgogHO74S zQBrX81PT^=1X{a|dO9ctZ=tI=1y>G-OhINX)GydS72}lC;YswcRjRRum&th?VjIVf zx{1YeJYFf^IF5&mP0Bv*JZpt>55Wjo+CrQV0IYhyhfk^FpI8!Vw3r!ppgZOJ=~0ya)# zRQ@8GcPHU=6Bj>yenv;YMiUo5J#jhQc;gHc7e77WVgzVxGI8SL;)6{CViF>Q^Mxv@3o3DpaFl|xZNq)dNMtCcJHoYxii%I!@<-O|x&NJMH zl{dc-@OT5aDUZJd(Kw$@M^;2UYSy@5Y(K(hm3Qq}z=e~ffCrSqG} zjaNQ%v#DgRdm69e2!QroRGI|zPgW~_g99soqBA>zu)z?5B&@6e;c7z&fFP^X#%oMV zNcC20u&*`9^EP3A-MG=9G;afn(s&)q!`;7|Y1QiuYVGZ2L)c_cx_2EWijA8M$}p|+ zhP|S2RDKzy@kZlhOS})+V*X`XWvRTT(Rh>bxV7jMY~mT~DlsU`=*a5y`k@)j$TDuo zyhJji6WT5ma&eKWGeaAI-&i?isWT(nApFK9`o)Z#4{j07k!}sr%GlB$Ym~;fXh<&) z9=Y*tJ8SSbdN;mf25;AxTxF0_`!!#&`OVke&dIq z%a~u|wPC0Fi0z8MK74Wx&?kS2WW6_M6ws$pQE$38tsT&32F>(1Woi7PKzPmaYmtp# z8Z^)QZZLRX4;J16?;iy~-x#z=wp<&(Jyv*2Wy`hkJCo)zId|Lm<6_~hkaM?>!1I;7rqC!aCP0 zs+C6~d|9ED-S&W~3nL7wLV(|{8uVmwI zZSm9G;kXG6#eE0W#E;C1`8yr-&v>P9V|+5jdJMCt#wTH)gJ9-aG`X-4!9^I)e~zMb zK-kE!3}I#hx$X%ntIs5CXJO?D7HiL(@U^iTK}b=o#&|l*62h#_Bf{aM&&^*f(O82= z3D^_tcMFf^mL%iHI-dst4-e7f``3?vedd}KSlX?av*Tyo+_`M!1A=Hr?pzWf+y?)W zI^Zjf{%>GzH(0Z)@{f}!b4~-`MNk7S8wq+h3G$e6pol?d;LVi?PgDNI5H~W@j>t&R z8Mw6`kFC2X|E)~&cm%0L>8S{iGH5BzR<(*T^TC5LuWwaIHWcG@Zs0H2wrd)%{68@L zo=E_`C|SA)XAGNqU9t$&N8osxdT~}UU|~uk_#=jrre5-XSN|$Bw(xRA5r5=1$i0As z!pqmf0XqY$QLvfS%0Cp0QXT=D*^dtaN{?TJ5c3*vJ=*fjexlWoLZlITMycZ=?dR7} zIW_i-ys9#E_M%hBwFTfg!XcNB#zBU)%GARpj4)?WGbs$Clvm(i5_fZlbU{&5H(1Gs z6OvaO$stXtVBcifuP4}BEPETgb?SD@{wcxUVcEB##HnvtcAJ04)p*;ogT-KfX4xeP z_UD$ZF{-BiXxS4J?4K-qR2A4hpDE+w1l#YEGWNfI6l!_A?49{91$O|C-3=PgAPjIN z{w49r^{^%QYAjO9zZ0agU+58vB+W8z*V?c%>>^D58+$BS z=#h6jD)Bh{E}XBS9K6y+2#_{-S{;NMS+j%qv!T8jWDkBf7gYW<3w2_5=wFEe#6Ls* z0iW+5iHL)iEOPuaMWX*tX#5$IO-2jAD_wd#FhvJkUO<*Kfq`8x>fm=7{5MfVbm|AMO&cKV&6q2u3{tub#0t6WtbgGlQnH>uH z^WbX#H5lZQ*U7IT`cv;PlI!A<>qT=S&YDeGUcyk#1rWT z%A{ZSA4j^#^dAdrV_&W-vh>eo0&l@-2lsNqgP+t+Mzx--{41FNdu!6k?5$4!6gZ#o zsV3H~j3u4%RCdMzteWttrqgah>fx0}PTdJ6-%<##lzuL9D=9ZvVxP;{sLiEL_&lmJ z+;t&)dHJB@o$!UMit^!u(S*a-AvolwUXC+sfHEm}N6KYP85Aa6#-tGz9frIIT^sIE zrs=uqxOg2FKDJOTfbI8W?9uGDdk%Q41Y0;&}GxEv|+kej+g_)^zRY?Y!22MBFVm*Z zzz>F_?z5DCB4xOP6v&c>FeGUlgnkRihNS;2Nts)=zsX{*Or8n-E+e!v?3lq2J?tv~ z`xN6EABd|1v25^9S!$Qb%K9%^JD17A8KV$1C|g{G*h-diWfM`HpfAAXXql{3{UYNG zdj+KpW(SnN_U?EV*?}WjQ*HW!GDGvwGDWOtw6 z_=1y=WtnV>-RI|I(;2lB9lo(Uyw&Kt(X!N2rWJtWz~#!{dx%rXT}LW2aNqy!cc{?e=j#%-Z7W)CuD=rfU?@cKMjZMqp^-evEJu*O@gZp#iDAKE;ff z%&Yh`Y>j8OS28;U+Srp$q#P>5NrLT|_luG@A7Yxk_etJ8fUD8a9aN&t`$fsS0u0>K zKN~!Ct!bpp@M(Nb0_!$pI+m}~fXVl1E(L9jl=wQuGTsS1?zJ(F^9Tf00IL`L$r*JL zq>kD;Nlaz@XPA4aG-E_2e*hofna=OvRq{82z~gJEZz9D?g#i_qZ{mFo?2LXDkJwb9 ziOh(LKutkcyZoNGeueTApGBaV*o6|i3V1BvnNVGQs7_}t`F~;~(Bcb#O?isMZvO(7 z@-ShP2g8C>9Yto{@fq`OTM&DRx%WX3M(5*}(Vtd=oMn`wVmye*pUI5e8&@t%lncQ; zM!76et^n9%t|jvdV9A^jk$H@n--N`rB{I*I%ug0Oo6M`qAp4%FIcB^98D9kc+C=8> zNzL5`TIJz95oUXN2H0f&zSJb|u9nQNGnr!)ajLr`u?l=l$v>8!k`DJ_>zJZa$6+Ul z`PIZmBK`Z6q7sMj=?2;0eQ_(?CyG>qW-@+2GM)!48MlQXN?pN>??B|I6B$1&8D9xO zn=wTtz2tosw}TJb1jWCr*d#6UN-kD1=0c!S8;5yp&H!X0@Q1x_&}_PU1x1v9lL8JIeg5 z#TsJ1c>`R8)c*}^l-nuFJxhE>A7u8V=D{0i|5>Q$yY~W5;Hu`GN{ z#qSq;ehopZ2t`GabSH`V)hwi=AFULX_ywOpE8vIXQkJ99X8GQ?3N>98OJvHZ-uhRbmFg|!-qGJzXnOH z!$+m4Wav>xArZ)SCUD{6py2#@Pt{J)B^Y^A~ZE1@Vm)-m>!2ny#q?UfuzeM>E4pGbDa7k6}+M5w}PobMG7`G z@Y(SQwBV!+Olr{!G~)|~%N%Yja06An1Cgd9BQ+{;4B|BH0qs;Uod&LtmV&c}+?v2Y z$Q=sWMc_8|Mc@VmW@JOr6;>)x-c$~FKLz?D@H_+E5%>@RxB*(>R> z)KiH6F= z`f{1vj+hK@udeh_W_EvkjgZOp244-rPWj&urrCU|jyo^GOX806=zoty>>Eu!v_UPh zKa7w2IDD35bE9O_$&1(0zeI&Wz*Ts}uD1B7Vl$u_m+tnJBKj=aaRt&VWzp{NHKiiQ z4G?Nl2;7c9b1gWN+XL}OyTo^FgZvJB)HS}sZ4jmJ_?&U*K3YLraUF3f>pJ)hq=~NM zSOky|UDZ}3LNO#X4hdDqal%#2IUn3L_{;%&ayKY(8e`8n0Mgs|ECYE`DacL(cL+%O z2p_ead^}cP)EshhpO`v0>M94@r%%_+ID|R7x?;(CApH+b|x*ulPpqX}GF4;T+TqPq= zg-rMN087UIH5tFbjQRXLijT>7gzpe|UqBG0nS?KjigS)SNz4z&*YTaiXJd2K1dQxz zpifbu1^8g~)b)vY*B&T3v~7(<25y`R!3&g{3hn^$BNxz(U{6K;<1PryM{n81?dDyPM)Bt$!0{of+OlF;LS(+S2F#J0Howy z5DO;%2DCXVknl=;-a@|9q=Wvm8`$?k)>*)E+yUl10CincKfrxpG_M4nJRImlpy|~J z1pJ3V!(UL&6o}QBjabcdlG-4Qs2{lUI(^ z27+W}1oGUs9?&^ajV=KHZpAoJd|>da8BJ_(H%+>ca-$b9nXk>%mvXD1>^5-5?0^SZ zD6GZk$DoWwBmG+TuaYvrmxTT+x^)1i*Zfx9g(ORXPU7~u`c5$w-({6z(D?|%pedLn zOyFkKx5zDm+*H8VbRF=qh}U!(0t*RDRt zEI?C<&#`iDBNRXIA2!iv2xXQhSA2W|D7r8U=u!k-7PZ4Tqz)}Y=8KkcSolGL1Bwy+ zZaS&MIp}}O;K|$$Tm@CX#YgRb38^$a3({otqv|+)@~fa+NXj}ZIq7{+8n`oj2PjYD z6Z%N?VdQH0R>LNs_j^n>Ob4q+t)^hN2#TJM zj~NQ)$xTlS5x2S?#0B_NES~MCQ$$_Fldj18r7N~^l32hY-?7i!=aaRk8vZoqKG#nN z<$jrXRB+PqpiDX{WPb9H%uik(k44UqIkiaROrPnPn;|V*x1ex0yG)FF zmgFECq3UciyOQ2~j*mS`1`bA4OsafDzbOc=@vVjzvcpLK)B1zdWU}z@ijO}{j6Hzo zAk<7+YXF}MshPY4grm}N<)95Z!3G8g27o!6a*`pFQB2p7EwAI$;hrG8X*S&0F1F_3 zc0!nV?Mv~t@un2xVbI3XSZ|53egLeJ#_*1mIEc<}8q2#g4oZT{SGVn(h|8iE#V|{=> zw)ntVV|egHeIk}lLaR2bn@?q%uOqP->N6h=G>v#u1>`>${yJbb{VxQ)NG?y4s4oRq zWC8O$iTXhqP`aVCo#{IsBZ+1>I5t`^k2c35Z?$P^{wDvfTgqi3q?g|nSsty z`xIN$c$Ys;X6C-t?hb^PJPdVr?M4DJ(7z+|t4!3s)9@vl_aW3-DO`~H!8iIDbg#pp zEdaMV&Y0W^ZEPbblcNaiLSPPA4&p=+VR9Exv$8>$69p*?pCXd`g4~zn37oQ$T!@c) z)F;!`(d3|mvpY3|z7IhC<|};`8q5c6F8EDN2;9oRL<9~X(EJO;CZ7h>DF;)K^AHI5 zYw0Kyycg5S0Z`}pIy0SY&;~)SDFcC81ZMF;8Kp`gHEWP+dK!2RB_2WG3HPAZ9E#ULGc_6O@HGFN|Wq?f^@pTiJ@>hKj+;8!jzFxHa z1C@`zIWC;ytN2{;9NP=JgI~_jKAHnVaS#iEw+J6ps*GR>C zC(e)&>>E(fzBqz$sF}$KU#KyNP#wpAAHgWmY@}oabJ1{R1k(t}2o{&HBUm*BID(ys zfcaa@=k;Oul?@8^%l1El>`vhc0MfRCmin%87W1k7Oc3yXkE06w@5Y5lJ4m4~A;f3* z_k+MqeAUD6{|{2)VFA)2J_v!am{0JzR_0*_RpKv<3z1evp@7e%v=0RS{FbWmkBtkF z#$$*~seu*04Gv7a{$l^S=TSCJU#`i8!Qu?5{6|Q6+KL{j{DYwUf)6VHJLDjhe}JNK zhE#rXo~`^i)mHvs(53QEL?996e^dF)!hvf;<>yjIPG7EJoH#=&pCf>+{1AkrjPQl3 zM1<-%{(I$9BGX7oNASs%Ua}dI2O&8^B-e?gkuu>6MQR76f_vgpmmVc$!q-r0&fC!XGki)QX>z_q zB=1h-Z15|T7AIBN5v~krtAF};Ba%3&AHWqS73yN06s5j}RNP5vFvLlfAkfTbS4TOi zDdMCUr8x&2aZ=Tg6DL&zaw(`sJE<99%HNV&a6W(0s$-xo3h2ICPg~%Fw)OY@@7a=m@ZcHVa zL4O1$Gf;%UJO;86Sjj*J0-G5~Lf}3G>V8K`P5;H$ZXlz1cMR8yn0K-}?L}~@`CE)c z&A&yUdDZ_#bH2s7nX%K|GZ~wj`wRc3`4te^hmUIQ?xzSfZwnF8yek9Ld@uvld=dlH zd@cjjoIh20MDw*k#t|3ipwZ!@wA&uDD{;g(f?FMDh$G%fN~sk+;)o}KvH%}A;^mmr zh$B8o(KtgKae7zlh~rf2h$}!BM|>&*i75XYN6ajiGMi7-?aYRb_(sNwGsF=;42pHc zD7b4Jn03wrL2f7Jp@<9X+Fz`77e8p_~Ap`<`PO&gK z;$n}}***BE8n=!My}CSnaf^v3|6DEuI3Je9Tawu~8NGib#Gf-8>y+Jx)N+ydz?U&y z!hHRCS^JIQkx8{j!sXz~+?pbohOI-4+PxUARV1*8;eWJ2I5oftVePmYgp&i)8IBG` zI4Mwy@B|*3aS({$qYk-E#{u7ugzd8FwDcU%GXvnFjpDNhyk*^6W6xYpdn+ZXEPw{5 zJIgkNV626+sE(2)>iI%n-W9Wv=Ht|QVI-Z7f6GpS1JCM1t0=Yn&{Tj{eqR5Dh|K+2 z$cTAzZcsa*71_SY2nqsMv77Ro*Y ziSo&ED>%}a4OXZ=6Y~v#!?l<{o%rlUBDZiN*7xHS&n+X?-Kjw1m3N7tf1|*SwQ?3q zsS|koT@~{XbHES%oD+B!Qpp9q=5UPcO1$=pHOXP;gv>Gsl zBFMyy)_E*mbKpoG(&o>k6iqtHX?cf6pBuPTBF<*Sg$Rn+O>wbYr)4n3<^>)Uu`-HX zfnduEw88O#y+SS_nU7x2xGf#z`2n_Qr)3xV0Kj)5lZk3g+Jmnaua}TR`&l#!Ch_{% zmMd7a`GIU9=a4KV{-FWn1%ZA?q|ccDKf3wf`gXiS&qf5i-SYp^q2pcmG9&%JcHRGv z{dGC}YulYk|37rt73{F;8JD}s@U%22RyXke&P74gr{Yg3tNj~rfCK)0YaZsK$6&dI zhU|0wZqoPQx-mq7-*p1~QVz)N9^r^E1~3WD-|?%^d#KZpTc5T7u+^d#exGs!rIW8d z8R3l6L@fC3Eja0$w*-_ZTn!_Bc`+zg-3dzDYf141-n<5s>IXq-2Qny0RcPDEZy<+O z?YD!H;s%aCajBC$=pj%#P^sh(w<6f-ZHk8ie>8%U49#2VZ-kO`+rQyePbqa;6*1TF zDZTqSt$H%?@RGiLoK}2#0xE;OnOt~DzY?caUnUnmg~1Z0ll;*ve1#Y-c@z>%Zr27~ zF;&&$+hYn&@<~u5#c1sYzP}EXscS*$KyLE2C|8OWb#FvjQnH15&OZ_CJR4~wKXU_u zc@q3>IfD5jaBww(eBuL()7Z(MA@7uKlFpwq5iFA6!u1IDp~}hMBBOBnZU&QKqHr6m z$(`h_XCv5-$|kR&IXaxcU=b=LoP7s_+vg#eOaJOuzI7`=dEg3A@*gL2AgUnTg$w%R zR`3SlK0Ldc+z)*%Jcw^ICBKCV3zw~Aun!tRxOz2%m!WiFUKHyjk6>`M1gG7D;H@{3 z`UlJzzE4W)lTBlr;!GLh~k{a0!CjHbX1?T;&sc@jvoDiW=U|AYNB=T8oty zUJBZd2SJnO`ZWU5TyZG}jdnPWlbp0jYMY_x2a&6xacWyCgk&PuABEh=zm7to$gM}A zu#=XP+WuN5Fyw9|(1AfDkbdf{1x{*5>g>yNBb+*=W*HQUWG@BkWKcM=`34}(=P!5# zE|PZ!P_{{h*UL}}I_AF0EdIL^%)De%)JWz!p!~yApjdGZFN(!Cx*ir%#es0S^|LcDz*P)~zG zl4vT|HsFON(bQstB2Kg?OoZ1^nPi)s)aY9LZ%d=MTh8=zXz+IJXCv741_pme!%6Ke z6M&4qGvRPj)9*%<^p+EGKkF`|Oy&&vAHvH`)O|aU$1jwC$p>A==rI0YD1=JukQc!J z&8twdECyMa=bC}?*bnednlCaP%_c41!1H~POJ)HU8o0_A`SMJ_t_H3_tN9So`XV7| zMcGcruVG%~Q_RC~?Xqr$aPQ}-OvWweVM3oaU@r6Dc0K3=8ASe$%eH)4JdIo@;|1ig zCT-aIglJh@G^=4DSyc~!Wm2z}jJlnI1jjH9Cu1r6eT;l{Te=z^%%tL8cTX&3bWBjxvJ%@{M9stZ;O^u+@lUx5M9 z^d$=%U(A5a^cKASBGrPMTGH_%i%%-WmzR^iXtv|)X2kL%rMDyVA}WK|-5r`H>Q*cp9&O2+}9m68y)z`?1bMU|4L60aLxq3GK_y0;z zB%N<7_)3`(?!Ae;dp!ORFeo#^qmsUX$4Dw!k;69u4Klo%NI4}3e=n)jMsB|YXo%5e zW~BXAprNdFUtV+MUN~K!G!K8?W?!UiGhi7TAumdau%GxU*!1xhalq-c7IAa@k?k(k z)%T(2Ms~QXE@V=Uei)5CveWG%+Pb#Cz*j=mDTD)ORDDqmko?mjpFeCAt-3q764OK$Q7 zM8(;QmpYM`-LBABUc5}jXcKwgm3aZ)i`LIB1O7yk!bL7h4@0w#eCn>rq&#k8x^f2a zA@}(-;#ZY^0uznMkM4V?6Thvp7cO)nKf6QVdi{CdDt#fUJ%JA?{S`I+O^W5u`$g%W zsOs+)|Dp8p7?~1yrBCM|-N+x7f4)zj(FFXbRd1CqX9}85QT9TB)mWPYXzqW{`rGgnL@n_~hrYBcZ@win_1E#Xl%Sq?N^2`1A-g{z#hu zD<1E}`t;LiIFYs%<6@y3&;TPH0>(6(eR?>WPNbv7xBB#ha72+TE5FsJ>uB0M%fH{J z|D@^jE#BtKK5pp}C(CWL8J+m*M`0KuCLhpYga6<^7=i`nb`%u@Av(Y z&3)!fJ#)^PGjr$8us)T+AgmoMSU`7!Ql{_)0o?_np2DjG`mM#s;7bDf4T^VXn|@tD zZy}evSiC-?Huz4I7-tYQhPR@61()|D{xYCf zkRQie{7pcgxemBKxUo6uKLoS`jZyuAJA~h>eZ6uA@PObR!I${@yt{yh1gWuTkFS^9 zcnsd`>)+U(lY@hWzuSDhiK=p{t^amkFTVnKWbh(Ur91q*$>{D;!6zj9=Y4(JW{}Sa zUL)0g+1H&`0FMd2CEbf7l6peD)wtku5+6q-olUtPAAChHj!4=~)tDGuCdGf~>qbvLZvHif4Ed2*x_h$D^4t5hw{@vFJ<~P+=cXd!dO>vtR><4QGbqVS=7#Y>{;1^Qf zx}Z+K4fxDpD`Cg_puU^xGb8w|&~XHlqUD$w{6p}@px)2!ofq6GDWtg2U@rpVxzW3i-7!_`1;F4(k7H0N!u;`Cd>@g!7>e1m6|^M4eDjA?~}pLg$}%EGVrrj-MA-A2>?nDm3L!_?F+Q@EyKg><==QUm!lHkn-PyTbbI7hf8+w-A z(mNi{NZ=F}z^sI`^Cdt_W(7&2z6IrE7kK?8F0*3}IK2_S2`Abj{pSNaux3{ZlWfSkM>cDh*+ zqtV&>d^}JqvW1*XKLbXzS<8G7Lw;-gws6^v^?1sXA7&}@{48dNNKde6?raM;>$m{X z6mE-knss6u$$!bd(qxb7o(^ql)@7h%e<6NbN%kTC3Ou)V(@PG7(2q|-JHVj$R{5V1e@gzxvS-X&=)_MlE#g#_ z6-s}3Iasy714>EHf?aBHfO$qQgsm^l>2@)Tx({NR)18lG%RnODX$l0#ow?lrlJS3> zl8Yc5e$J5EC|Wsk3t~lng0*rZwcGhS1tDIfCo&I2vadwUNdL`98#x;t8;TUcuB1gO zu0W4OcB8G4NL!eI^vEHkZ4`;mz!E`Z7;H;sujRwM!8XdD@_40Vh&ngz9roV^NC z9{B-+5sl=5qp`^Ah|@H3)qHebB*Zxo z>4ao{WGI~dpi{CNIr%x8)-%D2Q<&gOX;Uw>)r;tRkN`Iizz7!Q?4XaJI$s4I-F^@; z$+4{yfp!|?t83BVoI4B(t7caN?O`IyuyFG$0O6+RL_bDVi*oMtV`$c#33HsB{j3Dl zu5cZczbGfe?FpK`2^yBu)MYP%s4sySzvcoDk=Piu{X9x*&dKgyLf`D`m&nH9 zE_s1-m*B;~rstgMQW67+Z+w{)<&3ZxUdS?-@|@G%jAo?&;_DLhT+TGnS~zh*U5rsP zXSPeTAfs#ymLTU+H&^0gl-&z$$hpkshf((PrNEb4j8XPPFeYcc`-8;Cs5*NA@YR-% zQFRr&c8kT|1a)v7@K%d4$}T3Ox4ZRH{x3ntXUCH{)^7OYp;qLM;B@FKo9eUU*e2U~ z{(TB>u#&hLV$qbfd=r;YR%7@%^ddX!1{ zV;Q;&bS!7ONBe{6ONM?Ewk>D2ceTV{pP~0}20q&}oWC|h2krzu$Ks6{dKEMx=Uj_7 zgFXp(sm*^|hW?Q~v&>^f;eTc5r|$+{?wRS(-VD8(_xt@urjuGio>x*1}ak=KHrqv{1y znr--(50_L5zF7!6$$ZG9g70mMgu?|twVg&he=&;%ZRr~2Lo_}6;m!*jCKhGl?9 zZW4Hjt1_)gCE=Qstf`z?HNIVWrX9#B1Nj&OCzNt=L!7H@QQ1cP8f$TgX7 zcJ+k2fzw=*JMMIT^fKT^mX14}r=b1?8J5m-vM@vxWZL}py1D>LSfDJ%Ia&FP-^8ZJ zIa#?ZKij6qIa%DoP|(cMA9i(LHm;O!R)NyIE%6TbJsrLT=zBM z29|$5fjAW8xyv8{vix)Xg}{X_yAkK~y1H~5a4U=7!)0IOPl?U%LsxHGd<_27)%#fg zc9#C7tIu0=4F1N|X%O^+4(`OM%pdDX7vQ0w+{VY6Oyi4zd%EvP{jes}6mplsSd-z2 zrv-I3KGtOR+b z+MrzZ9!B`EycxrCv3g?*Q2VtW%PUg7F-C>UxMTpgQpIwjnNW(p^iixCK0Gg~KSC*0i_h(79hwrKQv$#an7ug1d) z{K*Iai~k3z1B=g~kUt96#=jkp+m4Cx5}J(|42m{F--pAK-odl#2|WotoXlq9Wq_)OT`!z! z7+jJ)am+%eaQ1Q1gmTqx0cdj!txDYsSuLDvP@QT(VWD)o_Q%)r5j@|lK8h*Bav}q78scL zz~izeugIDK5lwt(;ZXfKtMQSAr|FHbPl=Dc1(J5GUIufV_{7#~q8>E?@KX=@Bde*p z0m7R2%r=Wc;a=g z{u+Xt_}Uv;PrTmM|2ZG{KOQ?tPJsOF3gB-T2mCO!$|pAHNEOKfEW=D2&dYUI@WS{ADqg{9`Qm zi1%M81;%GjA0kiO06U$__IeY9H{k`$vMq*$;cSRG*9K?Edipu?KNMiUmy=E5 z0DBroO?tY1B5-rfShb|CtUX0ghPvxk zpo^ynQfl`;pi7ntimB}|^o5sh62!%Tktitb(*n4JZ-CzqyNRM8drbF+wkKN2Vj&gf zWy}Q$ep9%9KH;1hzQP`K#Prp>^8ZGO+|Bpz=MP1B)?xgy%i%>Vn}isKA`77ni4~U z8$`VE7N#d8C~>NN%YnBre=z;&c9|V-RZf}-JT_=NBD_`U3lAwV+2RKRkh#&2IeB4t z2$Cj4Yq4Fn`w0PA?6538A?ok=7n^3rRK_-|do3WoCK{g*jbjZCSp_f=s24{gWZ77) zQgmvH(2=Sh&zUZ@B^feGLZ~q&4~`s&I1>Ra#51G%7!q4)b`gdA3lJJz1Y;5|N_zp% z*)y@-sVMv!9_dJN3@(ZoX~e{{3i1a>ff1vP$HDt*RlBh@5>1;m+iBI)3!A z?G#TiYSqh_>kM@QifYx{3^*!#;k1cPtK-dh6U&}L)W-}rarMVq#H=^Des5DLFKB$dZ7LWRjGGiWLgcN8HE0*3Cn>7ekZ7(6a5=THlua! zYiNSFDXm-93(1i=Zfnh{8SNIE&^qrIu#GNEbluHNR+x@lO|nEX*}3BpvFK+In5-6x z-@5f5g1EJW8F2oUB|qQtiGB)tsV$zP8+Vc1gW-~Gadk4=36Q1Y8Z+Sgif>?xYncaq znl(_|;+}W5AyR7XO+axcT z`j`OR;E>|a=PSjBhc6tH#MfmS1?aI7_YIljiAuo|!j=+eId+0dDz zfi54BZ5lccu1b8Ji5XL!AdB%Ux%P=Gc*MhxZ)pJ<@~H3uw0+=2fZPdK@i}-(_MBb)p?NLVsEh z&IE5&KE$^5iN(TZyeMA=G-QwnRPgh){fkX}6=Un23TmCY|K-R|DNhspE|3<4r)D znzbV;MJdcV+ITmFy!cFtk}4RB2s1L17GTA>!ZwQI0(vineQWhba&8v1p{txoY z3Pxv~kBYUa83wX?93tGNmdeD6eZ2;#rh0Tr>PFg%#eP~T+-0)pX_$Ivw9UGj zS?u0|MmPRSqTwayP9SBFF&b@~7z7jc3;eQJ+ZeG)*7P6An*AeLbDK<^iEeEhH)5Zm zo`qFv+rl7)hOrLOIoqHLZF5_fB4ZZPwq-Ko-EaZgYS=h55PP@AEq2=SlU|^ZQ?dmL z<+lqBM6$@c@Tr~1x9~9B$XDntFR}shfY%oHz#^%39hW0gHqPyCXE#;>%y-&#z6imz zx?h4j?YfvrUf7BCyGWSDMD6BafGKU)jn`7kdS|;HR&&&7WZkaXaNk$l?$fT8(V!mL ze5Ks3C+DQxj8z5$(ys1%q2)S09VP-1J}keo1%D?o_;C|#N=Cc-lJ+R_QZ%exUsE%@ zBSB@_^&`Q|i!VW{=+zL&aOs5p2+f`_ZjMtr(QG?|NO1yGI;jIF(P1-?X?t}sp5;Yg z`zA)QO{>~xC#8t%w(X;K+;F0gEW<*32lWk;ExO5ZIyCvjirY}svP0CMusRQN)S;{{7O9u!(DcUG0rj75`$UU z=#3a|S;hF7Kw};hl&c1802=$6pnRn+0~+_4pdxku%|MfPVLatRjfekbQ%$qWRmEnY zX?*XB7eMLDNXs2nq*pJ7K52W909WjFl= zV|wRa!0Q8ilf>6{U(W)(L8i6ndi^@28k?->_G1-CAGZVW#(?!2^%oe!6Pp58oj_`d z-o>;x1-LT`D{Q(mBs;M=@TXAgG_OxgY>}gDyu?^NcP8L%GXLcw#F2{tcgl2}bF1d) zuEeeYmj%#!u!UrP^s(Jo#VMbDQ3V9OXcb20GmUUzTD%=-hCyNV$84aP1}U`)Y%iZ> zP+Uy`*UM)cl&`*m>Xgqhs6L#X}|D*_IofG{R7!xmF_8hD7 z+Z>RVn~2yu1Mw+8-=MJCcP-EglT4|9Lq5t^8WeM)XG37;RCLVfgiOx86^DU!f*nGG z9mNH?ib{iA^%8uuiq2bv=BZO4ycJzcCcb(FOt0vgEbjEnfT|2q>RhnAqMJc+^}>Fj z?gr(nv!P!VJq#*QcY{Y2)drQTGawTcH3y`;D%BiKt>|e`wQ9c-sLs@-PHjhnDtZ~z zTOC>r)Z4`Dqh5goR~&Eh?5FCW)D?XU8mjImsyFB~^*S7&iW5w_v8wM}puQ&0iHg@i zR`gpZb(ySwChE^G1Ryj{^yEG0g^D%DlYu9*>1$1vU?+H2aj`*RwF|;haf$5(C%qdK zzT#4{J=zR~4XwERFmt#XxmBz)Ovi54JAtk+)$mm78-cDgG+!0MB34|*V(ISv0Gm{? z-k^Ln12f%<4W_Irbut@sb&`2!%m=#0pgP4pZ57uh+4bJlK-Zb_`l+WOHx<_#GywAd zC(0^ZjK1Dn9(JFvge5waq8oAT=%;_Y1~A>ex({o9%3I#ZLZzor3^Oc@>-)f~@=Vt( z>gDTU%K@`oGj><$U8q-iW7oW&tJY_r)#b|Nf)K9_JIu&UtOe|+W7LamYt(S5s!#Gg>t{HZ%((`L>#8k#S zyk}g9m@yBB42rAsFGjlelhr%|Jt+SmSSK1VI2mFe&xk(MiuJWkFr?e7T}rf-Z2}njoVeAueY&cZQT(9 z!}_^#fbHD#1ZL<()R0p5T7g*C-wN2?QgOT62EYz3k5J;k*LMkEnXPuN-pi4p+r#Q?rgbNsXxV#THe*xxk~Sc zz?FBim8{l#SdAX;5hn5x-Gh~l6@@4$c!wmP9>R1P8nvBF+u_}i<Gk4ZpL zOQxzx(ebedZn@?U=}5W+&uM0P`ixX8^6_Xch_y0B+Mgov2_(9vA%BxZVBeCD|LlJR zWC}l1eJ>$w_&*By1_3SHC>X%MWZPKJkRL!u;dSV#((>N!s{nd5CI5K$S3FZ(-ntU7 zkK4?uNn$-%<=tA(1Y z-=NSBbhiu4*FUq|LGEh;i}XIqx<3zIJzRdSJE8~rkNZK(&r5mRn^yoXwZoRL+l>cY zW?`=O$n@o|S=z6Zjql~>OFmrbUwJ90D_q|Ah2^Kb*>mQ@6LS{>@@6o{rvj0foN96O zAvK9O0};mU&F=l&M5pUZ3sg3Rv_+JI_pQ9L-IIiBb#wJRZiMDEID1Ui9$W zgD;5+y8$Z0DSvh)a7QUBi@FNCwm_Y zEY}yYlBalH9n)6oiZ{Q!Kc z#F_FMn!FzgM=~+P%WcPYU;vu~IMcp+RhoxgCT7|9wo2c09^h>6dx;#=&qJaUbL@-h zTzxzFH`k^u((4xi&a-KYbj`Vd^X+Tv68+*fzy%hT>J2boiG|+r!l80eyTl?(t&~p^ z5{tdzLaoyC*n}mvplaRWEWopDHL7)wO90Q77rGpxu!@yp4}~Vlw7c+ZI850w92U-T z2YeQS#5klPY4rOskvIXBNajbV(H4@18yB%Am`X|E`~RnuZPucCcxQl^E!=6yni6XI zkqFt17ScgHQ#_5>a4iv}vxLNDXo{+_+gzf_qGiaEiqa88%=HrUAf743CV!Gl8dg7x zJ3bNfp;Sz-E*Vp5${*0bOwkKT7g8D2Jj<38MyO$K4e7#Ho3sQ0A-_L<(|AczjGvo8 z;7>$AVJ{f2<%ty@Upi{egAyz4<^-&J+zWVtm0Mreo&$KHyw;}y`eifVMM(ps&zl9f z%I+CZdcXp})mB1E^w(77HDd61q49ys0oU5Jm3lsgY`l**u5^{2xDfC%sS>UDUTXH` zR;v5x>*09e8@nq|VQz{z>uSI&Ep?C{vlZ|voAXe;e+%Gx??#C{T;G5RM`D95=rmnJ zsorR1eyrYj6W~oY?L_^;0l=GWi>88ur-Na!MzDTh-o?l<_T7GYz6Q^*^FMp9;Gsi0 z?cp!pTYNt8W;`F3mUOuFLOlQK)%JFfa@`6^$pq0-FtWN+1__Gq6gp*^cM9eOTBj`I z(idfO`0CWyEa{ZUn~6@!u&h)ri|y3JyyvTwW!X-40kaAfKZIfm--FJMO?(mLwhjF< z%1?Y5{LfG_(b4bGEPoYjbdoViMWX?~4z?2**74f_{}VhxV1^z}HhmMEEKup~djP); zUL-K4r%wj_&PI;wf3cwNgFA(qtAn%@KLlSEn6H=8j{Fq-L12;oYA@i=!A2*u8YO!C zI>29o#R5xpQwrSSU^ju~`YH@>iC=?eT2QG!C#!$6uu8wrCj1^8E|IHsi!FeE1kV;& zr>D>q{x`T&U?2TD<>1fY%L4o9$+rUj73AS8+#v8i(;f*n8b&x&pSu(Af5Bpb!}V;q zD~Z2@g9M(Y8y>dp_9g zMAHE`u=XzmdkGBdd*~Rv7@RCHLznIYd?|RbK&7vz_PlIiOuvS?Q{t82PNBv%zuZr} z8hlk?uFk&^@U`G?0`v9ATL51VHXp)ri*)*RfNxk>qMw0Zop>|YQK+T*);j^;3Jw-n zu74qXJ2+Kfr7jo?_>QGk>A@`M-Qa4WR_jx#O#cpU6OT$1TgD$c}I8n-$lI4JKrqDmg~1^Crd4?(k<2lcJMzPz-rX#M_F!}&*6bf zIQ=Q|75>*k?WY6d0XzDK1rE~d=K^;3X9(ma%oD*EpVPKgV2Aa8V_(3u!S*qzP@|@? z#B^EeHT`#HfZu|FUGh0}Vn)C;%F%o;m6#de>nw0DkNXu8vjWKl^9=T15@zV)4S=%) z2c_D|DZC%5ke^s63*DOU&Jv4cLl(P*`xz38?ZUOMSCH{bEDY-(XtvI=Fhk#ZHsHAy zD*YlEf1X{|jyt8{#1(-H`@&{l1QVRNQdXrq47eE2R|U*g$`#9T6PajT1-8BJJ1S4i>tGC z1FbZ)Ty;6iyTH)$)!T6FDle=R78R+z%;h4!?cxiVi_nvms|+evdNa^!gR0ceOt;1$ z?Biew>pQ^&^W8kQIXIOY#v=x7p1iKByxP33qc~iIMyHWIL;j8Ujdg_L zxP^Dq^OqUUoA)n*9u>1Aw z{B(b5e`LDo4&>6vzY5RHwC_~FjAW+zxLJUi{(hl`O%1Ya4Khp(8r#T9_gjm|%EFlT zF9&R5bB^ohC}r9H>ylNj^{QCxKdQ_+8HbBy9wjBG!q=tfFOn`llxnn=Ef4wsLU6R> zR!CFl%qCDg`F^2uR#R8nC%b1lH*PK(>C156*$(%3A^YDcqKQlvoeVqdcaBvt3l1xt zo7PGqbj=xP7!;PIvW!F*(QhrIdsl0{%s~{1Dmf@h+5_aD%iun%|xzJiB+!(Q_dZiGYQ^o@%*5`6rfa*zg3G(Yidh+7BcJF3KUAs8r;gV$-vo(~y= z;p;W5=?kH!hLalBr)~#)DRh&J#~EhWeK}-?T_xYlCSH+jX}L#1R}-&>j8hfYcVoa# zydIhMuR4bMdSzc*Uw z>&9&5CJV#*bo!w;NkX&m&J70TMLQAtK=1`*7xG`judy6|;Yq%q%Az!zNuf+1xeHL{ zxroRBI)-LOD`aa&nA~i4>XD+$`XQH)vKWTam;j4_046HENRyS6d2H0asYvuKvyM(_ zi&;Bngq&tbB-Vf~rpc)l>5rf`pkE<$4o**|=zId{dHjnNL9oI0eG-k?&=)o9y|U)Q zl*vi$+Y)I4m_ZNKlyxlqNGcQhsD{q1ZYZlI0t}PsuO7`Gq^cB&zN<+^=MAJ`DH0u5 zL*mBGq*0%hqSKQ#9I~BpS&Brj*7T(`$kKPD=yY>U)+8kdyk~^YMFsl3hAy*wiInQ5 zWKF)3=xi(fViR4u>7PGnQyg@|3A)V5^t~mN#nDyH;&jzyBBCV4k<&J=wl*D znqyL*qH{KT4Bd9&j1-;o+5d~4#o0G9xg-^dv)p4M z$?F=n3z7DvB605f|L!P$Q|MGHPKFKLw*OaXmbXPs-Spuc^Eq87Qy&~i z8>ziSV({ElBzY2}%O8}&!2rkONmLfYVOd^xAoM&uXS#GLk|9?~JZ8ypGZ}hID)eQB z3hVfUEZ)SwSVwrbu!Q%gqVc>X^G-#c$PmP3w)hA*6{{r%!7TY5kJy=ELbP--bsSI@8-@y`W2oCdYpPvHpiYA!K7`{d}yib!mCdDHxOA zy8_YlC!k^|RvXs>c1{H< zdRtJD`t=^5RtA+g(Vgg|aM!elS@<85aPOQPD9XY=Uk4OHPRP@K4+oNDzr=8WCdlZeJmg?yRSy$OdM zvbGiEuzU1Xp~avkjFlYDnQ`nex*t;iJf71}zZKWfH2DONA^$7+1{q(|{6CYv)4$x4_TyDb8* zzDJuWf)w_1LTHv$e{y%pz3{ z)>QxTl+a34WG~Qv4JuV!#H;@E8=;jeF4|QeX)>0zu2k=$J=K4A5LBhJw*xt@$+TK; zTLS1>Sf>w70Q4;EBdaUb0So)-9CTE*Z{Z-_jD-f>{*v=h-HD}!EOofv1IevUv+y(> zh3Hm?-LVq6L8rmztB$yf1&-DI$c1#*uy3O73LU6!Mz)bf+fiv`LOq=Dt zFK~{&Zx3M1HOt@&oE&d1w#x=;zL$;4Wrwp0fi((LK1S$ z=A$7&2{{N^OUCgfq(9`X=6@!ifP_q6el)~mh$sjV%>&PwlsUULC%jcD)sUWh?%Re&fm>}}c%inz-f|}Xv z$v`iE_yPnqw?Qt0bdR$T6z9!dXw+^`Uj)-t(?Yh^$rq^GVe4yhER*mB>Nu=+)Ewtd zKqt!=sC`**u02HHZBLJZHLhuC1N*vt!({&59x=f zKCNy1ze3vE09-8FIj|2qP2bHRkB}hA%VuDNS`t3kT`rId+)d;+v=YX&6ms;d6Jr=SIMMTkdJP#|pp#3mfugEu868 z7g{)0x4#V3gx!=mQS<1&>LLp#>#NX?>Q*kDE^f@`7M$wVl2$(GZo^Te*!_Aexr7f< zk3%n1m$>ARe2BUmT(55L{vdRGh)P3P-NF4;Fh1y}DXcED7$2t2Mz2(tTh+Y7m5n*o zUEIGU{$3o_!O^3uJ^JE+3$D|;n`sQkW79Y6C6Gc0$aFa{|0B2n0VV~9nJnp2PREg= zN>XsR{zov+w#t+dOoCY|LQEbUu}x&2!H}FopPQm{3^#Pz4RvFt%Cjsci@bF?-&90VPtN(5xexcracArib8 zzb1GnA|v)>1elCArbtKYTWcbnmx^>xDiWWNp5s!;-;#>J@y`^%Cy?k?hy2F?VqZc? z;1_<1XM9nMz76?oRLJ+nVGWOtT(lLQ2GyRap(QfZ*Un(8=+sehYG-ne1IJlT8L6FR zXki&ZYiApjA)Z_90^><3@!V<`8utiaK*IXeE;1-CK3DDH4#=5@S@4x??Ghd;gpV}E zkE=akAgEmNZEWrNn*CNVRxo&5wy>*Yz$yXr{}W8=9n*2`B4_47Pz3{b3=d zBDGh1hi7rWYOmxYdv7P|QhU{_9uarXrJ zTU|qwUdxtoYEnsB&tzxw1z}B{K}s!{4b;n^m~?1OZ-e48wW#T{SW3u66@Ec}^6r%W zi5w?`J?h&qAFJv61#84PMNL1>N?4=W97g&ZKM-3pI7kgJwJlK<96|>gRH~xufCd>< zuIf144K{VCbfU8_Mb0(%mtr(h`5eg}jA9^W0U0}i4z?BK%M7FD(P}|qwS&!i%%BXb zt{l*^_=BeO#=q!uYw_`L&6CV8n|Hw1JVg~l*2WWly0^_*TJnr(NmyNd0kVG9)GusY z&*u!vP>(=BYo0eB3@Ej9CeRB8#nr*ffnGEy-*~Vu(Szj+%E}#}y=*+_Qg!nbpjS-q z^-(YF1$vc&##fTRZ2@}Cph0TgO+c@k()mh~T*`FG5@~4CCbvL9rb})l+h2}nY&6Ah z8oLhXfU<9C;pjHWY`UlEYq~vx(+pmj#LJxYR_8lT&)AblmHsVjPo)2J0>)$=N)P?{texR;9c906Z`Qm=y=cF%$F1VQPBUMdkihCp1lNUFV&K> z>Sh-M@n|EUOw|O=YtK6`lXO{5`ZTy}$@++~2pHgZfq3B~PMVqsjTWA@gwjfJ_o z2@3Do*1~-K_qBlSEG%-$gO>r9y2l|_`p*6M$RqJ89z*`y_%%ZdPee2CKllXF&-fQT z2cBxIuI-7C53%lb?dpXWIISLnP*?i5Aaij?U3-H-dxj#bc*V zm~%MMp)_oDRSZ|pqQ~mG8JWcy(9?jrTT6w~UO<#I<{EtfE>*m)mKkKv9Jj=&tFvij z@T%)o3j&8SX;ANfH0XHSAT=4m3b9V^iRn%u6Xl%@0dZks{d-BrUvDs!W8J( zl{bh(a2P3~pWg)*7bJLopSl8?SkS6i8fs*tptX?=oY_pZ?v7ZZ#yyKtZSbK@fF=$QM+8C`hSsJAk_I8yfIZ<)N+xT{EGq*v}&tyr3#i z5H|;K@a5ToS@OdnTBHcAU_C-Ui#D;C`!TUt=j34g2uPVO3zY4C$rlozOWK2o$kK&` z9FIt3)*u-Y#dGv+^mTbbk7;<8eS`%yb{}E(%-Iv2f?DG}6sZgEM00wYqc2LbXW~@C zy4gs>V+&$)ZWEp}kCHl=48PzL9zYoR1gvu+AK}rBWUWACRO5P}G#7OV`M23`3Hh{U9s$G=oCwnN>j3 z4GODVSnWPDVLFj6U6nzT`^++^k!k{i+-J5y8EPL!xIXg?%2a)C1)6VAmb!f`&;o-R zt66J-79T+ipqID@W(Bma{+-L98|og|-Fmu&Qt3xG1O3||S1p5L)gM~snI^De_3s;+ zFBPl*z@VU1to}oTLh2JJZv96Fr3oYIKQ_69g%S0i7?iFyFwaj7%24&FSN&%uU6#tn zL;dFlHCBfh^9zHN+6VQl|I(l)PGPr6kcIjtZVVjJ(xPnF5FIT|idyLE(JPU%scRdh zH_QQSW~sh@hWR$PFsRqx0vNY2r2mUKYJCd}({y(Xo%J~uhH-e@cGjYcyCYSLu9j$P zQDvd4dB0(OcMCoJKFjH0VL+b@L8`B|(AVte`Wg#^njKwVYhg&Ur|WxKn5J)rY}VIV zh)Uf(g_Y{(md#4CroScHN)52k)m>n5>IYfqnbr=rFrY8n0P2aBalZcQO28qO8q!A= z01mS-P5%MWsvmA4YVk9AFI3;kTb-&!YwsT&RBWNEuYr3~-^M~)i?$Zx#3u~q_3b>P zEI!T`yb#)5KibQJWj8%P=ARjlO=Wy73alTW%J`3)04Jm}{`6kJi5B|$5%PSJg+YBG zrDn2)A>9O8SwF?XG^e;3V*B->Kpkok84WRTB1Nc}8*#t~FERkF4@Bs<`;p^!U?^~k zKY=sh*JlMTV2Zb)XHMkbsE`}kbq!OTdJ$9f9M2T{u;vnsWWyl}MSdFtvlcmYDH`pR zbigR!pOC(lS-gR4oybrKs2h0`_QZ42XTolspjbfkItW2V--(~$S$&NKvc8jx5uH}* z`rCk}kwEwFd}u@8=?3voM;^TsJsobX-**;2&Q#2(?;H~WBY3!9s4arCv465(xYlNQ z1V*Y~x2|mnaurl#KVC738Ma|i$G>e-1v47&WRT}H_2Z>W5vloL z{KVUHHrA{Tk0>|Zbt_X31UuqY$+nz~ipG2LI|EMInug+kT`$L-z;66m9+ae>fuzKrGf5q_ z0X-al{y(-Wp4$WTf}w>KHyp=b>QpK8JATM8s!pA|4(PMaU@#|72UzRR4H~3g*$VWfsmoCH8O!_1 zpyBE{$bI}j2A!tTF?1$TgIYnpTH09EYRyqJQ3aq>@o!AJscJbp#-bT&=lY{)jw*$g zC20%PCo6z>t`+LJM7_1^C^}b_!?!auEC=IN$kd|{$1VSt`FzKeJf$Oh{Jb+$5XUW_ zec&i{ovY?<0{q@Y##@!MU{I3~Z&eyosw@?6Rl2}UOhUX>`DPj5kDs8k_*O-A!}t;Z z`454Qd+KR+&|!10)zhB(VhZ5z)J&ektG8YN=-MUj*F9azdL++z#*+L9GBIH3Sd!;r zD{ehD6~&VL0d`}W`?r*aCHdo*14oie*q%NU<6u19<(WCMM1KpcV?0+*3Bj@WIOPvk zDc;iN_X8a@YDkP{cEPVY9@)k|gtX&%6rR(D;3v8n%@4;9uEDb$Cmw&;94Bs8UgD3C zKrIjXV;Nnl7=QdpM*oR2_=J&NyxgWNJ;_Kka5u2&Pwj{kWx&6s4rNgnlP`ps1Ge2{ z!{o93KLd*6UhKr~hY3L)85Hs_$8UP)+Z?CA@iMogn2Z4{`l9J-B?M@|%47w&elg$z zqaeQe6qyXT(7qx@J_-qDAz#8TQ^9)NjFuDxS+4HAOaR$aZh={Ue zNczC0Opt#5I4nUn8RX(|0LFzu*_#m>^4F5~B8GrLu`8P3@u35FZ2ExEZpCl(oJrvO zz;n}J4b@JxX5e`n5X>>*11R{wrEES~wjF9aaM?bgh1ERB(!k}c5*Zlf3R`U8$^vAP zJ%5}t@PbE89!~Cl*b{$nS|3oFzlfp+hiN~W-+eb8BVt|Ct1rfLI@2}|53axl09>hr zac^)(-Yd$A%v}!Di3c;Vs~fAqT_0nlE3rm3xawvb={rc@;BLk^`RYU_>CR}h&GRtu z4(`D^5H;HdRBdA7ri-Dd&#NGrwY0_=gX@BelU3;Tk1F)GRWSJ-Z}YLZzQOAJoS!jOh!n0({EC zxSoZ9NWEY`xy#iW$Ov}Y%m=wHDp^_G`F$6o z^`2+uxRsgKszzVs20w0I|&TP7&7iQ zM!fzS#~CuoXe8`K$xi1*WE98fFL%RE zpWLp35p%{k&dH_8TDHJ=c5-`LOQ+=Zv5=tdKMp{|$bz{Lr$|>+#&x1+A;a=vQ+6^3 z9;G&HsyXn{QNtjS!=`bg5Z#;$CId}3C@vd*hMoBc67l5+xA+X3(FbOfM?><~g<&&I z$voJAmAfB*S^Pmiunr-g1x5=nmnt82DO0MaF>VaI>_*AN+?zY>@^nwysd_-XhpjWd zSy-Jt9q0<<1!t(un5_-FGFi=!n9Ef=B$v1v2?I22y`kl+FP8&dZBPlS@D!^sWf_iN z8g@I&mEIe+)ASy$j%4&Z_Sg!YI00z4Njz444hsHg zGnP0cbZoyuRiaB^w(?Ky&coc~jmW9?uqeDG7(d-P)gBgw)BGmQcTTN&MfjoA4{#?> ztu-i)c|_TS=aE5keqU5Jk%qNk!Td9wvPtwQAj7bSo68PtL|@5^pR&7>P239GPxJ~>c3FXvgi3} z6yJrT6WLg^gnSR;n?2!t0%f7tRseZ|oFB!~qKRYJm9X#Xfx*m{;i!pdY zCVoUnbR1N+s_eG2V0mQrQMTRi0aqYyL{)YeghNE3=Vd!}Ps6bnSj{`EX;PnI*e=^; z#;**X`&h=q9nd%>@28R|rW#E`#CFLve)er7%ES8sas~>Gnj;@D7sGltK<>Vz+R;kzl{LSGlc1y@1uJLv>0*=&HI$5m^u<#HtL4WNoWRtWBf zeg+0mmDumnm3(Ze+Ss!gVouB1cj4+}S9S7^z>t_eskGy*qkkhSI$P-LD=>dlUF9Yw z@@+5#NOhNsm>>%J^L>Cd9`Etw=TIL*7F3-rw@8oSz-CHiIt_^eb`5O>_iew&0eCX<_FiUE>R5XzI z)Xn4DP&LEj>rl+6T+?q0q@ysOa!to2G47E${$8X{V(e3^CJ&SNch}r)yU?b`B?W8A zwnY{%_sm_ki^T)NNxYu9%QlH|Nx@=jQ4(K*dt2^42CwtXUA9YX`t_LaL2FbJU+d{L z)P*F*zBhXODZJU!U9SZ`%ckFkeRSyU6yEOXr^x*z{SHruR~>_K3Bt{k+~j3o*n-v; zo3%sfUodq2!L^lJPfhA zA=y6x$EP`9Y%voU&*&z#Ok!L?nKn~wC4*uwB6HZyHh3=Fa5Z)jskU;NwS4KP+S!Y( zaY5R86w==3RhKj;MRNf=SQysZw*r>=0d4o zcZKW)9Awkx>i#zX4z_9W4I#bM6K&)o{qktQp_W>r|HrO6*}_siYct?*f3M_Rt{skTnigH%mr-oQfpLSmR{K^LQ?N zYy!MmHCpZ&*RR2|QDekaqU{S)8u%GTv1vuNnq54f$<6H|*(~~Fx=UF&b|ID11Svb{P41SBW&P&YE zQ#tD0<|oit9Eqy$gpQ~k7A`?Q@MiWHBcV%MB2wWf=tf-a@>h^Oba2$})Q7(RIRLoF zayG2*;;6FM@*_jnvrYSC*2$q@-noGLB_H!Txean`LI)yN2sWdbNz$KP-y60m?WfN5bB9e3;A>^jMKzhpp)M(y(KX?DT^tn2GabDkSOnKE*UX~ zQ!BL#)gCeScRZrYWoyZZamCW7=9Z)p6Ss&C8w!H5f7J zpwMF36Q|8{Moj*CENO9d5hi>irkE0P)pD4p5mU`_7^XfDwGq=yc|~Z(->6>fjeDf3 zn~*mSq>Dqz#!s8g%I}pBUIQK5yhY+X%4c5h4C;$Q<$OL?vra-jB=s3I7SwO>oPOmR z6gM;g3mWnx_-*0x^@GNf(Ka>?-_ndY)t!#8$bZ2&Co&s}+{o)|(V9r#J7HBLcR|7Y z$TQQ>Pmy)-SwfMaFcWE!KW~KMMaoe9NF);#On0I;B0=uR?01lzoK!wCy3-R@XHS|n z(HR*t$gp~3(lXF-qqIge&$Vn==dgm%YXwMKSf^T}M$Itzx~S_tHq7Ufc{7 zSL-0OrSfmgLQG8kV|$qShQ0xx&)0+_g6x=x-n=4d>g<$)&QR zxM79sUdhPidGjaDbQ&&jhqouJ#P0t2PQz;Vb~KV69zVWlSmTz#5b!XPPY~R2v1@v{ zpZ*vwTEnGoNFoo?Bku*g(oK_`Pt%V=fEuoHjinx|7tRB`&dn6+RDBTY(r|-4<#vWH zngw{H+d`-dbQ_3B!)EtX$$5!hfT>i&7T27Uv_!Ap54cTcD7>%d2(+-_7Ms<%+S>tm zoBIK{z$+8<&)`?XcK2Dtl3mexw*l{P`=Q5WS9AgExznXQaaT0hO_|G-fMf?e0Ale; z&=!Bx7-?^07RG!ha^Mc?tOAFEg~8c5s&baF-L>%+pAsjlkH-hE7Z< zo3|P&jitbcWaM$@t0fO#eY**$%UgoNsu4_KL)VzdNQOF$S~YY#EJ(?<5)IuIc+DL- z%`nkw=waj>A60=#4b=wa%I3(18l%C<;YPOGuz%A(*niX6QY*{;&DRTJV!oF)LnzfsBrJgNBP024CY%a#S6Hlfa z_=FDNJxw?u2q05TW)|%xLN4XFb$=4q;a$e zOnWi3G-DqvM}s@KhBsj?yeV@Hb24`o?FA~; zC3cw#_k@*PE9_xZeEtn4g=Cr#@}EIStjkKFMxmh5>2Pb5-}O{HtMyYbZd7sq5nY@r zu-NZrwpWMMFo>An-8f0`p9-L|rT(DTQppB$FBOyBhymF@(YRe1YRGmV*`q<*J0C8Y zKlB|WqO*JgEVzHt2ZC}Um$M5Gm`bAuVHGw@6#9YX?#A#SSm$C*vF$`m=?6d5x`PB4Ygy(CLY=IucOfAR#R zkGz5(C$f1A3Xj~31p+T}a2JMKY=4FC{I zFYZ5T0^$gelOp}c=?L;w&I>z0eu4sxwHbU($|^j`^?2M*iR-N)WBya-3(KeJ(0m4V zhWynKuIOPfHSB-$Ecqoo`Id!%UwAn%+3~+ies(Lo{E5-%b4U*F0GO8#EgK-Mr@4N< zI~)?HrPm8w?vzAES~@x*A2V`QS9o14F`?P|QVg|Fh>1wZkK>Bj@-p{qz(C?$La#!y!fT<%%J1p! z0!81m4DssRr_PaDJB5Q_;p+So+$|6G!vWF060a z2ROhzER4+1Q!uLd11-$VUvxX*AnVXI21oL{+>DUHHYAHYifl&65Szc!zb*wl*e14hh#kM`439w`lm^tK4c?1dM&l&pt}bJ(15qu5BRWMHjin(K=dDRxtk9Hs#lT; zkGkAqh~W*(vyT6`+gGZbuREh9{u4IiBK<7o^(i+e#JD9gnem^o?JJi#i2tlRSkhMJ zO`22g_|LgC33#cKH*wM;$A7^!nlM#I;SBpPx!hVTpA&xuXWM_-9frj4<~{u*dH1Tt zSVkRB2E68u6grksFQwgm-C}IpxsNvFO_w)VVh>S3|3poD+kV-*J)r*uA@|>r&J84P z4`^PV<-cq3&OrWhcHMinZ}aeRa3KFNNSJ@f25AXe&HjGh2DOx+TVOQ(4{T7b1RbDm zd}xD?lb{pEA?PC;lp{f}vPB=;pcV|$`FA7e6Ja+#KMv>uis0w=^J3ii`4UC{3yX2% z=Vvs4Ut0V?Kp%#C<$rBIbgZcw@!vB(=9|!d<)B(q?mG2Ge>-GY>c5V7VP`^eE^(_6~VE!4b zk1uaMVCC^ydoX|WcmxG)5IPM(-N^fp4ML|O=+oT@O0z-eGz4vCTf#O7ora+I$nJ;@ zLZ>|t)N?6jjl2tmLk|aa!)?GBwuX-fVa8~NVoyTlFxvJ)w2)7$h2wo-$b62e6j5sg zLvjzGPXn9G(K~L5m*4pcUAz-4b-B}GQv;IKL-PWKhK6> zh@YDO7FBG%4Z#>c6>cXvz!I`J_+;@3o%1XHrG;UOLOvOS`yWw%iGdIo&n6w)Y|^pV zNAeFzH_TfL4KY1AC zo$?F71pja#4NH}{-xI%?ZVUWo@dqJ!_}6veyz$Nge~16lCKSl;@BN*=@jq}|8+-T; zUJxv@(}mV?mv6Qlgmu9dz}*&R=&54?_oNoVrS5m8-XL5?-8x`lt}bEs-X(?pAKJb= zJgQ>*_SETfIt_FV4e3-u5;Bm4bRa;01d|XTOp1UKWmFKE=Sc=dMMXtK#2FQbt6Z*E zy@(^|MMXgYMHEFvMMMNqKtu&cl)<;wuG0*f2pQ>*r_Y1gh@yXw@bhIW|w z1#TL}$%oqzV(YYCxjXP;W@ZWje&k47o!!dEzI_3d&Z_`ohd{~=3mgepa$2iOV zvUxnwdDG8$P&PdqXT6`*knG)018(pkE)ci{aH9`LWv{pz@NFNC%jOwaXOmy$N!i?4 zb>4BP05%?DjG!6a?A#`G<}bTZ$C@mHuuGliTsFl>U37S z<}^ddi24=R_%R_P+*kdyVG+<8cbOE1pC-cE$a&2tMzedf57+uIJ-ZjF>)a=WIZGa% zJ8$~bT+@v8t~tQU?SB3wt1}9f=T-5>g^gNc#5ghrzfOvtj6Fmx3TA(dm^#BSRIEDn zkWSS}S%KEnY55{1A1hNsY3if{apBQ$WH-qQB24%!(i||s4;Q4%Q7j2hQO2Iy+ z>4W6$*lyIvg2PSPr7F@Beo1hINsD9Fe?WPIBTd>TRpdr= zRd7@)BH@duNI%S)!O@2KITh(P18|JVd6kMxnglq`P*WFEJ58Ml4^7hzCrBiwIeI1|MVuUl)D~(|YhBgS^NK$Ts+}LG>er z&jI~|?cqMtR7&*`gBnEIQV||Cs9_`w?=QI2pcJE(|Li6ej>->V2bUQmTNY_>KREwo zw6a3p6A3<6C?)VsZK`<6Ca7H0&182*);|Z2Bg>c}{4g>E>^ANw><)ef-Ey-Hz%5O) zW?F8JL17sQZtg|UdCm+tK?SL%+=HfW3VuOBM((CecXpSYaOwrKckoLyc{@fVyG&z3 zk()0CZFhWwgRV(%kMT^R5qcuQuP>H{_K0xO5AHQ{e(y*!`ZM?q^$Itz$bM*W-z?!A z6uBJL3GTmD(2&UdnLq~&8Wy3;5_uf&|5)E@tO*G&cQpyg60x2x&4KgiUrLr zVsapdw|fNxa=RDbo{;Ok=(I?Fxc!B983aSBuN1dJW%H(kU>(IK%f(T=j3yYCi&*61 zsQ$MCdx{=_9PpV>C9UscTpZPx>K*a%I+eW*Q&X^kk2i4JA`?pI^h5sqh^w1~SlZ{H zL*LXmQ|w2NBQ@@X4MT(>QRG5Gf~yfuR_wfZ%v}jSw!vc|;NwAFlbYRUGWNZ&mlGuR zp1Cu_PqhsZ$%@?=&*!HEGkfzCvv>MUGzui#dT=H~3=&60nhK5LmMr5(G`b)HPw^vg z(XWRj0%OgxYCfVXaX>IIb}dp@U4YIEjAbO47vW#hUHFpQ{@VWw6XDQ4D)0qjst&datMo}Nx9|@#lI;i3!$)Y|CqB@!Qm&B)&6|cd;u!pJ>X~?7+vDGuCS@tkcKpP2l zN$zhNHxjhUnd5=UT9t{hmMmM6R{IlZsM}fv=76QD_x%L4RaV8-|3&zESr!K#ND!|V zVuzN{{UOgQQ^VDucI37KVi-mhU&p^B&JG<~Er$;N<(hncjB_G}6GA81;XEd)Y1KTs z1gs|<6}SK+ts|XVAWn;txpPu{%ueD`{w+>pC-E39w-9A^dJ_8LDDh!B{SyMknM3+v zoy0{82#-}!0k^~*Ybx^~N--@S%SKg+bsk6STsdhptnoP7-_9+cL5c}Q2v$$WwF>S; z#$um~gY`nC0zV;_PGhDDqUK0lgMDSK--#DS2K$MWI?>!COrB1>&@tFwQIorjhesl@ z==Pf+wR)z@n!|Ed@{C?mJs#1k968QP3Ue-#-b)J8qF2uxVI_IIRK;pP3ZiwZRG<&i znO0S?Ri^&ctiM$;6MY@JTpm9Mt{|W2+~w4{Dz-CpxzWv=#v(k|@NFd@>mHgb>MVS7 z$=6v@-@w!&n$V5xhpvBMW)0obt$Mr_n$N~|>l(WoG3Z9C;;L&fwLdEjR5PF$(m?er z8(2l}Pd!I-P{}Lu)N_Y43@eG%te6QA zyM2t>e254m;6A6+rk0g8YEw%EF=D?^Dl2N!m$6od<8z>xD+8vB4Wt-!sxpirce(x zM*%%PKtt5I!b`sN0{q}S2oHk!T>4__T>4@;C3rgwZ`-P#^ddR{^~$0YdlL=@w0bL= zMm5n^%%TTAC~_N%q)U%@&L>xb^E}F&1my-6KxvFX&#wrx>tB)=cUJqT0j&5iTQR4CLd*IMyu4r5)Mc2|CA9@!PZ@8i z5wb=d#-kTsijIi0Bo7>X72xwIe$X^_P`p_zS(=q;C9(2-lzSV< zcPYgtl{B@iPmrc3YHW1oF2z3h4RPma^trlQam1&zgb-!yEtbuQrob0UAKk0iN$rXA zsbcquiuD1OhF|;);@rRw$YaQQRDKN#jkt(=P#r^U2Jb=KWH1l@1cA8-SeJ0B*aWs1 z*&a|Ab%P$MeuFFU?_P42An+suRIqgnL=o7|KnQ{F890tStXBA#zGW>$2nALWn>ti= z!HQ4KlDbj`-HLG2F!)zL3t33_&SLMDBg$yzEJ~#ZpwY}L*yu5Y(&*VVGItS5*I$X; zthWF~1e=~kQEs4Nz_Ko7-_JvNcjBY2KaQ&OkHbXQU&^j0!(w6Tg5+oP{;*TMALsIW z|8o=>@BLwv_G;u%Lowbw4!MZ1Pk={+-LMpu98O{H2G<~R%^yrzHw8hYUC98Y-J1bQ zdlUnd_8bN%?ME4)v{xeFOPdWAX{T996zGVS(~x;ciL@!{vSRcw_-9};G+GxDtvi4? zqg8c9tAee8Ib*7N@>r`iu?RdYdG#Zfc>;H_q4ep*(gU9CfZs&?)Lf*muXv(k39xj@ zjm*;xG((s4n}f>FM5X57qteuZ=g^?r5cd?A&0t*&%2HA@)H9&=kK;s-^<$5b<1xd< zTU5{Jvf5K!7H9LjY#mC8cUeDrKbw$6NeqSMs^!n4Dzg#y8<+-9Mj*8f0wWNpK%jq| zb>xkR8HAXTw<9nS0nxKa3{RKwac7T0M*ZV3QR|CYYck{t(_mVdTUY>%%s&ti0~2TP z>-!QJXkd0Az`r4MrdZ)=)Sx_djFsMwxF5;+9s;T@0_zZnGO!AP5(b_`pc4Y479ios zZ-52>`DS8q3<70_g{sL5V5XV4jj3oRmXS})#A>juCR>3L)qRO970Bux2B^9_8KCO^ z!~j({sSE+CZZig`x*ZYlRhNn(s+*1J3gOWz8;-W>ZYEjk?P`4bBEb<*%{0?prkNRt zGZVo%W+DLQw9`YTo#%)~#?iM#)8nYH9Hoy|ZN{LW=B6MPQrZlj3P_z+#%G-7GUJRy zoEbDFQqUsc3*aNF5_wFroVktJ&&-x9#Y|$D<~JesFfuX;mz&XsIAhaSh)oZ+0~Xu& zwA=~XmY5koBagQ(AVhr%9|=31q`G&{1{3*ijR6tU6lGCcm{V39b6Cp zZwK>W3xN#?^pA6m%tg#+h{0bUwenv`mu4&0b{#&4Kv=gb-t;tSdibokj2lVQbAbB} zpNWJSB4steOud<>Prb|pWBpu?b(-I~$b1n#D&L+1QvWzkj0>51$#JLQI%6cCHuc6? z{E^WKm5Gn!xCaqt*>5Su29;t;9SNR^FQHK~mA)lnzcJCMP0}s@Bo?Fhju^f7iN(R) zEJp56Vli^>ijga*@QvEl$QTVBi-wv(Sz=jRIXFI1cfN=Y;GpDBrOTk~$p8l>f9hNY zB_%}rR(-f*OgTHUDX&Fp{s6->*NL$vK1foi{gpc{&AdWsz{a`+YHx5;F9K!K$gcdEg6Vq1i*$ z;UADLUW7TO@*}YELVAi9(xRHZIueETl3ttwEMCMpC! z2#mV~fi-Xn#*IQ?6$29y=z+k1J_xvhEvVBl&dftlCo70L?Y#44RDdJ?edHh`ejfw0 z3V$Lno>R4q|1g%9qtcN^CgprtY)W@OjJ%%2M{Rf!dG(LOM0bnhN`@7}bb#GcE2VL#A$VGqUa|Y<096?|_y_50uUc_^8 zY7n5Gl7@g8c!!bIaeUN?PROc%943S#1CI3uYi0*b7%9 zz`ubDpi5EYFpRkjQG=fazM}?Qk0G#(fd>$H34#7`wvn$O=2OIs+=#$;2#D%*Lk_k0 zxECE}h2!wd3X`FqFiAa=I->wu@=OGz!f^(_!ewM&g$E%Ze_|;(EX7i!TS>G9L)9(M zqyAFzP{v1W>5P%vr zcrV~yDR;8E{NIS0q?m6lKF1I}MLA0l`5(oICHQ1^!T4r@GC%x>%gOeL5<|jx7?J}R zw5H0V)gd%XjWNcJ$(NMjEh6v-UXL5MF=E`VM4Xv&#))xTL@W#Q@nXDI02`-hf=p3r z;DrsRBkPG`%035GYQSt!1LeSC%%QHLxM@Me%~B7%1}Wc$xcXgDJ#nF`LG6K$x?HUV zwSOEZx>IIma`ZM_XSh(OtzY9TeuoyIgfm^J(dwRwC})l@2;_EWIm!lKXY`TTh?ygT z7>76`h-*aAx|=VG3y?8Hkpoc-l27oWH$sXW+aq>P($K9e}ULP z4ilo2p-YBt!XzVMDpJcxxDf#v32_Era1WD#BVirO;h&5IHbq846Dx`Gn)<*L)IuIS zDkUcwrXY5jHFfY94D!h%*>WW*xqmy&x~ys@;zy{(LP)wA|E7LF8Mn-}K?tmu^?nhc zPN0dFghhzl42l$)E8qCVvF-Qcu)|7wyUAk}{$2LSKd|#~p=>OnyyqHQ*6)Z$Jw6+b z@ipmtVV!!{3pg_I8XwmvHT5N^LG#gb>FBAcg|}i;;RkRLe0wR3&4qkM1MnM0dfuQ$ zjR-D#<^jyd&jk6BJy6DIpczRWO{%X~U_4FXyLce|`3&aB^A#VODK(v2`YN5dyMdSk zpW??G5RtP?A{OC$Iu8Y^ToVC%Va@n-93q-9i4pwfb-omW*7RYkNc(~@fu6`N=@kU0 zzjzO0k4S9HLM*R<7SRXa@Y8B*`mV>wmByGrRDtVvBoMBWI9HK1ean^L%I_dthnQCu zf;0XekJv(~)AS7VlPbJaIJ&S7+>e_+5l)*bGC-T(Rec%c2yYVjW6M1fEestmq!qnolF$ zz#v9kwGa_Y+&3994iQrP^ci4KOL+CJ8yJS-`d+jc5u;QK;p;;_TKT>`hf1_z97M)a zcH|RkfG{>ABlrILUU8K~8^&5P_Gf48QP&BhLq@Iv`o7D8_9(;HgN(6dh)J@a6vi(R zBd%!QW|vE}VXQ&4$m|1hQD#|I-zT84s>0qQ3D+SmX)S_%Pg4IXY?H78(S7^ejF_%= z-SuqllVoHc^qt1Zq^r*eN5z!Tnp`ZQk=6HRD6|@Cca?-x%A`C5``$cPqD=`@v@>kL z83R8)+HXKQoWl5jjQ04re$H_J@8kOaKA11#V2-?z^#5lx&*W%URWg{}09tHW?>%i< zw)ILFVp9*j4C=twEbFG-W-_UP+|SMggA;I)&W8Wy(2h~6B3fl3dP_1Ns`o-%5)~$( zLPrD23O)EPm{LYaOtAh5*sim-ASOD~@TBcU%u-ufuExN!a5KvABZ$%U5R--uMNCrW zF2wwd%-lvCOLZJ~{FIqiC^d|j3|1oag^OV0x5*xIN22zj%kbr9e=ade2mZ#(zgWAw z%~@*QS*_byZcAofcShSbmRrhP>&{}ZHM6Tbqg|QhwqOzkCe5N`iyGLGWdYH#BY^zSi7|S|vN7*H`1e_X(OBTFW4g#aZ=5N)z`Z zZrwi-Cz`n(0ntp`7=Z(EoP@h8e*#mToO%HqSQtKivQ;OS1vTt~TGz=#)_9Qf(ih0B zPC*%1yiL0iUq}{|<}E-g>NI6`IG<&uXw)uRr+5e%|A|W1X~x=sF*;(JRi`=Q$>*@J zN%;7qC8Z9goZLDspJzHLpp=4P0Y5^i>$En=@eZRa>$EW_aCi!tdSft7mUN#>O+5n3|K zixc%slw;@Ft%R4^F$dhH0-PMFn|e9^do$4eb^TZUEpPT|$nmZ@4TZcLPD8l;Gq-M| zkC_2}QqZcK!62n~`S3|r-Ap5N$E$#n)Xg#|P*o-jA2wS!a>T84LZy@Ia;^*LbCqK%9PwGd0O6%-+)>eg>bx8JAt@efrKH+w62_s zL03wqb$u0xSZRCeDjuw7mg%{5qZ{$RQ8^^ja0Tbb=knP?IjScfB&n+Azv%T7bfCUE5v%QrtMB$i$3vAE+46xY1MHqtUF>4|+67|oq z8h;J(qMXush--K^8`}6NQ2%Nm zo|yBhV5`CdE)@721`zENiBgUF{&<#H@(2#dH=0e}5%E~qxh=>#AXjgvJOT?-8py31 zLO)F}vjTY(7K)EfFSi0s3~-{;+o2K$grd{WvH~J;XiRi^g%v0?lt^@Xr4?vuKr}jI zk`*X2AU!%}niY_4!8=n?oPG*Or{ER8=(LempqXJS@UFl(2{dPAa7Nv77@Yy&w=V1J zuW^-_9cXg`aWWVKZHr8Gy}LJ{No8>z&xXqoC})$Yf`9IYh^D&+T1|$T8Guu2QhM! z*EzNGnU$qiK-rVua0;c(j&2R@O@7mPO(ubmrgchQFP)8c>fd3&lQ;MO z^YL+|XTZTr;JLQGm(@A$)92axlFcbLd1Gpko%`@UL>ZNI6yBIZ z)Hc?_7Ahq8CG&LcQBL-uhZJPH+^Z8qmr6 zfjhgGb|yX$(05TDU448gpvNBo?(XvV6LdGAKl&25hkKdGdx4|Zp9JpdULkmqqq}1E zP444z#G*Zp-pu}p;T{SYqU1~5%cZ(o9o_H?;7i>{rF*wIx&f;<+`UKmw>x_FKHw4V1A=!t`W6n2 zQ7$hh$GZiNo=f$L;{%TVF$vWl?b8oC`f+yO7+1+iKI-T^<~Po-?gCe5uzBO%wyTlV-)7=?T z-cnb0WBX>g7-Yx~xR~mAxsM-n^;)XimF{dAeowkOpQhs)ci7G32fm)B;d-CG!qq#d z-Z#0|O8&r8IXrK6Ckg)=SAPP#pS;MOE_j`*Z>D-Z;n#nIt3PLX%iU{*z6tgJTJSu< z@45O$Ow!3uyLSrS>gv~MqMvo!RazEz|Xr63w^t*JJTw!^yRtJ)&G4Pc$K?M z=(}D0!>hnAx;IPzegk>1zHhnD2pzcZ8^D|W;eNo?Y5RfSb@`$&)YaAfI9xw@Lso>$Y)+qzsmkS^ z4(bNGfq!zjbb$E_>c2Smxxpf%{z15goc7Z=eZwcsMmIUwG_$G@5Hnlf%EN1Sp-1Z| z{9`O&PN)N<>gAma*rW**+Uhe!CF8Dk_Odq!to2hnB1p$BbUx;W`nkga!BOyFf}`-f zILD|RSmu@92pC!h=|^s(FhU=~E;Pt`6|pJbVhWBn$h9C7@lP7$bwru;=5BcfO!@xI z?G4!qR6sWRCt)rDw=>&gu?R0EM=V^W_DnDjzwb^ z$O<)Rb1B%oQBbW0ZP`W^E!mfu>`~nX+dypB4tyyOp}J1P@ybbA zM2l20coPkiCoq)-k%m(mvE#i?P?8kc`d~@D(4{Gvtb!~`ryWDWXzQQJ$faDg4TEH4 z`=f20hK3PWh9JJ4A`X)UZ90m7DGgvU!l`+k5$_Ge@K0^xi!;iT->LZqIo^{P%Bclp zgE*1+9E6hSa-@e+Crt!s_#^s0buwkp@YTHtPGO0-P#PNxb5k!GlY#>7#EhMKv2mvG zJ_JU0>fm?*%`tXUhZuo|y!+71R6f;Zao)!m7pX(*Xri!pJvuLS6c?s=3COz;;z=D{ zUufx`hY2WkOkJsFmNyR)NgZdpB^DiZ=`1UCDt~GMPLx;gBxutNt-@OfOPYF_K{eh1 zOzWxBIV|uyDqb^+WyU-yp|^KG)6G1ZPFk&Z;7_1gM(6r@X&(b!aZ+f5tnBeHhdq@3 zz-G<$li%QLt1QXUKl(iMoc_=@MTT@w%q;pNA4c@@kh1j0K1|mGcY?Z2PVvB@*Xf4= zKe3G<3v^?cCH<+Kc7n60&&H}-e`Yttz`={BI^`o!w_^i9+O4ZGrRmS@ZHll=Z$fkQ z4%@7TD|9{vsQ$u^33HA94g%C)*__WI2|X8^5_-1}YxRSy#vUII(lyw0&|lk^O4?yM zhPhks^=masU-dfRH}(<{>Nx!q(|&8`Ni`1Wu=AMCO1h?go|hn4x!o-Ft=rKe-w(}(Q=!hcBVDs-g&S$YF@S!LWH1{l8XJh4hueE?}o1ON(numGEo6`I{j7sFqBu@0pqX0KfMX6rriKF z4{to$y6&gIK_A24tfg9n0%#}b@Hcy}1-)*7iohR#*Oy^v==y<4Qt>smzHTe%5g)I! zbt-$iVSxHde-z`G<1*-Q0H>^8k8Od}`BZf8k)zP$n_D%a{4F!$7SsxIyw9OQskclM z6!L!JSXnq19`7gy1-?R z>CPDKx=?0G4wS}kA+D)w6gH%9#f+khWKQD}te8Cz<6;Fhjp)%E0gHXuKwp9hQ8#mq zI;ZPip93~`pX)~ETzx0JMP1?^?oL>sm%h9LC`@3^?cJDEW14<`H(&=}Rx@>zUjaM1)Hl53t23xBorDVY zRC+8XFo@Tv-vXtN(=>GP-CvBO$4KwyjuQ38II0h$uemOJ}40r!df zp8>s(HnP^8E9#BqM~8jD1AO-$%a4;xf3fdhVma{`?Zhy58H@^sLqN~MJgmp~cnyDU z;SQ*qtdu>dp-j9*{^XyJh%h@W%n(?M@h|N-ECXC2avL9^XM&9(uyL-zb$ba0jti5I zu=-pB5_FCfp(EAh2-i~_E%BH|62lQ=^5Dz?#zzp5sn{+KA44KC&mw}(i-=8`31bpU zOFD^gbTS^Aq=lRe>H+p>F$bsBG1}-@X#=5uXcQS!%An=7=^eL#Gdh0CRQ#TsnF_2Z zUt>$J@rRwa81UhanCtcU5a=8;xx~D0F#OVc7*y*0h;f~Mu0a*vQ!KqF%_7E+H~n+aIF^BW zSSf$O$c7tbIhn9qbW<8N#t4>nKY-#IW!GdAInsniIbX?)6SA@5+_oYIc?R9w-=nqr+9Ph|m zKu3u<_`Er&X2zfQqcqN8-fWEejN{iKAHI+4J%%YQOy(Gu9pDjUBq@_S=C^eiM;Y~e zI>zbV^}u1DzC!8j9l*){%U91S-Sivah>uq({UrGt_~}K5_V4P>9`}u8Bx($q4My8LkV|6o3U`CdDNTjh<={-=lj2!hqKHI-d=}EhQ zo2Wt&&vvDc{0Us>Lixn}{B|o{1Vu~WZ?Gc9<(|_p=KF21n;9)t zpK&bju+mYsx76pyG~H}3a3}RosUNnH(x7JvjBTW1%A>~T$2L-5ct#2Qn5{2_UCQVz z;~93+)@|N64P)A$Ms4h-c+oX>Fl~J`Rt6d8sFwv}+RtG7dim|ewEq?Rw~wD6ru`kT z;~ArrvGbVrzk+j_F;=BVm>;&C=2J5#sDFz*-?MXgUt7jh#UFvjHjAxOFx)cmGLV$F z&DML_|Cjsi!SlAD!@-vFCYJx1!Ho|z?=3dhGEl5g7{Q| zLy+SjEMLPAAGc%wKy1q67-0pO?HMoGW>&|u{rxb^V2Aj)%ua=Q zL=o==jGxS!5rVK!J_={%rU*#)Hf#i`%f?(XX60}H7^rJUXp&snlbe6tE<|)Q5xB7@ zH-91QL}qsrfeU+b^OwGYh_g)uF6GP3Kl~;l&M^_VlrIK1kg9x&DZD0W!^;s*(feLiA@v0@zX)3_^402*(LnrrXbSgoZTUTIO3Q`I? z(rFysjj-2p7k&{U)hviWqB4|bK1glwXv{MoGVQj!C2N5mjxRGqdw~8yt>ZE?ieZ=e z$SqBXN>B=OPH7atL!r!xR3&fVt6-Qk7eTg(t<9V~Uy$R?#~hnEC9dSSs1xyNNyrg1 z?Kp(%DW;S5AnTb32Oa7`*4GDc4NNHWvQH4@{csGqOlOcK42Q3q$=7Z%Ea$2y&uC}P z{1!x+LC!(CZHS_8l1#!Hx2y%ug&v*-%OQyWf&17egdI*WBt~rAgCPcFrAsbw- z2!Ly@5KifX`6is*;Vr~?-$8}5JF?1@K+ms%I?b|)9Ip-rNp{V9VB;o4+UA`iT_#Iu z0}~m}@#?^&d3PPfi@WuQAjm9oVGMI32H~bM7>%3;2I1lF6Id`sbE3p1S?U?d^cl(0 z{AAvmUy(_=QTwph{s>SbgLo+k>yT28(H6?d;*{mFketTxjQ_P6?Ac4Cfq3jU{0b{4 z#~^ONJ&FW{B60j;8p2IgXaV#*cOi{+QJeKp`Mltl2*+-RF|=ZRVZT&tD0Jk-SBmvcP2gH75o5$z~vtR|J+r5_^Rwdj>5RUonUD2C5O zQ;vQCNjB*|l*Q1DG&wtNM)7S9q6^cWmvk|&7Gfz(=Ucxtd-4FE zK)MQ>mt?DsW6u3u08(-{;IvrNf&YZsd##Q`PY1 zLKU0(TYeF531*$9mzbF)>fH!UZaQ?-HKvL)Hv(OHlb|ebF^p@|VGjw)^}KyR!=DyZ z;QatEr0JMhbC@pXb^ZisoN0EcH|}?!@!Y({eV^V7uxm{xnAJzEY!^431nGk|$a@f0 zqUjVf4u^Q>W5hO{%E`vgALiACQEobo=9LedUxTG-dYPe(^X~r=wCO*#C2f+&W8+O{ ztdyF~^m-iznrS34+q;VOoMq4)Z#JcL1!X3SgH%@S+OlH4T3k6S$>7|DoiK(O=Z?!VZHP zbyd1TQ3SQB4-SCQ}yCNmm0Plt8B+{-RMo!Ad<6nBIxhm_ED-@X-LD2;vr6eHMCNFAeMvYK=Y{dZU*G z%#wDP-tacy6SDneHOxy+za z?=F;9#O+5^p~Bn6bi6SQsK!b;jNzVMbRD;myhAK*u3>~L0`)1n-XI*iLPLsfFv%j` zPtcDdUa5;rqE<>z*!^%Ur%f|tQWrKNmiwrXum*kuD9`kfF`cm{3A5AtOB_fqZZo4f zlKqVFP~3K)pN!l1#bpL5??3QIi_32ln(Zxu&KI{cWjkIJ{anl*LQO*6AdKST3WFk^ zLQfS}8kFum2%A@2Wl*j+4@R@Ny+JW=Cq!FZZBVH<1gccr!8D=5I~Niv?qpE4=c1{_ zHKr~#-WtfExU)fByit3Ax){!GUJEFGaaWUP5APb-g5qul)p~s~+={y!G{|cT&$9Sz zlWv&T`dy%NOrE2>sm!y-)zZE(-c>~B@^m6^`AoUM!4^jGEz2puS~h*5$02Y zyOvG6hs9FpW7u_z4a)T%#57ubuPLj-t499C_r-;G8O3$KK{eieUjZ#KsGIlq4?qu? z@_Kj=K;4QTG^i(r%?MO5^%acEr9~md`$hCe>!E^mls~2G`qa<5vOJ}&Xo$8H)$?IQ zPa-w!!*snGvMNfJ8%?mZ(j%zpo-)&Yg&u%<71dYfd04ex4pA0GlzBSSO>ZZ21K)7= z(8K=*Z0OsYFAUVk#C_I>+n`bN#I+Dw+-^G!zP0w-d;F|Mei7tZfwP7gK~|nc-Nqq zu@&zbRBCL+mUBg=DvYgo-=JzMr7K2BMbW31wnSBGK0pDV{Rcrh1{LV^qV3D2VUG7H z^tot<8Q8w9_`=Le5o1+$8qXtYtjd=Lp_+S<%dU7e`#{NxzKU0~4#sQIZZnr+qBsss ziWJow&7)o_#Oo-Vb(;XXgjvtm zVEl@T)guBOy>dHXGxfT_kUqQyu(|q1U|28y5wJx4Eij^&{R!B@r$+U-Lx3$+ZfoY8 zuGf4B*vhYVmfpn)rBt;SYOY?i4zRU4Phf$bOf_!fGsko;<V2U`^?#^p=lU>R_vSe6seTe_mR5x!TMc- zl_4;^h>0)gY)de(ou)>#Yw;TYmY|m<=*vl$vKWU<=rRSJRDhuKEX~q7$ZB2D9Q8V) za-bf;M6Wa-hPP}8ZdxJjIYo*`;Z#Pw5?o`_&DV#Oi!p;B&`fH!)Nfwnl&_* z+Vbvs9VlfO`VO`j&1wvmBqnX<=oWT2pyu3k(k*TFZ;1y#L$|V-+G-Ke&FqEX(BE&x zS99B}h%C(=16|@nCujKdv3O8wHvuOn`!M99Tk|FWz_8VF8GJO|MvB4{VKCvkdVHr` z{H0~(X2p&mEXRDZip?BldGA4Cvzi+Rz{zMaP4dma6B1^aafkemMkh_5Wo2DpW;y&K z`GF7d0;xXBK3R_9?q)M8?3{K?V(Awk5?yIm33T+UTtHRXy#|w2YcdKlE3~L zeXeWl>jg&iAc$6Xu^$&0)oWq5b$5H8z;t~Ds;Ya~85K;MrQhVT=RCVyV6J`COY}C@`9k{*fu(vLE7{-PBd|;_`wVcPU#kke5A&}c zWUES+TdjY61@K}!OJI#ZG*i&N@WT*qm?4P05&ot1`a`yXC?+$4DU~o6e8LO1LPXS4 zlukUR24Ta@rBhhG{5*N0B6S2L*h5bc5$e%!*z`m>5kuL(vk`ETeMb}4)X@)Y2Au34 z1BvJwIO2MWe}p8WU-}f(srHC`GDr1h3==)gKO>W+tKI~>%uidOhf^!3`)LdGoKFB} z_$O#$`bKzQdZrIc^c%2=dY0WpBvdM6Szqo`%j8&~zQX3QK&;AiCYvzZFQ{7o>m$G` z{c2R}nr{HFlCvdtem4m0!i0FJG;yI_hOiMDb;n3pB*(*fym5kEa&v-d$C*rA3=5O_ z66$WSAPu_|y(HlkiS$&#(+c??=|v4>RO44iB~3pRKs`0RNrX&u5rM8}w4~sOM09&Z z`2C+CamN;<3x&kZe(JHADY%yurY#CfE&NO-Co*}JoFWR6Od7T=Oak&`Y|yzs!Ot;Z z_@z?(0{!g-ouk0i_dXWtm$yGb=dd`H9!ZlB5p-hsPNMlqM$70x%vj1 zMOwzlnf_@#;3A*7LSKs6U*9fO;_UGz2mc+u;&;=7;PB}? z?P;hmk8nNq1E_cV)ZV(wpMdxHIoIm@jsh;W=LmB@y$lN-eXn28AiZxF;KTl~7^XMT zGCu039i^|toTmTjw`d$BSP6lpoeu*E;Y~n}X|H0HfG}_7!Tj=z{Tu=%Eod@-wRxts z#r-MBrvGi@qn4Wwj(l##zenkSp*H^>_nSN}p&^RxSbzyiI8^T{vnL4h$njB~=TZm<`t zQKEZ8PWm@DU0|sWG41cJS&o$H6!!EVKCIAfUI9GnwiV`TeKx6ox)%wo(ItNY{^c$d z*iBzU19;4RR$vdk^BCZ9_XB~w^&3ok!aXRkR`b1p z2eS$e5I6*~e-z?Q%17U(PK9SMPH%SEgZcql^LJg-x3Kzb+k5VBXERerf5Q&g;^v-X zI-m-Zy?)>AE-Xh^V3wZ#3*g7@ zrvh{JF$!Xv`@6sb{rXRUpZGAQ|DfmdsoS83>44cB#Gkn(0!#J#gxlS71eR$&OVpqH z)C&D53)7EiIGDb0ZxC3cUu944be9S2run!)f9bv{u!p{k!*rK>L||{-<{;o# zZl-8wtzOCY?si)X?5C@!QhWTggLEgR{n{NY)FC>Xy1UoCN#HO&@iV}0+nSA{rUHREuHmUS&bT9pEpX)fok6_~ zI%^T;@F`(GB{?4obl`H45avLWFJ#12^%NQ6F&hz1-GUy?)peaqx*&s-TvWK=YgMbg=RqO@T5l(s)&vPDiU1Qt0Gs;4P&IkBTx&fUZ zbapWK8TDWze7;=0Imm;~n$NlQyTR@#o~8Un_+F5rrET8Cnr;a`ejZ^+&!Z9eAb73J z$6+(=ZVj4gHzJn>=no}ZTJGBK!2D6rUu5gsF=6X%!9fvbm8(nl0e+Hz`=~UZCE#{W z5!(~+IDO~O6Yw2c-yLy?wta=RrGD`q9)ReSAP;QIj;W3YCrM2${TR(vYS4H)j$W_^ zFwKV{UHUCxdeAsOVZ9Ub(T#j+L@(krp5eo&9)n@8GkqDP>j5;ASw76tXYB%P95ma{ zxtJ4>Rd#T(RHHzD&FLz~hcW%bM!?+Qt3oZ&KYRt47u+MTRQKe(*u*clOh=%kI^Qp- zLVx%-U|}#MJyWfdxR=n>hc$ZRT2N!bHbU*D?|28WI5&+Xa(sc1ypa_~bNr>DEF$@U*DRVd}pJOR&<5G+9ZRr?WN%$>c}hGJI-bTg2KiBjnUem{@&-@3{%Dzwf_|+Uiv@})s%HQeP<#Q`lyD^ zV}&T|c!ETK^;G^Kr6Iz|pT4U}MduBqHVG0PS3{CB^uEN;OVH`b8VUKN$q5p@TC>cT z2Kn>_2|C?elQl{43GYdvb8CTquc6BZfG{PxDL%by680iwK)=|q6N%_feW6W%2q$x) z%N$Rihp_2uy2@cLS4}3ON>Uspjr37#w2M@=NvAaEQt=b;biB@EX3h`(`gI6>!v^;CM4A3=oacrIQ~k!19N z-aJ9)YW6hxawCae2|Cxa|AQXp>KmC%OfYekdm58GCStq5bZ3HzYv2FF`wv3ru;OCa z(Eav*f{1#Gi{ew!@wYk;3ypJzl#7DG2%9EzDQr^s4~DW6q`oBa-3mh|MAEv5z@|rn z>qc@(cZuN;D80WN?BKiw^j3JlDG8{@Tu+~tK#T+vfcMS>6Ia=WDPg%le^Kbnn9J@{ znSk^OBG7(JIYzc(5PjQpSdvlYxE?ojW@2{ce5No+MkKWfCJBkrnXYv@tEnt$C5a2#$)FtVxMKKh>js-@gn}EZNx+jOZZ@djn^WWXE_q0 zK)}mvgU%ZXuH)pAFLoJ7HfF`N!@DK3{lZ4+b0#&Ji3AeTjoWb#bYlQG$)3h3y(=B- z3#>vonG5G%!zq@@-xM8@pwsIL(@7I6VU*aQ#hE~eLE$~2FHoo|LIJlpE2e#}tLB&+;?f4of#~{4Zv>hndARK;% z$J8>UCQUmO6cvjjD^^KGv;QC))^?>Gu*RnMRx4p3sL6)COr4Kq3CM;zs@cbg=$ zyr)pF(y&3c*X(W3lF3G&zb!UgOFcvLEQf(#K@zbzR&uCy>qdQ$;W79Yt;^w*P$bbA zqemu?V?~<7=?b-O*&d7ySMI`}+vfZiN$7T^G=={iYg<&sWb@ubDKX~8Zrk$(Q1RJ|LRidfc=tJ8@W0nfE)|Q}%cAMXYCq?ur3chU<@oSgjjj&$LYWuttCL zI-u>tZnC>l7Vu#YeKp2und8IWdK?RNRZMcO)%#g$(5Lp($KL`>^5G!e9;#awQk{f( zh@K3EDXXIf2ppzuN};YY;v1!BVhohkQ&$UhoNjOk)MWLrz)AWT)8c@Xz-jtrtWV0K z%4~zrw6gYMv3@*IzW>|-=s+$&%MZ{}v8VYyMfrCdbBP@9Eoemf!SP^22g+u8`S)K) zrnrdhb8sFq=_1}uL_hHzW-JQ5`QHK^E*VNx;;n{Kl>cmKrQS(&OZhLeMIn25t1!yT ze@l`)dwBbgg40L6Jz9YB-~TJLS~;p+{zn_hv!9m=$(A4GZW&*O^L}MT|1@xkl843R ze{p#66;;{WFF(er@=b4#=BfNRO(TDpGJoD1fG1{xs#FqxV>bVyb*Ey267$0Er(#@* z@i6Y=sT_&v!G@hQ`2-~9N(#k~u^Hn%&X~W+6UcvB>B+kREkz5?-@KG6gwe>|uM zVyu@J$uSZf8&A>`*y%AJFGX35>7pUUJ`Fl zl0HKI7K$Sj^-t1YQfXTGN&|e>X5dnlc?s!9li(0hU-=2sQk?Q2F&%M=2s%>{ox1EK zex9K$O>wG_U9YlqDHB#l)9REpQoh;Ie7aYbq4)@n`%!%EQ7B$ayPVSyM?XujgLCS)@q4a}lM4*K^0g zsVIvnN=ROtUk$03wNM`j9k1uo5SF!6p9se5xip1kt$d8vbDKhZWu^YmT%qJZP+2=g zYb>VYg>9gpB`0QSIv{mgcjL2jJ~n;BUIOV`MATE9n9qo|5Mfeqnh8snaygC^X^6np zxBoM`jYM;*6mFJ^u*rinw#kDx#)x+d`rrhebGV_?et>j!g2YKXp5c9oSWez1!T+}D zu|k-*h~b?6e_{F%qDd=3EVBq{`a$yK0y45%!1(5dipW+v;M;IsS z(6>0aAmKguPNE~1(sK=daG>496BqkaeY;6U`OW)&?ItgS%rMnQsr&7w7+Ods&~{S| z3XA8~Zl>|1BI3EVn`PXis7Ifs-Q@dNVeVV3PHKz$F;la5{sVaY?e5xwu()6C?q-mV zT0Jb|+THUST7lj}rS_r6Q`-H3Gt%YlYvCWrO;F|443a%eU#f%O*gqa8~YYP*gg!yo*7&XNeP4w*gW@7OL7v5ni zKj$shh--@S9$b~MMtpu0A^V#wNf!khB^tfeLIn3jaRabF_q&8B`K<9fbp zP}utg3R?c2c~TwmKE%qke2YQp-fR1T-Zv=Mc(5Os1!BzOtB&PcjR#%gwSE)mL(_ZR zytnCaebf=v<|D}+M?w48Ab8MN;g)YRrSp*_rBqK*B+}5hsvVVRN+aI>`UvBc6~2?$ zbwTGb_AM=37sSbGx|8W^x;=uE3?323*I8{Ee~(0GU8WWzE_Th2NFA%j@Kv#=A$~iy z0g|#~Nt-c)#oqr6thgQ=BB@x}5}ctakbcD~N+4w}MnOqs<;Tdz`xD+N0uBz-;{=6M*=PQxD7il*gI^%|f#pv+!S9iXv11RzT?)jK52F0o+~3id z*t6fD#j*b$M&n~mze81Gb5YYev2$O?z00vr-iHihqhXZ7v46vzNRG9|;=_v#hd)q1 zHfB52F?K#&$_6pD8yg5QjZ`VI5omEV_WZkWgkn#?Xz5rIYLaFZy#caQdBcBM#UuM! z#i})|+-$h!c5EaxIuN@ISv#@Yu;g>CqBoI~Q~AhFCKw7$z)u-Un-1Xkg&jKzXBDsi z4&8-!Nh|-8Hw+TvS=`FyMhPr$`C6c-405~=(BR4y28FzfkWuBcOvL>Fk!EWE>0aAP z`3_YrsC=O}qHvw?G^=tYD}ipXQlEeb3M#|uX3+FiJCIGPVlRTI--FUuY9EGl9oU!3 zOyT5V1u+=+$4han)RSmmsIpeAVpe?Nw(ksZ*7mRZHYUc=q3bJrs`@!aZ|zDr{9{ zAKwXH>g4b!api@oBiOMLa`dMZV?RY%;5H3Mzp@*6fbX;)a>O019Oz@*%J~3vs`6rW zzNG)v(L3J&9`C!0xOMU>D1PNs-^s_VldDex-=>BNKW?4855}zWc0WJdI%z}CD(~9}Q*TUeFLe0<2&0oc^afB6`4!ex45jt+X=MEEVD_Fx~(2`}h{u+ZgSUK8e#dI$W^2#yx z3kXv&^8W-JYriRVK3q>v`5AbeO>M-*XkonoqpNa)&23X$fD_jF7;}|V?d`(9IIIs+ zd9RYAh;XsPc+QMAUhU(D!@4_mB`fFncxhN$>%f1lpZ{ZF9mUj9d7aIQ;s%zmUPc+s zwbRiOxYS`ig7|u$e-$6Mk3s`e6|xOgwzNmFNmR(nRuX2D{{1CjsU$JeGPOAMH<;+G z%5L_3Oz|d`f0fhOSQC}|t#j1MdFf!zaF4U~UZCd< zO7>p)3h0GnlFqY2yFLV5nT1SS#H#XCY&0Y@66#UaMEND@;}C6Cz7HM!J_dVLfe%AE zhR&-hRHhl*c?!yABWndq0iCTcHLsvsu?ejaKwn3*mzKx^LJDJSJJwqT3!@rdNP@ib~X0IYF zn^*0dcNfW6UJ#1gzT}`F^J@p~TNo6?Ui3`-aCjLKam#HiQ7dKviDvAP{}KGm2Ml%l z!nXi}&U^Sa)galtgCo^QciNZM8-t06Z(p=;U5Mfu%$PadYTu^J#3I;sDS}o?FUTj< zzJl>yGYr}Gl^y-6Hr)VJ<@=2&tqLqj%r)iU32c0~@5l_IlZVf?+SmALWGT_U^HU%| zMNEUboYA1JeuKQx7#QulnRF5Fc1(ZmyR)9K*C^|8memPgIC98Zez^}vKdKvT8jD)) zhOMa1WROZZ2NpJR=~&+MJX(GU|QI2e`E0WM;wdUPwWcsIapsUBk* zVtIQpVynlRs^ig#(;=02Lq&&M9n$>A3HTKlOp_hbnK+WDiePD?@CNs$1 zxdA%V(KE>LvXP`?eS<>YM<;$~^!D31#H-{x)wW>|jP=k+0yK_%fPy7ldi77J))= zi7?w+DWzytZbs|*Ot=qbBcly(bz-Y{w^2sh$3dX6YXgImQTDE&i1#pBmC^2NK~Zlg z6fEPcqk__9HIq?McLLM#pd1&XygM!|Up3kO7)C2tkD$Y%4Ht7ijf-`T--WaSq6 zCkJBLm(j^wxfP2}#;tTU7fWkOth9d~7tLZGMdjZ?^)mMI0=n23n0qVMVI!!quOWY4 zA#xK4Nr%uoc(lzRdn7IVt7LF5B5-vUOm5l`$QjD|1Y*)|g55)SrBI*Fhvt3`gWO4; zm8FzmP)0kAxM?ElKZwzzZbOdjs_pyni{WDpvb|+60iDJf{cxuVLouG{Ydz+wm&UOoQrs z@1r@LuGokc(ECm4`vukrHJ=Zdgi62oE#4#FVHmN{!6Z@hg+a=@2cxFu%L&jGJ~(B? zYIYf#BNeOp${<%NReK7;CezmjvmK@qQF4-i!fHEUp{wp)j#QcVN36D`uxqK3*4@iM{hU`_F%((QHv zrYgTtdf{e3?Nc3H%Y4&(=<0OHv?kq$K|Ks!R81ovCh7CH0A~0wWTifW$*Io&V(q=d zq$sxV;qIR9*^!-ThMn2o1%~QP><;WKEU?0o7bL9YxXvOdAQB{l2xiQvsCdPkFkQWv zFx)FD3P@DUf+C`V2}R5~puhL6su}S2J>Os7$MY~-Z^cumPMtaxx~i_TIe&JBiY_`( zQ&Fp-=?%i_M_o4!EpH6V>8@eGD}f-@_0Z7v*v@r5HN;)#bpqHx&B4 zu1-S`H2@v#n7VrNmn>1o>p)G^APr5gKh#Ox5DhI=+o2i;yf+RZbeLwG?Y(~xaJUW) zdVj$}s~fFhjyD84wQh`tprQ%dGFaEz8ZjrsnsVzO4OF3_>5cy#N!w_ssc5TV!0QJ) zsjkveodpxO-XEYp)}3U%oz3{$HNNDmL$ZjBc>+^_| zJnt{)d86ZVu+!{1H!y@L4xyhJ$vhBbCU<yf#f_46LvCy8Htl@4F=-@O*D2+ z@;&s~5bk_|inseTnaM2j|7I3j-eeXN_8|)+bkkRc(I?6RVr?J<;l5KIhTF~CiS?AJ z)O*xYJD@xJ&R_tIm^08D`ktl`ue{=Yez8fgLhQbCUS(ot)OVhWfK`alal!B59mj_P z$Ax<7EQ>(haZMD$>dF`_KOC3K)FB?3PROT;B6gw!KcIEb0Nn|GHzKK-1znx!q>yD4 z+KJQvM9S+6vJzF#K@T+#0i)bR7k+jtZ&FIsX6n)iLKD6D0Uzpu>){if`Au$fnMLsz z2pdGZB5&>Ma1Q1Kk0lI!1ab1XubddhjPmwj@J$SF4JRJ;O5Dmz4CSHj#BItHGUQEe ziQ5^23z=L*Ox&UGNHhwgiCc{M$mTGXp%Zt?%y|o2;;uJKkRWmF0mC@mOuWR~7u{bV zDTy5_DGYR2bcvUr0HfFxFJad+@rnuyx#UpdRURPZxPJ*N`o^8ef@fq-hD;>hR7{Aw zCz6G4DOBhl#%wpSQ=x==#U`L#3KhlYO`BpQ-o8)fQs(Z1TqfQjk7-Y~f!ro`E0l6e zS;D)kWreHVH4NLMzaV#SBW3TYb;vq*F1k(PeZ{Cc_pHx>K0PdJRPR1Zsy|a`h6W~HcGhJa)WH3pVT``+wlw)iTss46OX}I-Xf@?glV!z;u2fSn?pJ> zm-u4u`6)6npu@5E%w5HVlUe4my#KHnbIfhBH0(W(dKdVZ%w8?-dVdADiMbCm1?=5o zulqINguJ~=UbgLH*i5v_Ec?(3V-G2~?trwba*=JphmdyISh)NOPg~+A_UcaPi^Teo zaLXsY5*xTeLXE}8CK4MNz+Miso6$*PVPf;ujDGBkh_FS;E}p)iENx{Z_Nw=O1lqQ$ z8BrLpAVVGL~6#e}o|Q#kXc!xtYwGweGI0R!W_ z%`tQuWN~2r#WHLTeq-}DAlm`wyau;>CkB@R=T3l=9PYRc=se0PS@tNp?SS*olwl#a zA7p93Qj$al#y&;0;{z`G0yw^Kk}=@oD^wmv^atn@yFMp;26W+O6jdLh{>WPa!t3$U zCH{p@_!!m3P#qCy%fY!-Vv#BDkD{6w5T7)&1Y~be)7~QM*WGJ2}a@R^;PQ-DNk~v zopg31vug@a!@Q>s!`YMkZgw(WbgS=2F61p@IYY^Uyb?@m>KjMMPzchmD8lY1m>owHxTW!!VcC1_r_pOAK9j1p*Ipz5qU*_TaHWrHURF@kEImJZy+OY>nBZ;-lo?P`i}MG zg`_^^pFYiq?6H242p>A{N8nydO<-$0?mR}`x75~S8eKAhdc{a;^!P%)oFvVPuGnlzUY*Mc*HPE|e9a9f~%4w{+ipA+5znw8-$wauW}O522u zVqS5CsB0yfiI&8YSMcQz$hC~jV!4t7Gb0$GhhMlHRp*-0-Z06-igfG72 zS=M2*!e#ZZ5`+VOO6jGg0rj z4!h{?|7huwLYtquEEhRibNa@~BHOQCz^+dwN-SdqKq zU7#BjN`i!INWvMralhfP)ht(TPY-)gwVvUAz~~Px)&$Ld9_SI3c%s|w8K6g1qfB>; zk;kw#s>ZWeL!@bKGA=%IfLoSy862|f;%sgL&1Q_qm1EqU8Gk-gaUVbdUyH*?$6+$Y z&rO%7eCHgHCqJew$_#A#(W0qhMS|@{p_Ef43WeOO&`(mOOhkKi0VCwX0s} zuE3&A`Fho;MeZ6{edQZfmJnR>S1y&o|0nQkrF+%cr=?U*DFmH=4e^ga9Di300P}~h|K*Yyb7CzE9<|g$X7aY+&csno`twGDhT}&jeKj)WwAWbANfw_WOx(N zAtK*vXvr*D>ourWpiv+>k@LF#HOzIuSsNCg_w9)qx#SMYeyvFBdq?5G; zBcp1Q8a>|P!*FJGtcJFC$w9y_azB)O+X(@Rbd%em=*Zq$tm#L3T6|ZM+v&R@3z0fq zZkgA258wa|lipTz_{cz=Hszho$b)pKx>_kRSl>TWx0c!P@=&4rm zM0QX-Ik0-4z(0HO%jT2bkpatpU5nW=YBAsGF7{sE*lE-DN{9E2IG;C z16WOtWH1h7Zz2yf_*YZCwYo^B{}Ttm$+j~z#sTd^l*Yw+%NlQo$+uNAc$wwpuoq?U za-4O>;E}~EEcLeP5}ke}-mXQjiDWPicwff8kij_MU3zpl4tV$Y2H|Jw^mwGC1MJEy ze!%j6CHFJoID7rrheu&NQnHGYo7s}bS?eOG$}GlNYxy|l*%rq?9AL*=WUTK+QqlvZ z8!T@;+wW>?7lc(lQZg4dZ{%8wiU2s^t@s=G)=c{Z44dkJvGr(b(@gp_gPR%!bD=sT?KH&OV;G1c z?d`TQH0;%)zehUg(5QC;bx$X|PKL(4o7p>S>=Ps`^v=V6XJm*@oA9>6l!*-0X^Xr8 zv{HxZ$YoyHGk_y>XwuukrW&PT%DeApz%lj`nRB)GBzxEi_SF*BcrPCS9A~eRkk=V~ ze-Wnhhf(ufGXl@B{Nb1zrV>Sj7<_9M%qN3>LEK!E6_n8sDBx~sGCC`k@vVkC*JRy} zWQWKDq&EpW;w?+b6g2@s81hgo$qh4GBs)(gBgGk?m2l_pejd})$Vu|uYwxmeQLU4u zsYKm((+fvItUxzB%~{JV`@>71>ju1wz}fb{kqP6LvS-hc%cxXtcf&S}%+(h<;0C52 z0O!eVX5KJ!);_=mwz@LBNa^E+8YaEpsjp7gu-a>2pIM|~t@kLUXR(HL-pABtOEj$a z&gVFHmWCs|gCye|4b$G4lz?+Joao)poX^*Ax_YSkK3O}fbe=brqu%}Ym#8eRD)(OG z$n_r$mw=&sDZGG@(4?OtQvT!U%!QGM?LnBqdNgn%k7RGOxDjg-kw-OWLte8j2wkK3 z5%&7APLIi1Cx?Q^IJ7+>^HDqX-y!>^G$0C6U^B|&B-!TM4t#Z4_D!xeO{s(L2(JmZ815TnDChG9-LVV>p9dIv0F{ONNw`DbLwAlE zu|r0D1HUazZa;hmm+Eb-9KIGB)nIm91{VGG8esA@Br=l*EEg-;92>cTkWoP$5ed4LKpsq z6S+y%YPf3~v%N8Gl#On?|NazVZMPILV=RZ=h-CKI%HNpmOf=fql(rU)&^FX{Y!x$% zEkT#)H+J*imm^kFxW{fe?@C!CHy*e5`*DU@{E!AcnW zx zxAXBQ|5hlZRSjpGj3yOM!#O6y(a8Qhqv1Sr)3pS)Tw!TgYN{2MkhdCg(r|(P3MVB$ zooTqxd{IWO_7|Qy+i1AhycjKq_h#`K+d`vZnYmy&VV%dX3>z*tf4PdVpBF?!He6|{ zR<8G2W2A1l%6wI}#1QW=3;LJ&n#?)veGdU@xXx6XdZKqZ6llZE<}MjJ-FqM1rQue6 zd~}vKZ9CxY=6)G^y0-=*(y+=Dl8hzZjF$lKHg`geS*1(7DUhy)d*uv;&uD)CIYRH# zS)Jo`!WhtSzj;4|NWMnkCK8$ zekVw1cZQES)=V{elqu6*FkF1lqCd~Vl1c;U?U=Ao#ucbGRw zHiwK(EfK>w;h5MJ?_v3=p?m_EBoDweR2+Q(rXg7?TTLB+X=sy{D9Yg-nt=@*mOpoc zsi^Z3c*H)17O83I#Dr2QH`Me;AQg54d3@|iG7sDJe*)@!r$ixlDXP@aWv@hG_Z3jp z(Dk{inJy~ds%q%ATcWsI4-M1MUCB9atOt`CdMK2TUja1qRK2=L_UeY-Kge`tvR60M zshG+5JV<5BA^LS5l?f zziP5XOne^_s3DZyN=jImE(9IMpV-{5F%mVLMGmS)I9oRY9vDOCJV*6S^;}ZJd3Azy z54pFn5zbdJ!|r@YVZ#O3-M;!Gp(^X`UA6x$Pu?UyRH7b&)1rec=4 zvfnIYx53`0Y=kS0YJ}w#*+%#%TS2zFs-S*aY!f_G-C2eTVpl-jKY$0i9)5Fd^uL0& zugdY%Mz%pLW%DCnPKWp_)G`CaN-T1AdgB9 zkKV$aUv>zFYXgqtB5!$8y&k_~6qJ}Ug^OlBb{ z|8H1Xp@s$Ka{yjG2gSuwLqj!sb6{39EYZtUI3`~8jg(DB#cd~G62w?ejZwvw zxtn0nr^hOkGz#v35To%~c+ft;T6}?aO{5!*>oT<%#{*_0=h-btdNKpJzFiL6E<3YY~^}9o{h(e3dmS`o4QJ1I}MtLWoz+RS?otJHIzQ|FY-(BWbgBGmpR2l( z*A+4*8s3Y(fuxmY3JLiYcz4#kz1bHKZ`+!ll>83*6ZqFHPYPp4xt`2p88E;=1ry7u zYg5DS0XP3k?4z=j7kdG*5N|6+^>m$i&DoM_BYzO40CnjB z=4m$|a0y zt%gW-VVg}6p=kCm@ENLoTqdc58JHff^N)IYByE(L2AN#Y&HDgwv>CXCu*^G|rH|3} zZqnPp&<35h+FJzel%Akrjdwi^xAaLG)_Pkho0Cjl-h{L4hG;lw7~8G%b24-9^9=}n zUPs0qqU&Bd28vh4+6cBeN$_baM+(`I_3$ zr(ZEuPnhoAL%sQ$$)m;c-i$*qw$rbhEs+@3yyZPY?!2k-D$AQj2E1h!%Wy2Cwqp97 z8spebAGBinZL@<44|u)Vdb{-%77qlxFs5>LwKDn9Rqw#}*q8qW+lisV_ z*2gUvfuh`9@Ooc+3F)<-?frrFY9+mXWyT+BuY~m4&c3lvd$p8aGuOduzxHY&y?$bi zKGI&z>E*qJ*?Rh8$!>fu74YV;5})aNG@cB2A5gvyXuLMy-9rWVxyI`P-f3?l{GgOD z=$C-^9Ch9y*&F0quau&1q!i)oRKVM@2jSoA@?H;kQ-25k!R#WLxHI5M{q$2N-1ZvC zq@SfEp;Oylt7m|JksDHh(%rTauP-=WhO`$N4PIZ8-N$GzG}=1H`}IS36QO0x@RaI37iigx1!Rne(zCz%9(DeA6i7*cfsyNIxn!Aar=A=%3_&7ABR}e z@xbe+u`^=->ousC+H_IiZARs4LAp4=Sq#U4S(vA$OZ45>HAem>=+s&169cc_in#o^ zBRxJqON((iMM<9&_!>b}H4py~@dRkzl zgmF(c({v3By`6^TpcT!Zjc;beje*Yl|IY!Dfe$*>RH`ODFbqv;O< zcL8`jW|96-63PacN)@nAL)+_1UB6$$kX(XDf25ldJEogH!o(weAn-MFl2+&E842+Q z??=X81k}cUNXgnkEo;%Dhp0-v)co;b5E$)#+ybwk0>2|K9D2N+ya?kr%pdsV;ZNs9 z3nm+aw0zR5u zFPF4Gp51I%|0hD9)G*qB=p4BAx@Fwj5TxX}`$Xe$woCbr^KI=|aub+1{mErR`r+RNZ zY?$WerDoQ#K%Uqpj@fG2T;Dj4$Yn(_SHm;Y~WL@!mn0(CN(@PV}x~ z!)?)UinnJc;5H4Xdps_i-mXcW<#7=<{i00);EqR-{pclosic{Yvr@+L*MZs9=`{|k zqB!!H!_Gi~bEzF3cho0swi1)I&XOoYLyFbUILhR~(KRynS)Dd48MMy1UKSSh-r#8U zoDPh8=aRDZ8WwsR7`nl^RYt}O1&0A&(4j@D8k-z-)|ER0+aX}~2_XI&Bv96F!OvhS z^eBCB1u4X_Vh1W_H;S$BNmio;jO5TCIW-x9sj-#(5mT*zk+=apY?;|OQWUnJtr>L|KnC_Eks>Uhnz!aD*rhDc(z*AM^HKv<>1#qg$`AO4#dMn^` z6}r}R|NA@O3<;|8n0u^s;DcK(Bcpv z29w6?KfPBqGUq*wH*f@ie3$;P9_U6kD{i*K44^azy{+*kos%$=qS;6_pDceK38a>OEaVK zU_Ti)#pOmoxT72}pW19Z)*;M75N}Y{m(8a#)|S)6Y!F*d-TkCfoehs%lg*gP=Z0)# zw&sz@;iGRMhu!Z%9u1F~D&pPn?!k#SeCS5Z2N;t|vCB`eF|283U@LrTdC#sj zjl>#VC!zlaPBM#ILqa}6V9$l~jKD-vVRZdBq@~GNMg1}NgL-_0+hi=G*8YI5)|m1E&zwY-l7K z=EF}cuF^)Z%`%5A^vSbE{K{Ztws@isln)VnA6attR~CYjQ`;FC)r|> zEG9G%)#65)*@lbkEdf=f+i-H)4zRy0wNmz}zMC<1Hr2u&^Sh}FPRt|Dh5yOW-jSKk zf|sJbhO}QnD04ZMxjaWGxz(A(?kAMAcOmRjkFRhp-3o%nUX0uaUi5Fnm=4D*{5MC| zUk`ZviAVW0JYm+)0>-~V=JDSl(tVP(ByBDJqsniBI@PfEk(@y&p}#Eueik^8l6)^> zKEx6p9P9zkL==#6JuDq_nQ68|ylzq?mobC>gCW!A74+>nM>~cz1?n#a@TwYSJEZ9U z@)&w_C`6NUdffkkSUDU!hnb)4M6QpUB)YEFFwO%FGak%P{x}Q1175>fn+=GwEQsh& z4*n2u9sEbE0v>q~Xb;fHpWuidkLA>d!JD0k{w-^F^)3`Q_!)TBBW$1n$8PxZB}i+= z;0WM}@E=?V$6PpYmgHpwF*z?Z9uvopF?u^7z5fOp$=T&aj5>;%Bnr9{_-|fY2Fm+n z;MjK%W==qf)F_NlBqKE(rvC{);5X;m>AA+f7IzM$_RPd+a>C%=fHxukhGQ9(Bw?X$ zyJ3uzx09HroatPE!WxbA{ZE7b*=GR2pVrCE(tjLJ(w{ilyk7?7T#Y~ST-FP4$N{WK z{vywxVJ_u8VZE**K7>E%Q_#ippQDv;n(4q+!zeyAuS|kE45j10B1aI?5?08BQB>Ff z?Lc4Gjw)na9(sG%V**nqGicmCm;)z`G8aKhfX3i-NYF!)_G`a@vYyou02yq9Io={| zx0FdHLpett3G%!yGAP&pv@oZaD)wj0Tt?5~u^t57zXdtriml}meE?nCI6~f!YMTAd z{sf-Y+yQq2hrmX;pZy$4lT|m3emo9fUi2`10yUuSA58uSXEW^lS<))mnPJ>953}f; z{|Dp7k#UiYIsdlnIm1Oy=^6?aniB) zlpeCXqATJTBZ3{Ua}FU?N)%f~GZfyROrpIs7=Aev#(){RKaJ(QiA5M-V-N@U1YaEq zpHGY76X!etahlY^=cE(h<6TN0%V{$JK9f#{Pr*&nCues@_}qoe0?jF9$Jow{Ij0+; zQ4`_Qf<%O_7zbyoZHyjrnuESj1%3kJUFnl^-x$+qvZ&SwRI=12i#l{R0_~W2lZBl+ z8i8u&+GG)(ax&dyVdokn(23bKSwv?I^9eoM4E2^z5rnFdp+o$Cth{k=!XBhCD)#4uP{&I=@cBStcWF1B0B_ zbmD~!=JN^4cH~t;p^u_)R!R<3_lA?7d*XEgFff?+7@fsnQ852S=6+5UoCPE{bOv$= zw%|vOp$are(7%z+U?H3(x#$c5)4I4Vi2th&K4lLu@I^F1u=Nvk?#Y9* z4(JLeAN@2!$99Kv-Ibs!Vh5jJi@)x@sA_OMomiqVI1u5vg&y$Ra2NcfWbTGTN+$N= z$h6Nhn8y3p08u$;;tnIYo0*}Gs7THgKLSLeq5OLE4|feJ6w=2Iakt7*$abGO3WePD zN1?D0DGD{ej~RT4Mh>;06J+L{F=>_&YRM{bG394eJCsl;7^tpgCP0-%u0 zG}NB$%XI)|8md+(YQ+14MVNIn%lx8H{6_rsa!^jeWaeK)h8G-!T!q>^NaqJ=j!=gP zVi~al$apf8_cTD>)Hy~d_8MHEyKuVv8#0>94|iS!3iAgwVD>?qDO!9r6c^E%OwRGysFd9VvtG;fdjpm!c(LU!Kxc1~RB)N)K2-_WM#1F}Dh#nkPh=#8 z%r{!z1oonw>IV1~Oc;U49d?nJSVu5vd6Ta5S^ne4!@nDyDBqCltQTbRC^2HUpp4~B zdf%3fT9=8MNGBL{{CWhb+y}{mek(B~402jnlR&A2rgU$oIOus2s;0}^Yf#;Yp1 zMSBsNx1h$zEhe*2eBOd%jocCi?7Rh?jarXBe$&zDRXO}-Eu2Q3>Lu+o8E_x z(A{EF7kt)a<#v262X$v>%54uEH>xuz& z`B|c9-YN4I8M(Epd^{`)Wt!Vnp+a{z6mD*}-ZGbjdm36Nx4Q}(;?8Bv9)HSQMz{+b zfO;xgCc4`ifqJpktur)NR-xyHH`pUCWmbkb8^RvmsMpDDaXzIk~rpTgx`?g9bhBN z$M@{vH|_5(k@YjhwRMQQU%p|4?OjtGQvv*$%nIAPrr3-6h7Z__3mN})Q(WT$|7h=O zO1#q)mlOg2Wb=b*Y}cATJ^>B?V)Gl&KtHq}<#HS?n4~_pc zMF;XIgO^%j63O{fhhJ=olbZtnrO8`n75xNN9sXNlxqG|ZDw=_zEv!12ZDRKpUT2UB zOZGO~#O^J;UWAl|gW3zbx63X0)^9lE9E8fo#io|{0^>*c7>!q2qBn#;obRyVvFc`t zwGf=Jr}1r;C}xwja1?7+S)w&WC)`rw2P|J~@CbL*_)kkzlAaoeUpsO+TQtE)k;NAW#3$$`S-dPD%FBody9U&QqH+Tv8UPlKla0bBIz1>ESYkX`8^+s9+H;S-&!WcDxHqCXT-c!G1G zB=>b&ywo1}WQQN4^WcQoj3F>Q$+=F(-;MaJ-el)yiT46C{uGB_=3w)}7DFgr8T`2| zt{)G4st*6w7WHhtsg5ao@~^h|x*PCxP3|&B?54QQkehbsE{>RkkuiLl!*7AmT^tb{ z2|UwjEt_|xBQC)x8lL6+SBBr@h$?E1+0I6ZZ*#=0Y~BUVLRsD_NBl{87deLPe!!no zRh*&my^dH!aXZtwG0O5DaKtxM9p^d|FVnc9Dewh4{2@nNL-D@E;YAGCVRA&b;lP(U zvt;~rj<|x|ce%4b;th`INAbE})4v(%S>9@gp8`QMIwFn14ftY-U&fRJgLL>|XNAPC zJL2>L;76U_b&S8$5f71Hk2$x=@ZFAZNbeJxpL-oK3C2hGN#|}EzRwYNQCS8iI0U?;yZh&kc%SXP!+A!Af9r?<)ydnAItlor<1aX6kr95!c}{BX zUmanwz4kgU^dWsqgJL7a`(uaqY+zq7D9)t#9@6x!0A_dnO5>G5agg2V8|N=6t~Uk6 z8jgKVutIg`AWTCJ`*9B6ut~p#mb7OeER6V4%{IkNPnfLO5x+gWiYG0Y4Wpi|U9h_a zzH%!*h{(9?0`^WQQkF&(_pW2%-CbpJ3u70PG~hOkXF*?4q#d=iDnOgl*t462Tsp8mG*KP_yCNMG3b{oX$|E(T z3PZOM`wIho$c>Q~t_L}C<8+eB8z9vgM6;jelzfMrZ8u>RLw3bd^fR}WH56_nFiM(1 zt)KwuA!KI7nLtrnhq%SoXc?E;F^8bdw53MV=AjNyK~0-CD(HsrG~;7Xro0-0TH9@>1>SFvobM?&>y4KcLRndLX?|bMac@? z4keqH*aP3#O3cLKc}0FRhO}3De zq03N%yjE=yh^rUy+g#2dhr<~_I;WEni!)P?iN29H+@(a*Ctn!E9 z4wT=683rGF-;1bW`9rw?#UH^V7D3FSSh7Q&=0mKFk{Vn=bTS04Qk_Pz3wfO%I8exo z`B3-5YvkW}9xt(vjZ`FaE=qzzb1^u@)sqXu(W-Iv7nujj_x3`}^3E81 zobp1nT(JCltgz&i|Af&oRNe`7J*NDRJj`{i7SSH1Bz~>zvFx+$S+`mZ)BbRg}Peh$4*27Bi6E$ zX_V#vhem+=D_T5%wVGMu0fsnG_Q{1yP~rTCGPCYh(AD{mG7*JTcH*4?lACyP;Z~4Z zmjC!S@WT9Po{|3qiD17fxdFYqEI(|vjiak~ZjWrTPcDe%5TpF;lMA9f=)|H9WAZGN z6wqz}y3I=NMg2ngBg_++Ra-DGf25fa>{fpbH}T{`zA!iDBeV?~Ex#o5iAj4O|>LDA)nB)b9Nn2b8rJaA|$pty<$v^Vsf|v_koj=a}MW+7|@iDCBA9->? zlwnxRKl0>)h@z|KUuEWa%pb$(Yv>L6N1j{|k3&52k36{`o&{s_SDNq1_!u_JV20!$ zd2&IV!KOX(jNZbVdmA&0&!?8}f@$Aje zN2FO|KDYNcvRkL>Qcq9q|ErVg590rm{bCMG9Is|H#7&VgUMB z{%IEV4wh@05;skSoQSJRGj?9ug#j*)A zBex`mE{MT>b_T-~>4PaX($Xtd2C*(IsQw&osRs%=DzywF00LN`#}C_`jZRsh#}C^* z4GOTJGZR4%xD<^7efxXV#rt(eK{qwX@m_o`gv1_%`4TPY-x@}j%Pw0mK=)X=$Wbs* zEpp%^6ed1iC5An57|Ftg{&*(a01Kk92qz)P4@q5NvFfXey228bC2XL{7=i8P5l+tC zIP8_?k;~C|NM?jiMXNNAFvDE)YW!wSk6s9O>|L66Et=CbbREcl3%T6S;>r-xq9sK@ z8d=>(plw@r_>2*0nzZalCnIuDZ`tWriD;NGuUwNj%qZjs{@}KBxLfpwiWzSv4%Q`* z57$f*hbEq;@*$HF-{=}i4ky0neemS>GYts)DJo;uyBG8Z`kB|U^TgY?P;rT0`b#dI z<6hPh=vN|`wx&B6>M-#e4?V~eZ^vO~lKAs{F^Dvh_P}7I()M!ZpQ$eDAf63edimDhY5T*C##F~oz74axQg^v$qlUU+z)X` z_$F8O<@!z=#xF71j8MO(cnGtSL~D)rn&M*e2gd_s_&!to0J+HGPfYP9>95q`pPS-; z5U?yhWQz09-xBT2;n>5J3r0IIkSD5jd@Q=Oss-+C-X-b7qRS@`r7Xsx%K<3GM4gV0 zMVA#YL9+N>ONchWee~xIScKV=e-wVm5;c^@e&)k6e=N$ZMZZZ5G@q6ji!v{!fd}jQ zuC+vh;lneZOIYG+%IFk1E@RQb5*0CS)X58CFYuZvjK|| zmUw~uUu3SAsq$*wC($Ua zI#W&YkqxTZR$9&0Nww3en^F+{+)G)blg^iU;*pJoaLmSkIRZfA_X2C6@#%#dZ=h}L z>*2iSs2BnSBL=-eS6}yFJiPT4f*ESXBcwO_2^g`#%VASQP)kh$ZN7qC`<{ z5LC}iDV)yG3gw0c7wQkq( zK=T!jTa_gJ2Uwc;K0dH+2tDI?d3JHSByLyPN{IG!rXA)@|14M&Knm_7OXHB5_h zCjowBoh;K%6rV!9`X6hmrifGw@DuAM$*Sq%6{h{v0x`(>G;t63?|){g=AR`7LN)mZ zEUs5trL)8h3Bb=SnjReW#EY;a{4cEgjw4=ykp_b6AGG>ml$0aeh3$dAwAe^IL@GA+ z0zPDoA3%(eZ5C95|CMz^PhyO0yU5S4t=lBN7b6o4YyVqovWyQ+{yp>iUbY67pUuLn z`!M03rl_w&z;D)Ls1&yZ#m^8N|4)svroX!<@L|h_tYUn&#Bu0+z8PSnb6s9chVc4U zK&{JSNEpG2H~~r?7WOQ$p8OAL3>E$h*%XqWnc&S`OZ-KqHVLpt@nvbT3thu+8dxF; zUx)lKWcg8zp~Ck-H~D!1HRNrk3TD5ADT7WCn*ddi5SLQW-A1TFaoHDAk`2}4mNh{# zE_z(Xo^yFyi9+rj>?>E)NfdTpV_&&)ltfXtJ;RpIkSOjh><)C*A4W?h_u*Jl;752dr{(h7u;ldr`o4PM(A* zF%;U$Z|{^!SS|KJmHE}0j2f|@4cS4%T5&Vmxuc`BQV(%0yFw?2@@tjWiMKEc_%(7h z9vVe-XQLl07u&IEC!T_`^E+!eUGxFB{VsCtlU<>LId^wzBpLI>6_`W#JvFaR7yDS> zUJm6ASICHs6qnw5U3IA`JofHB8ZR@&cIYd=uU_UyKN`*Oe$G58-mnl~Z3f(5ulu4O zeb4?sz!`wTWk0$S!>&J2=ZAju2P`zd-g&7T!(kDw#Zw?-(Cc#V!z0WF3)6+DALCDa57ZRK zRK`}zceMIdG->|_ZH_fT`@69e0n&#(M&-eg z0}<2kXf7=?b{`eQTFT`^gwKUvp0P4#Af}l#2T(bsct_ps3=$YUqyU zEyCB6#mD8Lm9PerH;t&D8g2^RLNrlvf0awZT?<88JV15FA~%kasd%6oT$1jk=zhiZ z3RSz0L$ekiuTZT!j-?M$19F|)9^JTj@Vm0h*Bh}Hq20qJiRV!TX{MC4>Mw%~Imay# zoSI3!g-lBP4^@S56Bh=Na7oEe*<_`eWJA$EOUgb#aZJ`49lxaf6Nz|sgc)%D6_!7{ z=~|8Q&qOdod5%G&iH;miE5A4G}IW z8w6ChMHi-Kcvx zOqJLQ6*KM@K;6Xtb;exAER+_0?C$;Zi12zhR7Y&JVqT5g2>FXW*bG{qR`n)m%-AEX zB&u`Yf;hw;Q+f7tFM!C#p4eB-nDy@7-at=6?tzB5xrIRgRWU~xvBj{kLnT9hW%VX? zL8A}LlWaEJk6@dY4DTY54H4iOc7`1#0_=_86BDa&#y%>XLXf$xsSrUiHl$q^Ps8ng z*^w)&+AhZ1aS(>;(pxAEa;2s8R#k7q9TZ1f-Ig(u_e1%Y-cG4w58aKCu=EbIk|+gI zm~-qMNMpEkCPm40(A7(4{R$^_0&813`!9)XcTgXoIT;}j+V{Xez5_WzPwaym>mT@) z^+DE$;Kp_Z>e}KljG@ayrSpfjMG0%6uS*xu$r65;0JM;OgDV$#{8FIw^a%)*D;Hlu z*Ox9*p%*tZ^~%8e_f6Aj2R|BGc{l?&E;1hO!kkU4KipoQvLLgpfDk-ZR1bSeoy|A zz*sKCJ>0ryFL2&{03zJF7fB{zm5`#=y?K_Iiex*+`POy)WCMka__-YS>$x~|Jn|I2jc}8-II#-6p%a>qcB~NXRkXYxI$h1xL3}(uWi#E+v z$5yp!lb4YquG_YW>2U+96h>BU+vqz?HVXqq+h(t7af^Y@GODN|`J?D?Q15X5+ppgCg zanT5&@NWrlCyCp3Z(%I(ZsJiczZxwjbbK=x+8Gj0EQ;T z4NQAyfJdKT3y5D!09OS*lc9B@3FOAVJD_aZiDFIy@P0Y}#T^#nlp4SX<#e2Ls~fot z@Nj_30=VB8f==egu7v$kpE_-R2MGEVNRXPD>2J@E0-BZSZ%+uI*_r;92HR6}6e@H_ zg6pZd3Kh9cz~$6Dg_3R=bD6JDwVOt1sRatvy0}jM%@yn8MWg|05}PLt~_t zs)&ZW2!meg0)_C5C@PY=P$i4Hw}U0Aixi3*vA>~N=T&w5r6V$V4js3u(+OICa6zuB zMj_Mv>|~&0uaaSw+ZV!H)mdeN?SuobI*g~}4|VL+o-U8zvWjlevsTCQ6G zA1**GR$WE5$2Ov{5mndhV-Ee0Th)q86HLY&rRv%Y(>ucutooM#V%2plmgZgu zHr+~virk6NdR5n}vTEJt=zLW-WSHlZT{kLJ=Z=O5SKX9h*N(nGH>>jM-BTeqRktWK z2=f0K$|{+NwqBJAnNQU~6D@|;PaR|G(NDa09AFc@bsrKNDZIHFMnx^fFsxyrxCFdP zMNGA*S0sFjtgD~vs1-4Gt)`~hpX(v&z{*tARO_t$#7ahPrZr%__zNl_m8X^32yrZ$ z66=dfwWdWW$%vbm%H|s{z9Y;xUjhAA=|p@F09};&-viK|p_XwtpW23qvHya)y405R zv1k+7&9}ZF6Bw@S=Gznsxw4yYS19T}f{`KhqC$nP?DQ`wRHQon4uz7c)4!}xwd(Y* z94|$xR(1MU73zV-d-Rgp)Y~7El}{(vH_B(den&YB06kOE3{TX2T&aim6)JSEsYSXEGGs;|WT_7`WUhe#ruL~p5gLCrBq^F2VUhqbnlVR8 zgPIzD4Fozh%G`|A9u7n2QO%4t)oeQ?3aRAA$b^{pL6}&blAFQhL@HsfW_}x}FF8x?n9WJ;B27#D*ue5Xn^EYy<# zmJ_BxW#;Q7Ld_4DO_<#gbZ&vWq$dW7`c#GaOBc{tNm)#q;ab@U;uMnI#w?N07V}70 zTeGi(A@OK4z)Ewvgkdp}JtSpbBw)RB|oeUi~h!<3i}g^;Szuv%Dbx??r>YQ(GTKV3A< zwc>0DT&k-kvWNJVWOO$_mj%^{2sBixmuYup_4{d#ks0Al#YdP)PAO)RF)|3u%!6C` zl0PZ|MJ>|=$!z!phRYv@Bk3vd$WhDF_1ReD2kv@e$t*tX>3 zKieN3xsspRwwFGv_&*AH2OiDMzwpcdnYxiqd>aOzlFQjrslMiO;E_1L5a2j-zvP!8 zZs`r!&op&6xxWsue^#tFW0Xw|Fe_weSe#o1I8ei=I3I>zs@@zWL*rs9+xU153q^1C z<3Z*^8JZA>DD;EP>m)1^|6{pB%;zO66W3ENhiaJAjY1lautYYByhS$CJgkpuK9c`` z#YE)~WW$U98BU0B8cjhv2SDXAd5q^rdrysktf?z7s!0L(mxCnmDGjiC^GRpLxp}yL))LU zU>deOtbZdfTKJnWnescxyZxx(+mD4^>35Vx1#MjWakuWO$f<@x@wRTAu7gs{X z`u(k@y&1VsyoVO?>#gG?Oo;iMY7DhblCVfD=m;)z!7`ONVEhg)aL(4@EnmYzSt zx<|s4IGZ$&vR;v}S_~qQW38_wtPv-q08h|V)ryrEzWlTmsbkJP#4Sw$$5}}U>$Lp$ zMg7z%Te{Fp_4pGv!3!*IkWH$akSk$MvSeID8v~DAlibPp%*{sTbR{f*be`PCEGY*E z>;2Ot3q=WRD}SckhUUP1G7L$7mX#xym~1iJ2b`_!cV4W63{V!<4uO>dRkbwUZpG zmfg-jLx9R_89hX0SHQF6hAxLFtYT%^L!rqq zZ57;#!;~GxVaYijaSy{wDu-;OW6;n?MdAchMp8dA^shphh6fk1CYVi0;roA2DUVsp zu7^DX#B6SkLDrN|)s95S?syqQ3$1y5pd=Q;((*6ThZA5R!czAy)^cl$j<9L`OXRjb z70`Ydi2kJ+1tg|YD_o|}3`9kw6mXfAkffN&u6(&vcsvEMqzB*?I&F#wlR0l_>JF}*L~zjWvjad;@;bvow}VkF^8YnhBZ zMvTFP!@ph^lot0;s&CUWKT%vxwRfjZJ4NJDlij6jG#wo54~E5mL_NX0GmvBa)Ctmk zA>7dOKUnMFsQQfr{b;>FcXz7UpJYv{j%8s#TW$IpNLhhV4Y@EutT`CjqkWhGF837L zN7SBz+CXdXDwDn}kHc5{rfNwiDR(B?N7d{jC3g$kH`{5FCpB_ew!L1!tOeoQQA~-O zG>wV=0f)yn#59!ef9||Jf(Z;UlWO@3=Vu9R(Z>Zm=y)R;8WQo5fL}TtBn*o|WYZyM zq=Zq?0Q=Pc%9$@=T>Jzx+5cKcE)*kJ&^OKvGBhE6qSE=+c~-(Av7UP5d*?j~%ft!} z7C$&YOPCbpRQNwSd80^1N>~)QpPVuYtHn+XZ~o7YnijyOCaZtZ5DJS`_|@qxBli#{ z<={8xR0-?E0n7vZ-<=yI>?gWWLI2@AD`CC3e+1y4&U+FL5$7=NVdrNFM~LZE(0@63 zqe;~m(IpM|x6?(!v`DrCG=q~R91q?<2zKYRN86T^V1%CTzvQq51<(KbI~>)vhA3y< zUUtl3%oJbHk@{Dhl!PG>WK~~vMoJhKZ;?%}IcG>170~yT*EVoQtfh7Zfmxf94H0)~sZKstCO^FJ2;&+@{ z39H2-!rjhj32OxRxBPc?XswvQg7!EIWoQp^Ke~$lo^!Q?b>cKuVXyOug#F})1OEHY zs}k0WQg+i1oWl|h5hm@A51k4rog>6pOl|#rPEQHPh}Il@_Up81@f{SJ|B*9IhK?6s zuq{7!u9a}2D5BBuiSw9*Q_wtv&=@&u&_*RY&^#0UBAdsQ!~~LCEZyuMeb}c<DA$_@x?##r{0NGW!g<1{xQ0`UAF>#~f%7&0qtRYuH?@qhhR(-xYIp^?QaUZMB0@ zBqnh{ZzGTNvpvFW__nrM0Zxgz>=2ctP}S!=l1d& z0u0LHMT&d}dzTEY7dx8)cC`0NI7FOS1lY|!K|E`qYtgG@ zEBbldKTR(6s`i^1;KyEIm;Bz@pA}G*G6eUf{Mi9+XMub2U2lI*AhTfpCsjfQhQ+a% zllyb^rNB|6(#bX@n&ehA>g+^t_zcw&$AawR;P{IDc2={CorndRTZ-335@FV)CNGveFbe+eZC3{yW^oOtCy;o56{>S9S;ERcmM|UGYSHJauWx$}(Ga;^SAB!puA?~2N2PPfp7wibt_Ey=JRG!_ z;Wz#iI*wU#BD#ObckE~2B|f8e!}n%zvz>mUpyt@`OUTdN7!YPhlRwCasd7z5$oRYg zcgcfj(IUTzJ>z&}I=KP4CvHu{MG%0JAWgZF2OocDbhCj`4`Lh~LhT5{` zLHk~K$6m+a673NA6K?taLI>B7gSZ;}J2bUqkF@1*-$4)e*pTg`OgJWs9l&JL?hr3U zOnKy{Lw*~X2u)KAI}2t8gW84t&a!{2(Y=e-Uh1X^zgAv^fWh9VjQXAIOOT+dDfwMv zZ$TMVC6FBdSUUv&)FgaP?sv7@!)=sogOL>VO@~@X@Y@sLk_XP%LSs211T@47B|DQX zW74V^&2iLmly2h+B@2ZWkKdfD(fC-Cpz~wOfdxyn$bTuwql5B0Dt|{13QEesebl}$ z2UkmIi*rfoE5XOdFf=3va0q)Xc!eB~!)n-lJ*bA=sQf6_e?w-=jWE9#BEK0_MpdEc z1Htxp1{X`MRwNF01KgE`4}rJ-J6U)yhlt%-7@G|EZWgZOIJ+kUQMWHqx01_?u@T|N zf;<8#S1$c{aEYW8XQQdE@`K9SvBf~@>jDi!;xGrj!k{vK!lF6&<2To#QIX~_-a^B; zXjuu^QuCltlu%73G)#yeI|8-}s%79Ju^(E&7r|AMj54u?!1={kvG{xt3dwInk5>4J zUjmN7qZ`~oyB&Sjfcx;NgIgYV84rgX>3nRpqUodltw3cJoSvY zx!h)WTZWHJ zY2}oa86l?=WF%5R6I12X8Yuh_s6qHSDigRL%ZAg1pr`OB-T=V{+i#Q6mv6EmT$3(czzGGog*D!g1Nd5>a%?8nSRjFvaA*fe2 zh=!{Qda)QT&GE);I4xPlAsuvPHi%ZOYD-xm9lkOfPBT|!&7jPH_oNKxq5|z+6)qP5 zWTb2}WhmJxqqDBGi&b>lO#l2rodO6~oS?~^Nna&>SsYE}@C$u1nMhHR#gWrUe_S>u zt!Pz}j3m<>9g}yVtCDD7tC(y&Irt%`8?)h@c&awZayN7E_bC~P-kgpe6-gfq-kZ&Y z^V1{ebTemo|ICJS!g?e<%1^*U(Z|W_|6%V<;HxaIzwu|w%_aBd$#QSV1;Rrh5CTc= zO+tW#HS8e?VUO1h2#}2>M3S%wg0j@5YOS@_Dgy4f)~%HyDvH*vbzdu5t=8REQLEPN z{eEZWx%UR!U;F#L@B8`xKcD~KmYX>cq zSUK0T$CUe@Lr+0ueGG}K+ytb<=#tCit{4*6zCS!se7`8?wBlk|maG21fefF{MR7da zeFyU!QAVF3+66Zuq-B@66qYsA1DfHnqQxxYX=PbX5LF*U1~xrnSU(|_7_Mn3_X|*r zzLL(*QC@;WVxj^Si|grx3ha%026I;oiK}dh6ti4t^?p%K!d!O8iJ<5WWT5|WIa0R5 zAS&DRji^SI<9b|{i|Lby6he^{$w@IJkrGCiKWK%{z+;UUs2n)DW%0NJxvfb1bcPge z&K7~kmgqO#+zVp4cQaRrjwz71AAf>Z!4bm}UK>N>g-Y_7ibzo)z$ICa^@kXi7f#SG zemG<(vXK#d6w4M6`&6J&`t+odn2_>B{A%Z)ALd8ozq9x%EWruduT3_!gYGbS0m}6$+7kW>plDv z1({l)Vh|qVl=W|3hyeFmglJ{X6DWl%w(mw9Up7EOmi;Ie_hq>f^4iZL`YanLA-{c9 z1E4{q%oE<@j{}tVvVbz|qX?$U1|JsCVEdCLfQCq@Knwf>gXA5Nd?OpbB1_jshzmv8 z_zhUujp%g=I5zSOJCjg~gm6L!4UF(f$fE_eBdAI*@AWZ>1h9xM_njxIY4!==tK2Uk z!+s8n((+WIVWDh)UjWFKWwvH9p*1M6SX!!gWa$uq_6>+FMvnYk63pyuS{8#WE$5N> zV1HzI1`xB?V7WXp;)7NV>{_Rd98F@H*9U$^jwPkQO&E^QDE~F2%H#5*Qe`NND+w{D zM%i>N2&(NQFg7avHlQKIvH37-RE8`|w|7DhM+NQ?WkF06V!7^|go9sW_@StGA?>{k zyECIRoT7_ZN`Y=2lq6Clvzn+nHEo5g{8ncC!dWb>E(j*9On+U>QSW&oC~4370C*WI>~reP~p{U1@cKwB^0Kj zm%dbhOPpti08G)P_?A0)m;)6){Y+8X>O5ZsFje0tz*Ww}tZVC!3b4azr6hv7+y?K` z`reE+=Qn2MI}1<70CE9Z$*aJ{Nb`(;<$L3Y$pL&78d3RvH_)KMVl%z+gLec`zqpsR z@BLsCrRYI z3|(_`ERpjCq+I!(q+^PlQ51^GF_>d7W6t-)G4pQLo#~kPm6~{N&rf@ZZH7uiUju>T zWl3FZ`Bs`bHwyUl9Uo+D)+#Oilx2i*-@rg&ooe>XBTl4=3mspBmQ*Gy z7%zL);(1D?SLd`AFL(Y4R=l#8dY>Ne^H;D7DGJ8>{HJ5BS}9M*@j6atEz5(7-+e~z zGce$lS$bS{M(!>SubV~T8KpdOAIqZjjNI8AS{IArGjiXCL5O8hen#%8ScF&hR^%x_ zBR3ms>&k4Er8CRfJQP_WosPrIyTx#-VY({&sBaeH4b+Pk0`9AXgf~zZVz;BRpI#45 z5^tbRWy3k*RW)3yfHznK zd0aVApRknl-}N{b!GKf_QbPOC&ea+RFWdMKgrHs%BxuC3vy^6m2Ba?*P5gSky z{nRnNsm^}Pp^6;wCJY~D@>QCO{tB#f&Z6&-qlE*sjs;;=$id>1r(e+^=c;z2&NFmZ z0~L7E0N%8Kz)9M)CC-(c-Z(HV5{U^Y!oMZTyjUg+*a zFEUhrehH<77g3Wi3Ka!9B_v)%T}S+4{S{G;7g1>lE5iC40>%s7G=&ur1>?ok6EP|k zC2DHkq>F<&6{B=oV_`Zr(0hzlS6|$To5CzwcNw$OAIq`fD52;RjDb(5WA2gdM~19H zH{%yW%H=p}c4hDA(-4ZLO50}JfKT!3|SP`AJ zOYq8AE}eJ0b$O(LHXc>?3#594Y4qv;0_jy0`E>dkiNF-WzLwhZV+YT>_vD8G3Fe}3(njlVj6R<+_s)7URWG+zU)yo28hc&@+m|M zxluqemxeKM*a&iI2P7&g^dW}I&Lp4;Jy)nT5(yQ^c>JpH9wYnW)Rba3{)7 zP!zatFqR@?e)=-fBK#V2A(ITr-x`J9{p=n?j2@UeiV+Wd2*a6EIrb#P2jZ%h%5h8* z{V_&F-_oQ{U`M$$`G#c^-NEJq!pbTMrQ2Z|`$-ZCiUF;hETNECT2xM5Dq6?^ z3x5JV@$8iGiMU)w3oM!qvs5|b8FIumMP)TtCFF?jk5$f;abSTxg-)tQa$8^zp$n~* zP?7y2o*GovNvOm=1cj@dC3z^vE95ZJ>6Le9!yDP}(v#iu9g=LoOFwpBmIxRvvBIc) zV5oq+HV;Hs9+r?_O;F&SN@LlGP}AqYLyRjih;C@gdZtZq(x62 zl|8}z=~xg|J|_9YtHculJuV@?eHRq8^7mUZNG09glmqAw5(?Sd*~=#+lq)0HC*=YW zFWkU)Rz4*o=py^w-hiH#qc_!FcLJbixCy{Vl0Rnz{j7xQ?9;IAUiqACosT3bC7(`_ zh>p6dW+B6;QyOmn`yq{krua?f(0Qy|IkvQL44cFz!$djO40{BeEa7$+-ir4};Hk$3 zZ$mBbTNsS7SzL~LFFzT{-Xb?0q0`t9lYv7RyY#U)eU0k&Q!r~|Z~h6A9LIYx$H(46 zx?EE>V*Zc)l`Qkx2Py&G%4x|}^>ypW%E4EP%rmnConXN{=m6;9xEC6m)uQk?sMD-a(Mo zxV(Fi^jL@SD_sk3M3c`ym_pHO_!GErG0qo^8(!H088R#y$1kf186Jcpj4OIyK=R8R zs5TqH+0t;h}xpkW(V!F=0?c{Z+6>a1oz9s)E*St_)) zA1KMB8n_7|RcPD<63ATLxIr6NrRoUhHEz-{6wsB44o&XSp((0Eb`Y~=oVaa(GjIXs z+_-7v6OS^{)?iRbz6WjLsRlArt?^mB8!WR?8=tMVP&Dr{n6dGp2=W6fv6L7*A?1%q z+uwomgj6P}w9lb`6Kn~=_~ZgglaSZmjM+RPT|&4U3TwCt84^mjH^4AW$dpjfehSuO zLf~ydGh{!HIW!?Cp&a}Ak$|!!lnaKb(7_k6HbFq}I+^=+5k#Dm$NT&25*YQIAwxw+ zrEcWpOWnYw%$(LkfF-8!SS@e_);Bk&^hd0C7Zf+AjJGSWSG;2&XT-HA;B@0113Bf7 z3n<;5i(ci7`m=z7c0cf%Gx|#bg@gsqsYqGDdORFJ=gYeT{o;o%T4)h^K|VYdo0eFl zo`6N3U1xj~ihMd7^a~0sL*1uEUD`ahE{c%*u0SRSZq9ee2@J@_367kx3y?3)5$23n z=Lj=buUW3;OpwvTVB2#Nx-(H;eNm9P8n+TwogjKsggdse0|=Ru2F@tqTtUv8TanH$ zgTc}A-+{f-^RI#Y`5y946eNF$(eYRpFv$@KK88gJ2>cuw9*YJrI399F&UMHM&cw_^ z`VLY04Fu=i4wEoZ><_W9|6@Fhu7Nwa^2?o3?&5PE<~hdTgDZ~<}E%MGi*^fs8fsy|9Z&HfeQm#SAJ zq}!7)(W+iufi82in2c4uCd(|rSk<2-lq49ddR;;u`$f#ksy8H*ECf;YXGz5?1X1;- zgi`EA(tJxoe)|Xpsp>DXo^5}~vbQCaW?xU}9SNn|83?|rs8Zl8LmTvN5ce=wW#~uH zBS-WoQG;JrK?UkRS1HrdaF{)8AiI<3QTg|MDSDOdpk>krt|YjD6Ln5vz(h?8LMWiQjha{=xNn_1tvRxhfS?opg?eOA4bnp zHN=?H?usVg=rKS;6{tJel=(0PDlUdA&~(z_sjCVNIaw@i&^HM7yj6>g7h;4L_awX| zMtC`_W!2Ic;kV(DtCqzG-_{6lxdJWcUdp^lfk{p}HodEw73gtZXKz~+n5+#60Nbka znBFxoIQ38iE&mQMrsu!em$z7yqW5P0tN@VmN5D!aX+!>jNWrSI%{tb&6pEzfKLUpI z{9jCAje{dtBR!Kf?#G5oQvP;CJD&Vk(s=p!KFnFKHgq^lyfrChB}v=|vReL6u|uNg zkAgihH1A2UTa(h+K;U&Kfq(Myn~}C(gAz|}c0JKKu$`0JSism0?@nryS4fCAQ>Mp*_pV|Vv5&|A3lPSnvx(K`Y2lfc! zybUFAMNJ_p^!<9Qu65~w$9M~p&7;bJ$7NM4C^5o;-`@d2aVRz(59klF%xm*Bao`Ca znxNkw&5l032P7CnrNRINo{>Tb+DR1Qvl0r~`w_?oo|90H9YJIlcwR!enH??5wZIG4 z2r7f^bD%(h7v*xcz`l=EUXoCe{WP>L@bV3!!zK1~%yI;T4jG$6^AVkM=Vp6MADIS>&M-1qKcx194wmI<0jTkIGGO=~|kHDw*3-Ce1zKH|$x%?{CBZeI& zlV5UX@{(Pr0H!FQtNrWeU{cA4dx|gSM)w+6vi16xCq_%2JV}Sw74rga7f-2F1J+z_p<=g1hfi>P8LIf2hS(^EB(>j zLsEA&`|}JyzatW7)n)AZ!xx3bJVNlwIppVDbf5N;0?yQAs*RMp0g9-6C=TNxv;>dL z!htgUdP`wEr-~3Vun{WjpSCTn8w}J!e$%$Q3~+N|+73BE@EsKpnYL3s{{@|wKqoK_ zowcT&Rl>>_p(oSMCLIKkuyoS{{A5vPXIqOlJs1{K5G~h1)2C;#g0~4BoRKja=HHt& z2Fc7;k&-w z>09JD=W61-di|YZ6lbHC71&pb7DT?Gq zS*pLf>JOwYSeVpGSjVc6>M&Gjcn9wpMqsTb?q5~ zb-(?0*q!P+38hmAb0(2oe^!|*{flP*41%m)_#-j$JU~%>d^3@3EHtZ6K#wS?%*D;i zwdxa<5VWkW>f(by$`;ZHi)1l{U7n2|W^bH_{|AI=xg;!WJ?ogdVY_Tm=HNypcRqC>D2`p8^F$bvcs?Yih=u)4QRMx$37nOzq-&B z!PSWGs!wJgs6pQCh{~!Lk?f$Cp{=L;?=g6~-!Z_i|6X-pvF2P3o8rGuf$D2uhZN{_ z#$sCg?^mE-T$$@XtiW_D=_5vAw&Nk)cbTf&Ua9E|MTj~WxT_I z(8m9Qx)`~@xd^d?|3%}2ZREaaKv#?A|D*ARfJz*`2j@Rx$OUYjTh&$kBYMSJX#Mv3l&zhC) z{LF*^YgW0^rM0P9Ev=1T%hPK6dcQ2!@rQH*127Wlb#wT6LfZglo%+s>W@p1@)yF|X^QPZ5#dUaULb9ojb#i`AXL&xq0d27Fk_dS?}WMa1tg>a&VmE>q#pW)&+g zwW0eFrC6gr$vhQd>R5z?TK)zs&tZ)RgO8H>mQECid(!G#*NK2Zv!_5K>)Ut=h+$3$ zp=bRH35CRIp8Az%qY^Lo;`yEWRsKzc@NP*Bpw+Tv-daHBwgc18AB+Qe@K|gxuyhU^ zKaVx-+u%3q&u=Z#IWLLoe)n6pba_uw2fG(C$0a*A6Sr`G&-cf%8+Z9{#^*74V)9g!$e$#rz(0~A- zTV&-W_Un*!{jcPpwAxQY2kLK?Jzm8gqE5O_TpVpgTC~JZsfnqJQ(i4F!`d95cv!$s z=!tw@c6$wgAiu2#Pe(Ty;43!gmJCS3J2vtKqFmRp?S>?2s1l?-y#a1rK7 zNggXPUX7q5C4;j7;Rb7{L4PGrb-C+AL(PzdXY!etkMKsH|L)m_iG@1$(%+@J`+$C!XpQ{@U&0qlle=J$3J*w;`^8Ky zyn7%bAgU@q8&Y_W`&^+J>!HH?blgB5^I{1!O@Kc;L&;dPU?Kww;b z6z-F9z;5LXK-Wvivflw-;f;Lhof5Oj=1s~p+1J5s7v2o{qRh`r9SeUYyP7T@KDkiP zJ^%$Qyp3()#YD~Gx@|51p*zW1|MwBP_>=r^=(~|AuAlJ#SzQpNId{Q~`QH>puvShE z42u6P6}aw5alT9g{1nC>J)LHr*nDf&@CI23 zX4?O;zJ|^66r=wWMF|%wVM6$iDiEKmZvN<&H+J2xSc^na#6zc%P&7~yokVcbAU z;tQvyA$ii|2Tm;oTFz6L9R4KZWif@YWwRWD4f*qpzp!c&r99LiLkKsVCt(0_Bv*hQRTF!!r07r|@EU^O@LV^5a z#8;Lulbn_l0ggBL6;8hEbWRq)D%I{_=R4RH|8xZwI6GmG{4-SDBBz+hHL6tJ72&T{ z@7$L=-(k}G>tnC)*O05Z23>=J_fVf_f9DzUWzY`iXLAA0H>C01FrW<|4L(71j%z|^ z0-0PQWGp@nAili1ObCmI#^je*n+*Bo)kpBr8<+rpiy)3qk?KwfCBH&2YUaJA58$It z|0;veI!9mjma*AM4KGM$~s<96~#TGIZfDb@^r5ZdD&&AQ(oSS*Kte zN)unAT`wXaENTt;C0Z9g%W&@HEOOy<4d+ETj~IM`A-_bsLDjzq=f4;vxiAj3E#O>m zVH|4vn6aD-<4~IyuEW1k)xX+szD1N0gZCNEU6j6Cj`L>i7QH$63{DtbX z)Oanp3XK$7p&e8}%Xt!}(;rqK-Uy@-h*-l#so(jW9F?llbSG~Lz!6rJC=EJO;QjpN z)^P$1ImIUctW$M!obwUN_-CoQxz1;Z#r*XOd9d@C4RDSsEpT>mDCa4#$T<;PG5!VC z20^*RX{Ml$v(6V_xpN^F^!^j9y#nMF4oA0RIsYws?$c9|=@&orx$blC0CLOMoxd`b&=OEVd`WK0>ggf)6p<9d9JL#G;o3p_Mu>xxuTd|t2Ayv>Pdj37)z7C|uC?IjQ8!oG<4y$@I9Jnmbt$mK z8N@l$t-uPWliIUhfmO~=Y0Wk$u-YkxkM^Icz&XwZWMi`eqs~zJrqdL-#OWmEtqN?F zpY^^*^v=lZa7NJUU1xoO&f>mPXA3>o^$Og8ad-wj4-$#`52Qg`ut*H~Z?+FV!@SUf??cRJ zkBelBS1|J%)naaPuZb^!i?#llZZ2l%CYU7DU>5kqbjGnUOm`VH@f*(mA_SG*!)oTyjHm#mTTWo z3aCxCHy8{*4EBOgEfK6XgEnrP%f=*I+O~$wZxA_K@Ee?fu|Uo_O!MQ+NM9^Uxt#Y_CAitW!{{}1>)2A?W6PY!`n#7*(Ss`(wf(xmz||)`H#ZXYx(<7 zNzeauG@ood0()rYZ^i_(^4~|Cla#*$F$*M*VUMK`P0FEul&#J@L5$nFE|M? z*!;{ZKu%mkK0k1=Aw-?o)V^GsAC!>%+SL3kSJWJa`MrlKQFF(Bel|%kJRgGT;6g$B z3n-xrg&;2S9rzYTGJV0&*Vt$nI<}xdjv6*Pu-aQNOvdQAavYkzV7NRsi|w$5kfXJ* z@GDkJ!=NoJQqiL3ZG)C9EGEIgR7{Df3m^RcY+$_tU$^j~Ek71LvR_AtyzqAy2*|Qu zg^(6LEX%z1DngG)$ZrP`Lo9q$Lg{uJjK;#pBowq$;2#%0E}@X!0js?5_Y%snGoU;R z{~)1U`&9DygoFm$m6d>=lu&{FK1|udrzBKlUy=>zX$h6s>lXrgMndKGkKpbWJ}aRL zyNQ_3NobsX0)~6x^Af63^DFHfXbXQJ?JWEmG|9mNtYMQ*G+}TWHtQ_Md>YW9HEhuj z|CE3wc32ut*X0h2*Leqe(r|`4d0Zrp3pZ@j9~H)v@xAgU?UO-;0(!+MvHcC;baA6}@r#Vn1i$Wjd7~1DE?s4ZvN(#_2IHK-h;5^NZyvlkA}4>gR|mHZqYAZn=4n}s&|9iAX+7^DAKfaxH> z<12yXP|9G#&Tq*W5CFWpT%$u_~ZEzWl7=&{Y2I1VHu|fEAtb-hP*+KP*kHg52 zeP!q9#-$H$c-+-f&L=OoJ5ly-L*LRCdFCQn;4=AWi7~i-Cp!RcikOQv3aO z6P#efVR_~%-L9eGddSuH?m2*dceC-`aJ-gdGvGZg@xwwWe7Z6!v?iYg^z%J zh4~Bd5EXBDLr73xA=IBDCwM>1BT8REI&dSjINccST!`U&1vo|p&mS>9E{BMX$_Y!Q z!d(ItGsfJ2aX>_jLlT&>MMm9av1+q;mWtJ`o&>~t8Fu;YiExC5IHQ53fPEXBrZMLV zRAR6^9Twb}d!2xCWOMUnbGf!?Zh>rWu-%1#-dHH10xh^2N(}zlIBqFnFRsD3<`~Co zKXZF=0uPvxowN8Kvg{xxrg1x0 zww%I8Dbe376qtVda{BN6vh{TP*Q9d5Be)J0bd$>6tS9_)sNf)iS>vG0fO`%Vyolh< zxJPE-LtvqTD550eUYUUpfrSc=8-a}bWClJ27AmNPT`&&GjK0iRh~UV$UuN`S#te8$ z;{llwLWZ~o(s+=8ARp!2H6O(fQK7LnquWLB+s5y>A8+P8h)ywW#pt)I$ z7LSz$u7Xg##)lVDUP2}xu@T4%4+okxJwL+Fhi3WLTg2EL5c@oJQ?xP<2b3-LOu^$qFoYPDJ2lEK*>F^E2vZ zqyFeXk{XB4HzQDZ#4zp=#GOmCP>+M}Sj-rYs{WOTHHh(; zo+av*4`}Kr(TvA+ngl%58Njb68h_B`OlWmZ$Ofq=bsjAi?+Wh@0)9&GhsucN4QC~# z^NfPAjXIA4cvc@M%CU|59PRFN3dXUWzMTCp=%upUbdGSQy`)~--Df(x`T>4f46d1X zgX!?gSjHa}e509L$Duo-#&!VS{55m$!qVM%Rb@FMs~cN{#%n68zsR~W2U&koSvewW z9j(IaDyyH!8lHiyH&j+%k@Wz3^k^R zg7G=e*J%LXRq#R683o5=ye~8i_QiD0q0ReH%m%U7E41iuLW^*A%5=`hUb%5pwfB_i z44e)4Q+>1$;&Y}W?9=CNx#jpMq`wPI!lbsG!}KvlmQzPP{nmX!JjuC*gYcdEZgGCm-@o?Jkw!MJnv1qk$|2zzt zMW0F)RYuSwKJsVLK+JG+9WBU4P@7qUuEX^78mZ=10OC;;j;gCi=+1EVHBEi33Anpq zGb)T+^G4!w3&0p?a%n>2o<}b}NL}Jtt_`{nhH{m0qIuP2z~x4sagwQmXou?#W083n zMYJDFIh7jC=LP5$_thH9%+CercesyZG@I$Wh@9?lBgbel^92}mgzQ@t7;-M2htd@a z%yCB12&`0Ku460(xZ2z=C=YgKjRm;IoR8kn+RUTz=@5dzqA~Xu)ZJ6W<)OmEx8_b9 zhn%%42QI!f_hC-4PL%^6--@u4zJM+G>3sZ5VQ}unpX8@jFiC;nP68JLIgcVO>#@(W z9-Xhdi~35eoI;T0YH{>+tcU^;MIhK4=|RV1Zl>c?;p+f6JUe0hNifR6x{CAqbp=|^ zd+hle3iOJ71>?_ZDDfEdYJ@sL;~n!bDTz?>T~{X@KCCz1Gv(8IuT-G-l>(*bZlrzq zK*?tShEI!}(-&Evn@@t4$9f*WKK%{+`uT&LckpLa_u8demvO!Ii`{6DS9%yXS~C97 z91*-5Ejac(cV2htCLlAs#nwQJ~+cO9%L?*e1B({r1=sge{y~cPbEH^PoEX zS~Lo8D*efC#N2^)z}slXU1EOmV(KvqfxBOAwwFkW{Z_S8?%a)iSmS^yt#C?dMebHC zk8_6h0eH|tCRnZ-(Ak10(VD%7&{St0E!@3|Qni!K_~JfGy4E^5P=^#a$LURTcfTcr zzYx&Dq!psEbmwxqpnFtd(5dDa-lxEjb1q8{C3Oho9P#kn zctDlr%5EG^k_TA1-G4b0%qjx&%TYmwu)%#0DvTp@aPt_-hHgd2tf+Gta`IoqRMGN% zSS9KC-%|uS=sO=X>?}Q6cg7V6py@ZGvvyv|-fA{)oQT%*om})?oKlL;mR*mE zS7W1d6e4+5QNvMAho6%N`3Zq6^57k+;DB) zIA%SoKfovrkvL`@!MZ4VJZtipwLJxqP4om-<#{6eYxFmIlB|nk*5BjvTAeXrru)W7dAeCDEm_E{<8RCs)g4-F>>c0u%K99fBakyKiIK@_Gg`tt)<%R%O1CVDYF0IX8MHHbZUq ziXMdZ1<&FcM)VSy;bF!v5cfrYDKnCgA(o!eOQj~H+7mF9qnAm@wtqVb&@Kt3+0Pyi z=yLXl%jfx&>TU^T*d_@HK3zc(58Hf@$(&NFtCA_8y78!p_?#!-__aC{J(G<3?YV4%d?1cug|k zwO6L0>~(ijg5gB;4H-=YZAK5#KffTDtG4N=qi;$-U1z_HQ-RU9s0+9fMQj~M-~L2k zM(twQ|L8l(*Rbp)dm*+8qwh*+iOn!0`hFi#wp@IhIr@QwTI~;~qU@uHC|hOkDFO6X z33Z6Q&*;ZBqO42oeMUc#G&hK=C8D1vMkT-utzt|EBbfp&N2kXQCp|i7Kd`yP_fb!jGLSqsgmgmKBPO3z@0=h6#O8!8h!yqv7W*( z@t+7!laWiCiYq}7fyn@f;?BB^IjI9Ax-(4x>wFWel048AtAMHOy(E8b>ezA%GDCBUg$tid&F$ zk5$}@jM2@|*}U0e)4)86j0&EF&YR67YJQ17$$Vs2xdvn0aGNd>bFS62FBjVI4#&I58h-`&(z7}7hSmV&C4hQ}#(x??#*})9rR@MGmCz=)0h9O#FPaU%uV=|rPoYev8o z=;I_>D|twibPw^mGVKI~e=k#4dRIv7A4>0Ei)-r0)ybqGW<4*x9vz<5~6U$@~&wKWrOqOcvT8v`~2FUcZD$ser%MGOy1jquACP^GW7<~@p{WXWQE_Mhu#sa zOGXNT2^>|{Mq(|!v;PkkDKC`ze34LQD%Aeu6UNitLiR#V1O zkFZ+SOmcP}iiAWgE$e)Yo|Q7Y#6){{AdQz6NibM|_VnN{sZ+t#qSe>fYH-*pNG$kc z{Ca}tacqOHvB$wWl=cb^0)9&HQ_%4Ro58(5xD?uw8XOHK?BD|Arv-bXKk32cNM{6B zBb^!S1I$2BLpm5d018>b2QV(ZgN2}(tz{j>s9P!98p-10Xi^LILGya>R8%v9e?ia9 zpa<2g;LTt(Nz1yPoTlvl5i3-R3Rj{vJ-7>mjNq@quc@W31TZ+|`p1FfdyO)>fg?kS zm9P^xO33mhfqu$O67u@aMVl$VVkImFq%>avp!6%%Ks$p|ZvQ*7dUq`A&{FOo6V!z4 z--#l>UJ5@H+6oR+vUC__7KYY>$&}s-^oCvnYDzzW$*mco#gkA?jal|GpnFs1=!;0| zYLc3(yBgQ$I`r#HBgN4lNkZwREFGj%o!HPwcCAP?7u_e--6>tmlR`_$??w8b1^!z}p+6D6Se3t< z6q?QUuT=1dNuibG_bLT{oD|A{ex~fxr-=4HOVUgZJcT2M1x)Z`g_MqfQ!qb8S2=L( zlNvm8Kcq{Z1>750A0ngAnGjZmC#A_Cd!a`#X;PYvrO9&Cu4BtB##(@8-p9Vs@#MVK zpiW|m;txeA=@kYohnaVQKjdN0*BECB{EPgdt<+%`k^4I)LrkW6z;U|&reZIw$YU5L|IPP<1o-uB!JznW*()H+ zcK{;x|4Np5eG}QjttWv1tcdSy^u&Lggi?JMu*utR6!mN^c`9V>zvK4+`xjsv=Or{0 zx{@e^bk$PmP14R&pcT3ua`O*Xpf_|PIKFtmZK z6(}$i@{{r~1?Gg_W$ADQ=7tWihlL6ptT~^Mbdg>G7E>ocCH$#5{dz$zoH(idr-Mg4{o%zyDNout`)|_BS%Rj0v^F3m z=mDSh=hFpdweLjM`}+%`Y=bWs%5Q%mTi@(^3a#5;5;F0Qi|+v1v%fkSt#L!n7lL5z zZ+;Cr+zIe40(17ahXi=8?)xKK`A*uO3-rFYs>9ax3(|;ukskU8V`>}9JYAxPwzG1Q zf_Lemg@ir2B)(SY*;mH>~f>B>j)|&`oT=MB!g#gdU~*Ch9K={w^^> z-?D!$yvqnxlfNp3zt;$5vc3ynZG?VF`jhlO3f0(Wgf>zhE_{;_n#KN1)!!8KZ#6^1tSqQ6fWp$l2wt$!}sd(H^0AiPfX=OqKii<2$MS_WlK{VO^3(Nt?oXA)d$O=GMbbq)n9>cpR6TI~KZ^Hce*WX4ui z%W~MK99GWZh=LF+%W`5Tlv6S}MUW6(<*OO#xurLbT-mSRvEAd ze2i|K6?0!+0M=AGp%56UjLrfbqIyR3ie^g_-Zo249%nfStz{e z0L`oi{50S}9Io$^wbTzFB!AilFFNQu%&u(gFZwD?f7+=P0>M%b zOab>|{7HQjat>w;{{(5_T`~%ZLTTNP!OY;pC_t8vVQWUQggm`@CuBx=1u9{5dh?RY zj0j0!I^|_!1BUT?@WD>H5@RG}nQixO=!b>hQ z%2vo+BuBh}q?Q`RV0tqunD1Kv#Ei;uiq*FWjp2aFsHy`f9#Tzx8=VMcOdx^YyyP;Y zO4aGj+sQK~y@3MMksX@cqeD|vhkQSVNzD-Rn)aa;Bb_mgeDcMmBc&r!P?Xe- z5dNIZKHuSCkncQI?=nJ7>LXvvMeNek(n={9G{<5hD#{dHR!WJWmQu^{$Mg0g3p zNX#PNd8}937d96s4SbKY^)gvj?wf>ZnK?p26~2o}a};Ao9Lo|4lUXShrb=v0Wby)G zluh*wf!1d($`v&0uvA6D#y=q>Oyx7c4yH1*lB{k^^$rl0QTD0wGpTor%#I985_^l;o?& zxCU`6n85N~f|8&uA1TP;)ii+%)uZx$zszIi_{aa$g}Ha{tTpkIvdOp z6j+A3$;gnlfvt-oD+LKT25H+amA=TK}OhveV?)e z6QzqU=#48z?WzkJg?Em@L$6**~ZrQ*IPN__}y@?U}eWQm!t>*i)q2w)p@sFwc= zj6mUx0}8ko`x+drZrSy}@ep$)le zf)#8=h3q?w(H>i(_}Gu6AXKgmn})(Z zNsl5Y$vh5KJ^PRpSg*NQUTs(qUFnnYH-S}8tS4M73md!T2))W#|l^3j}nk#6WFkAc8^aObk5K~ILd6nVkF!)Hh8OJ=$N7(!hEd;3=|+@v1rH^0 zRGfTNRMBr7=TXBe&_*Z)5hdmM(7lnC93xRYD#oe+M~Bf*_Mc;uEBaJ{jkuU5RRV~q z+n6}AL>*h6fI1F93>7!B2_Pv>cY>lT7@HU`m!zsxL!xw2iXw%_p+3yzDT=fxoT?fX zz%+#kQBDubN@y|{a-R`zVP+sh&(y0t)Sv2jI|ioU%s4TEH9kyKJiygz<1I43E>0{? zYF4~M#HnYMnSpY@0iBy2ub^5_Ve4~Tc5!w^o7-P66`VzV$AkZQNm?mT=JQVuIvZ==A}+Oc%-6K_aaET6!Y4Z8y_)E!ZP+*vQ~Okv3wC7g zrg#Q*XmcE#DD<+YBg)kO$8Jd36k#!Xxz>?RC}skDap&YubWW+RbF!s#N=tN3>2YgG z)14um)Bo3conifv&#ZdpP8&af%FR4lhX@c`e7SVzN=O=(@XF-Df69c)>^`^pgk(J{TQLyRc`Z_o(>2yv= zK!E)^(RDf}9cxNYPRxL_igo80JH9xPAP03xLPaqJ5*-(sgyV9ZTjHoJbKS7(xMB^) z2U$q4IbJ_5?UqEp-|8CwHug@_;IQ~-rL_I4T-Bm`SRKaqBiza0x`H3NCebimlQO>2 z7j)1=oDv@+nY%WQ#u4d^gLD{Oaq$1J!$@=u|0mZiJy#1E$`XkwOSchoN5`&U;)rxK zSujB=_@|O!B_owUt}?P|!{~HFiOZcna=FvjUE%bLuW)h%x!97Xf6o<;6Dt+dqPcw7hs1QOGscutV>WqIt;P;`487E@l{J~tSjRd&t28fX~f)u>ommF zRc<40>2L-Tvmk~%A(2?zm`{uoq-m^*PaJ}iT+=uC2erjyor2nmU7~YMjf z#)Yw0W^g|x!DdX1 z&y|=xa(5#p9XnYk%gAF&LOzBI-&c+;MloBbxz=KO0vhsX#9NZnw3?HbJ1I)~GPfp< z_AjSyeCN}2cRnpK?r0{--TCy$ozLXNIqQutE_)$AW~@^Z7n8oYUeU+<p~`;> zeX`{yY?|xh@wmm^5fqb{COA{By8=DER?u~yS+RUUk->vvh|Oll+7rGG8=|h9SlXv& zEP!Cb)k~I&kb>4YN3NBz87g-undc;GHE#VzuVN90yAcWx64&p6@c?CzJG&4-$QWmE zVrVlY-UV!;#|Ki5>`;z(!Lj2#ERM$U9v%l(BsrK5M758gXomhZcA<6rN0W~KFJIfX zu4!#&q`Pxzq_b&lTjMG%(z<4KQ)GE-Q+sDqdt~aG_3f+HG%oLqtZHlT-cVc?9u*!@ z7Ospmu3grOpVg7J_GPQOmp4TkJ6CH7>Ef2Ab`V?^S=!dMrlT`fB*?@dRB{nxc>;qR z#d5mVHZE(5G_7lD@9M@b~JS&34$GKI@>lZ?uuu)Nif&e z-lo{>*&`HnwXIg%HFtD&HFgmIwa#U&P0Nu4MrTJG#%$S2Nqcd3$3M%KdFvb9c2=*B zu>ukujV+4q>eZ*NX;%%luUX!-y0LSmth>6qt7(Hwu3eA2{EFRnW!|!m?l|tUHLE*T zHFdSEX;&4Nb$2Y6yrZ>cjUA0k+g7!8ZB(U8yVf?THapg~tyvrgSFi2{4*J_nDY9-y zw~`2k1YF2me2t~Oah1fB>0*ows}QTLMJb2`B&O(fSF5bQd|4ypDbpQoO0H0pjx}r9 z3DtII(=v8Up~Y1Tcipe)Ub{@yUl|`Url@9Us}+P|07q+ilOogw2`@&c8$rCgy{k>= z8)|fJ>~uT55_ju2EmIn@66dQV&1Gv{60UO=5Moac+Pha%BRV zEECYxrnPIkI}~NAmn>M@xV&vcaeNpc=*EuLHER|9<~G6-^_1>4U5zri{FJ4uRxaM) za=i>MlgWbi=FY|VzhbDf>6FFIZSI@{2dgoq)g&R*w&n)_xaag+wY;s96B}UDDkTIt ze>)o2HY#0!aD^&huw!!@3e*kxV%noN02E;Au4`M?)YZ7uRIWdJLSJz(zGFx1ja!oTGwNGAPG_{ zo7T2BQL9nErP);%sF9k6E83bd5=uGY$WaAPIS(i4;YcL1y)IHJ{+f@SRue8Mj%bF3 z59oTX+_|gNd|%rgXvr}9)Pze5TX5%%DA_Cj;@9xB?72H)uGpPb2!x14sPXhf*d8$t zZ2d1V+V-@XGY=%RoLIeekJX zGt8?ug;B-y)znf_H&|hyJS0%=PL8J!iS!|nk96Jk+DMamYR#xJ$i7hZz1`ftxdvlU zE8uM&vwd4_?Te7p!<%ZPoNlwiW}w+z*=!}7uWTY4*H|^HfN|Kx_%$%nw@Cuco>KFU ztp}*cMI}dS>uT|zC~5YfRs08jXJBmVTxHu^J1c^`_T7O5xgA?>|ekA_QYTWecdBE_?2)tS#~+XA&2<~>GD z_ORK*Mkv(nEs@$;+qds5-dX(e_PZgx^K^FXvn@w=wA7j_Ys^ry`P>%oTj9vaHrX%F z-a2%ss3g*YKB1i_w(Jgow0X+3<&_HP_e9s+~0p1bpUe8uPB*TGLWnW*)!I93HN%Ghg!@0H0rp z!8}t8tW2MuT!Z|h8>o=yCrgzMdv=r!CwD0MT+}!}xj9l?TN2?AL@+2TS44`7OG+Ze zk%-w^qoiWyH1Dk4Q*6Gt`2e&qD{NMWTUx3y?7ziG>*m8&vpHs4t(=bAEWgLRYST7z zF?sz9G|+EeCbZ*RtESfcN(-B3ZVj7XXa^!Mn&)f{*G7s;Yqy)9Yc*|>_<1;&q(!)U3cB!a0U41sw{*aI^Y++8xWnEF=+ zVxI`q3kBi7iu45@SV_P6w~dt0&phGcNbOZ-JN5ZFsG4rx16A{whei7SO*O*-JZ?0@ z4bz|s-uIj)+UdKkxDJ(zBP(_km6U+w^Md|O9_WhSd{)rE#S?~Rp@9`7dQcF3Su}8+ zNWUr@_?1zU*uY(ZF^O_wO69yU83Q?$Ua>v`t-ghTvUQC ztz=85iA$Ug zcUsN0S8lJZTQOs<`I`;R-n>Y0iTSa$+q_^?^UBLj-)^&;rqO)EI%;0AX?LXBJJ{Tx zTrpVNVuX$5 zSdzQZ+M~VnvXP15Z=1EF)fkk})Fml;X=$-=d4?DHeX;ptX!jvb z{(s#*!4LNY{@Kn!&wT>50UnAMn z5#+necr@}~E%AGD#0Aa2UDzM9QxRW-xGV4fV8!2a8w2ddw*cas4*ySX2E>*_5J}=P z++9U>G`frQ`117MFO82~z#g-$5L@FPyA|BKg1;+r>U=RerIAy#bj zMgsB8oB!GF%zu9$rpIQ=4|YtJ$94e!hx-Nbje-B2mH(}ISot5Y^g#U#ES$^Cv$2RO zEi8@H)?t-+snr~i?o#{;*O_77vRSNEV=J4ztu3`Ja5x7|kuOkjO*6dgW%xDb@<+HS z5$_i7Ft6CUyZ3N+JzL{}H^l<=51X4UvzQVV<3InmTyKC5r1kUXa7XtX+yA37hh$g=9hD#a4>|7tNt^LwGsvSkF-YdKvD{RDw zA8sLyi}ae>5;XKMmgb@_w~3{>g{DeoMP>r;i7nwBXSJ9cn^6^rZ2~XJOryttL#M~D zX0if-X3^)xk(qVKnNc$fygZKzx_RBYnz9&h!#cs`8_BG9Jt9`id?`7MwGqIpH-ODA zu-G;GhRt&gZ!QL?cNmdpZKMs`6s7oQu8jrrnax;tG-JzyQG(13dt{_kmV=#-g@#ju30JXZw{{Qa!WTn;W^i_GL0>ifG#t_N=U}YcZeG!r8+T24M$6Q}p>> zcc2f*fu?Zkz}?=hyF-Yu!{w+GiSKpDw#2Vmo0}b6D4xBQ^7s~O6py(b%QA1C64%#S z&2|P=Xlf@`P+}ZDHQXVOl+NG?ZF5WhE=z>A&5U@fs5h|<9PG91sROavNThleYW>w^ z{hT=KDv<5TAlLow>TWNF{a!?@-P_ExW)K;m#{78lf5_Z63ybgvw;ZS+4)IHcZT9SS z!{e*k%r~&1gB7ao%?18jTWTVZV{t18UA|TI?iDTE;>}|KnbHi6!Df$J@&?4?HKWvz z!sgm9T57*+DF(6cAfmW_ZQEKiViOG5Rp_lAo=;ZFj% z+KUAZc5o0;)|zQY%?-`9-hmNwR@fZVT(=!NQwEq+j9mmmf6}%=0AHOJ-m%v*+BqD! z9En}uVKmP&PiZzY!{(=_8H4o^*p(Os1&Gwvb06zj52yRB8@JWg-&0ESQdtuy4ojgn zGi)~R)^}4^+)2J?`}Vrxne{E8f4*S;sLow2Hyt+D)o{zgFh6j|{=Ar0s5PT!@5@xd zI8`XX_U)1Fq`7lT*zDS7rgI4E)esJ6KfcnXvD@a^YuJd6#fe>Q#eWzbyHCR8 z_Fe%g?Ac5Y0C;YY z$|~w97m|rVDoYZdpGsJcY+{g#{Dh~DfYg&ov>1CbiCp>g2MIYi?$aM+B&^f`{j+C5 zB=v*GKfsMY!A*D$g#1_}i?obnK_MQ=LK9^qi{jX0NMQVjk0DX3=W|Aqi9KgzX?zwZ zJZD5fJdy&D|-hQ#vi8YQU(PXp}?WEV%Zj?l$cRO0Fffd!H)Eu!%ie$gY zHs+cv7RhoKtEj4CldZ^#63ezGV`OZsfe|o5Wb7JP1Ea<2gMbw<#*TpqSOYN-0r3F- zU|Xu00^4z+w=bo46{rMm4A)onY_am}R zJ+X>OYW4p+^nc)q`uG2EHqJaC6UqJfU8a#}zdm{I>XBy-{Z;Yj|42ObKR;)__h$$0 zx&PNN(LRNrDD8}^vA|fkB zc|!hGC*D_rPt*v1^BHxAgCwecsS$R%BNJ~Z{wQIWJz^M{FeFhIMbmZj2<_)UjmX#8 z1ZRfh`Ld}$UoxcrqhvVI3*J+w7o#+#MsD|_mzTg!>bzl;@>~X^8DTCL%}y#N@;*7o z72y&Z2^E(Z`N8zQqFmy_93azt21(UD8V(nx`ON3K^@6JIrujT!Nb`C0Zko>(qcmSv zRo096Q3a{ouryy^nIjx%w@m6eTqpGvNxu-y7pZ>)fZap4ADH>wdvJu_d*9tt_kU&e zg}YHN4*f?2`~!#nw}Hg`zyA22$NrH|PW_+%{DI$_{>l?aK2PA=fdl`MV6cP5U+Mo& zYJ63RZLvobU0r~tLZif$0hNg>!ywT=4TwDgw{{(dVRCF#`sEFY{&6Z1YxXLN$9|3C z@hfHvJ6W#P)j9Bu{UPbmj|ecTF3Hjr2Wm8qUwNico$6tHYaSDt@;QQqtA}KjA2C4K zfl;OL#3SHc3?%)L15*4we}FVR`-xlrK>-j$^>-h8yerXoKJ zbdlmk&L95-&-&WIuO52gaCPn-&b@GfbI;Nc+kWn_4*8kC+~eF)uGL?g=6RWN{1Zp( z_4(tQpFdK)_XzE^;cJG^KFV+XZFBBBl)nG#2fudctA}6s*q_`qa{uj`!@g$tO}VX~ z=iDskj;pO-I9R>&EslTN$A|aiHe5#hi*uuGc$Dk)_YUW0X{+P{6TS>))H7b@*1{01uya8$SkqR@Em{pLm2sDz4GrivSqKSgOt!M|}oB z22ezFugA%s9(?i8*AIW~V_&`Lg`2-}q`KxM;-HTYuNmpLyV7&srUBmKo5nwJ=lCby zI`C%){?)-hJ@hXRzxc7Q-}JSczk1{aU^=RA*DY`Pd86&0+fe5}%a+H0zPnBj^!rxE zx9r~cv9Isc@3;9K<6!um`P$p>9KH59zqh%s-iP@)Kj7T*1HS*M z;zjm7ZZt;!)Ues9ZkpY`#t8MkMB)WbnjiiA9S$ZF8Tf+a87j4 z^Ec0%L{oAb;LI*w$lq9_qxl$t9i75gy}-WbY2ph< z)45we6ZCK|8m#B*{_k>)uGgmDZ}R)c?7!PRFa1GWpX=}jzhm5uj{EwY(euX%I+fh@ zwx2&jccwnUMAGwgjTSH1@HMx%8XC%0=}Lm~3EYPFcUF)39~x#+mYbh>s94-wZVk#t zm#E_HLD3?jxm~mt2SCB0q@KmJh1Ibn41BS8eEQ_kV@Dsl=hOE*z;*qlQbJL2ZoQQH zRw5h^ie^WVxywa=Z4v8Kd2StHx+F@r)3tr0FJm1s?;Ky;91xk@-&}8�SS+JW2p} z3NtQyi=_;E&4NY11Q{3dM!8I?L($)A4HQXVuJpP(!*x^_WwuZ42P8|xhi-Nx+BcVv z>SKHD)_U34>=n~<CI;sX~Z%40Lrk4-*)a&BV0$R|PM<7S0QtgiVHeFj5FgH&Us zTwGr66}@J=x!7+apz`=7?a>B<#onM?as%~SON@}!qSGtaTdTcA$J`GsRC<9bx7pD+ zVoaM=j#5lON*tO^hNzuUQIYWLrUo(NaMT-t5q5XOOpzFUm?e2mVwr7blb&Q zwE^KI#8Wpgg)KHPBd;}kbVj+nz8HGswa2SuZ7ue29ei+=fZqr1Tehn!ok zww51!pd1uu)wLcDW5*UIPfe6#(=*e<2zKh**I?(9G!_QbR-;z~nKYb1tHEGdF1C8D z0pp^#RASISua^L-NVt0GPqYq}Z(MHmFs`;F^B0V8^=8ENm)%V!0cwVtV!*^|b$RM} z4fJx`X5*r>+UssopS7lXuvl!K#_VhXJ=Hkgy;(sGL#N)Wwfv-+43 zy51V_;Py({+-~xS4~+0c5-^`4nK-8m!itisdffyWXWywieGeH#eXyWxw?dpS;M;t$ul~rGeCx!MkihHkPAKsdKQ8 z@DaVuhHAN9@*UlnR^$)GkUz`gRyFMz^aHXQ+M+H>U7)Y~VO2GqVj7*En_QT9lu2JM zOq`gdK|GGz`Ysy0T|!&<@(vWQ-)^$dpL)1G&;-=HE5|427M}9#OT@@SwBKDJ{bNuJ zdgt>L5-#VtmHxV?q$f+tTPQj-#tO4^>HMJCPxjeT)T^~bq7H-jT-k1>$vZp2gg-Sl zH)*ou?pf}xFSa_a7mWu3eze7-Q!{+i{LEtulXFk*J?5a!OQL1uU2Vmf>67s#qE(94 zi0Fv)p4AvjR88YOSqO6vnCQmnhbb_x&KCX6{sv=8-%@U95U+Gmk=rC`l%5NW0;nb= zgz>zJiKgsz;S*152+-(I&SeukkLS31vm=57|5z-R6IoLSMrSQ8$0x5b?u-7S=92hG zuPDu@di}nfF=caQh146p+4F_VpeQRF&Fuz_*Jv-o3q0G=XuG{-ZioM^v{tznlG0}i z7fM>`b~-$TS*`> z>yq@Q53h0AVtn>QIrG?Ke7{&%!5A%jJzfCOIY&leA8u!k;+_n;L7$5CZuRN3EsVnq z)FylsveeL*Jk9aJlDSYa~dncINhxM%1o9fKaK!TViU0o1KCI9v4A zA%{3Y{mpzk{nryKc15DgOU<nS#40r*Ei9xq_17s?N+h*v z-7zR1Nky9RGRQE<7q@5@b2|^l6=as}0gvzV*zJNEuBM?$AF1JZ?uv=%Mo+^&6KFjx zhN(Jpt;?WI<4T{=YWT_m0u8G!mzpHFkzr)o&7>`%14@BJR^Yxx$aI4m^-9vLispuS zf<}?1kcZATlv@o2H8F=aEgKm`wLy3K#Ms;u<%!AZWb-ML?FcESxza?KlJUzdjX~CF zulp;49ENa`zB)KC^Wa=2Bej?Gln94BN8^eyE-_@)a-s|-3$%BqJ7}$(=Ve>Xp2%*e ziw(EPV$|ja)zJ*@oNM&AiXf5$C>|N5dWzCn-Rzp2!NoA7JDw8m-hvP@kL-GjCR*wu zCBU-bA04shG(|$ZfqEsX%t#=U(G;ij1Veo7ZnmM6!Lc?wn|*}M)eT6)`E^yLBVs=y zzi^)QS6t&VdUW~eQu90!Aed8nOrzK67v1hUwfIuu@x93xLxWqUBg`sfSvmcJe4cG} z8%wZS4MN)8vg9_5T`Y9EoSB}QoSrCx0Zh)!&P*ZJCO)8NCWay2itKAyqhCBtyGzzz zTkNdDkddG|eWsg)CXI*YI`buXYkQGF;YlPCAv&*GG#H~eUYp2pLFl;1^@0Ac(|^(i zMB0_9EP=j~evt@UT~E1{Ru3w&t}hNs6w>u_*@w^}Q<-)%t_$V0GN5WC+f&Zzq;*!T z@wp^vYPq?s4_j_SKRg=y;zg1=cqVUSD0K7@%c5QMP?k4N%#5Fe$7hk5sq%OT5B{<~ zN=k1~L`G*H$&-Q7X*AoTRC`;kC>kcxxEYd~C}p|Qp+VC0mik3K8&F)cKvH9&3yf|# zfa{-x02xC&a|PRY?OS)Qt>~95)JS?3L~7$vLM7o` zG1v}KDycFI?S9!IpS6-)Ryurwza*$qqB#9tBkMvMpiWWMg;>pb>G?iH3DKwpva!1c z;#h2#y-*)eV=P+Y@HYX;bFx^PKi_GrW$psa=#>(3V@QiK)1Z=z;u~9?G|H_6(Jz@i znRC~vOTX-IF1e>yBn(?A)x=DGs;sF7LDYNF)Jt@@(eCnWPrFQ^v(SdNZ_PnXxweQx z+lD02g+pcQ7$l%yEIkGRm4rRNxfDkvP>EwRG5gVpA;F4&mLZfd9oM^&F+NoB861z! zoSZ&3!JSk~ZNAoRBY_2vXAq%D((zW{sMY$qKqxL50RO_#@JPg=u+3&ng0{t*?D zO@M~B%c^AFL2b-k;v3A+nIE!?sNw0H^}%w1XtohVN%B_=AF<7$v}TEj&m3r!g`SCN@YY-E6dNG9+j%v2@mT+U_7z|Se2F4Ej3n5PE^Hp#3pp4H0Y=b z%!9se2>9gw2Os`4dNx`pa!#jNtUxrSqA?)_3=!v3PDZ3xV_ja&=0;ZaTrlro^2uBn63O%owmj^W$FZw0`hzyXsLqLW zXDbf%TWcY=4!9M8N7Hw)!LSlL$JqO@?F*(yn9l&eC=tPnr4x(Wvy#U{``SxUVlY`a zjrSms!gfuT&oZin{J@k9W~Qc23bEyY12*Gx|ZsqQf?jCt69jrehnW7?X$+O|S@k z54qD?P79u9r8LWN(*A5w?r+NM5=PX`j&u(MLBusCo8+ezeptX*nrm_r6#_j_98xD+ znG?$fp!Zc&gKsRB#w}q~TpDgWIi0MTHXTE6M5_?EY;x{&U3p$`4q28jMqQP@)lV{- zrA5pCGQ1AeBn@BGDMWy5EV2n48&!;7$yAG2}0-3Bhu0Sy*5E5-li;9yDo$qUd!=(XV<# zc9F^HQ)5%GV%qD3Y-#EPT3!Z!`UBYqZZM)k>ielieiK8Yxw43@(B6~2bo$i4F|bi; z8jzdd-C68wKF#M#5AvXv0EoQEILgkA0fw}-XhzKttZ{a8h%{oGFn18KP*or>NN0_8 zv>?7$YI2qV6PKr_dPXw|(wM|P#;KW4t%utTfekQQM2n+QC2FDX#E{&RgA7e&Vg6Pt zn~Y)efbv+`=i|iyOp7oi$wxGzaZO=x&%v>3dXY!CEjqvTgET2I%Y^wyT)>Qj?~9$| za|@FvCg#vOAeeIt$q*khpLGYx@HWsSHd;)ySFrofpT`#!2BAykHLA--vT*tc7y zC3gYCFLMouo9#wruYZoFf4Y8mwq^x??83FeA+SrFOoDn6E;5-2L&h3&UvphkDqLfx zys&C!r2Kll^Feeyv1wKuZst-O%T1Cnr6gdmtaJq5yw03ihj0xrGGOA6i>+T^Ixdfo zO^;8(VLGyXVcHF?qcUb8>0^l!jn*qM)Z-sS-;y207Ll-UKp@S&vvAflMHkBwrx(G@ zbOJSUQIlx9GRw zeXwmM72!l8N*1&t&aYznAtHvu6z0q~$?Nh=+tNfS;mC%z^%feDhcll9UxYP@cdsPB zi#y6}aXTBwB?usKsvV?mz%~Q z_fRE0Yh~c115F%liqQ84b+AWQ_E{UV(yPT;G+3aIwD({Q31Kh&&E62wCLV&W?R^Oh zH=9f}mYDRNUY4?@(kzq7iiD}*WMauI5GQA1XaK-1Y-LJ}4!I0VE(#064CBb1VvSRD zEXXw~LrZ>48L~jtD<75ZvZl<}UCQZOP4anLk*2;xAl1Qh9M#^`Hzn}|@AjG6L&Z-q zC}~*Y@Br)#Gv*fF%pB?;!l7Lc^9=I)tQ`>g$4JD?P&JTK7qZ+Go~9&;gs~tf?P)wM zg{)mMPJ^(AtYtaZ{;uPbj~_4WQtLe(;xRNQ+qW>6wpL|{MD8B9q?3%_$a2A-H1agt zLaPnANp6HtfZ(?nP!NjPFYvzQQFP|-aoUFFDW&Gs;4;g}5d z!XlgW;ZinBG_cK<_2sn|f|>k1qJA`;*@Yc5_{)aI*W~gTb`EWg17&kbdV6~jFNY*R z>A*{mNoc4v)x_yEQP$6wPm5Pb^pZ$`PFXVwq6#3dNHEd}&62xmLyY6laGMb24b15c zQzM3Tf^nNYWG5bJago2MgGtgNIom5n-k*I-))#a<7s<2U6GBM3j|< z25NP-#c()}7b_eVeJo&1$Ib0?Ft&0o8^dV0xq}W!w zq%f)V=s^^Zr{Mum^;EZ*z7kFVj$1Bli%in64NJoz5yE<7(1RU>0J^a%YAy{)5g3T* z;Yuk`>@-WmoNHc%Vl2}*?}n5yO)%bD6V%h~sTvA_iPU(&#?)0`isiu-O@zh7lRLw9 zE_u+hWi`zHro*^VwxBD^V)zZ5sPg@!PiFwRZJc&zb9Oj}Z3ORaxqgWCVN(gEPHH6V z6Kx$y5*wwiq0A8q5vT-n-CRdUOD|&_V97a0m{S_>sbTBfVnsrN;+e!~BqhRA+@mlC z(dRtn;i*_09^yMn;vW{}s-r1Kq}a!2Q>+|YDR*BGUV{rUxpeEwlNuf!01+A; znR#Z{vk8lhu!$~1zVR!_Y$el56~sf>Rbr=G{bF9Gk4hHVT2Q3NRI{@x79SRlp6oIG2WFo9rg?f z>$~bYLgu2^F-Vv^Vn#$1I~%q{yN{G?90r_9aDk*j-_Pm>zKdFZu+l5i5sYQq3A+nO%L+p}%C*W74Buk6E5eWf;c zbE*L`V}B=_H@@3-m8KKv5*++9sY+x_fYRG}N!T67;o?KSqWX4c>~pVdUu} zBj#DnERr=w+$Y34W)#rETo2zxb70a{!oHXVj|;zPsZ3d9Pg(m$Bb?wb$?Xrz^c`xwR6sfADi_kw8i;FcW_o&pFg3`H?Lz5}WU$8g zaMs*BXcoN4Q{!?Mg7FA|fR_Dqf_MO13OK&D0Rv1^uC zMhH2=YMW#yY~QeLC?XV%Aw{6BqTEc5!Y+_Nd2OO}FNWn?(H+>W($~YRlTs^H5-D^A zrzWv+5(wcB2!u;Wz{eZ`wV6XQH4ciUk%OmfTa}X(*I#G#0mydReQ>z@5WZZj^*D$< z;~)W?a}V-e*-GYdRFap36av*(FRo*V;Bk<16cM7X%E_4`EIL&@1Fc}MQ;41sBSQE{ zHoMZj>g7PN=9vV-M(R`M#|kOS^b{U1kJ`qnTg^fZW1y@g4_S~+J+Y&kjAgGiV~M$9 zqtwPKTwPWfxq7UOTj0UP#Wb(R8J>`28<%PqVk`XKq8Vlx0=FRL%o*t|xWUvGgcd;6 zva`u7Jp4mYzGQGm$u(t39K+YtMEQs?Lv~LyU$@(LhCJd>qG=TSg)Fw~0WOeuU$zu~{tgP#KU0V%%nuYRsXiM*w7Y zGKOc7*@yHKQGTIpVl4=(j3s1q8uM6*^2{7Nrh7d6SaiWgdOU4rc( zpEwXQS^Xpa>FhIR3&qA7%82GZ?F8*ahS=<6C0iuReix|`2$yQsqGOc>Hsweo)8srG zG?2vkhvHinHmcx4i7RsVwK{ZP%Q~RVa|&6>9s;q!YS7WuG0=Fnm2{K(CC)_O}){6g@@HoK;nEtRe5~!;-QZVk-1UT+h}@e2n4GAZ~}Rulhma6t(0_2+7E! zxUSW@LJ_}Fr2}(^dcM`iylvx|ID&pa+`6UOwBkVo>gp8K_uejz!{&gV8UOfUzGhQ4h3_uXX_48pF z;RH?yMO0LN+B|ZH0inU>5}jnuVZK3cvp_D3jNQS`J8%=oW8~N#CWF9I9`bj13gK!@ zQJ1h_m=Cronh?T`b9x!kjgc;s)hlb&CeXx=2UX~?2t!$r& zhTKElzzVv_oHh$I879&f2g|m6fk{t9G7&L#CXh0ERyU<9rBAmuqQKtB{|Gr>_Ge;0 zv%t$_YcPoA>$24Xw@&z#q{YiiEq{syb!!R30DoqY{6AYgj5yRw2_FnVY3T?z+3kom zm=--pYm^}ni6*y$RUk3uo|1t(vqEJAH-@W!gV{Rql+f3QeZo?YS#V!?_^ zZh735G%Av(Jfw;EN#77xcZ@z!>k+1pw^Xc)V5Kmo?~(D6q7Sh~!~XTw^sN=4Pgxk6 zfAnSqP$W6aa!q56C^4I>;Rqg&8ZXJAv8y()a!3b7l$%JD z1r=Xl+oGQ=dpLHFkib17)rjH3PgXD)SS;RH!-2L8XOf<%X_**-LKjdm;qJuSZ9&_b zikXB2gx*x+7^!#F3UH&!zZ8##h0?jk%ys6JxzjM8?Buj!>&6ub<4hLE?4%%OTcrv1 zMoA-p5z_)%z-CB&GzD{WWl^&*g@}1K0%n_?THMj(d^s^UMUv{h>`uuz=Uk`U_|{BSO8UhJqtnXkCZk_^At zTh)XK+d82(8>>CY(+NUoDlZAWhLpZ5>pBKy}9_-9odlBLMvWjrExWl7k^JFfDPdE$gdbD}8KBAA=k}NnPObC|SQA3d; z27o7(+Gnx7g7o(En!~V>31pB^A0?y8hIQ1$dP1=b8Cjyza4^PDM4r+LL?$O;GxN;o zI6zG{zZeVl?qt!4%w#zlsM5f(_GOadR z(llk@3=>QHEYZbWmj+y#bkpVR%>4YMvOuvacdQ`8`C}eK&ZR#j{lMCQJSmRvPClSf zhh}neI?cn0s*W4Otp_V~o8OfuLu$7K&d)l#ocqgS=9VthL^fKSxP&gJoNK0oX_{tXGofhH~(+-W+ybhihfzX;WVF3=nJVZJkH$rHb50Qb} zYU2l`^OPm0t3*(1h8;*|%r(YPxO|yR(eI1B-XfkZQ+PE*^2!bKWAfN?G6>C^6PrS_ zlo_KDP7QT$IO;Gfp&7$}7y*91>(-IpK(0i%Zz4d&{T;j@r8KKBl)?C|VSSL<)8RySM8dta?MFD~iKsn?K z9oWsxFj5PXJ*1rX4Ml_^?aDf{Vo3xp=aiC@)AghhS8`}YjO1T&u|x@!%<53kBy{m; zGHe(Di96RcqU4z~nH~D%qccewg@nLwlCT-`4v7GTux1{ZojE0aUVhTM-n}qg^McF?xNDcFilqE53bd~%*Ccj zXP8J)JZounxrfV-zG*L>m%Oyn51BNL#Lf!#7EFaXc4WcEp3s0-pl&gR42==}0oh0H z2s%HUyHy0ZLPJtd(xUnrtGqc#RT*K*l8vKwVZrLmw%YA}vxxyQhXv80b?^%j%ghY5 z59K2VMlxgSS!N^(45KEJmZb&5Dq!`2;IU*!u(SZag9JIptcna0KBWonuPYTrowCsD zEMrNdLz$JtC0gdPMS#}S2$N_m`(GL=8m*|GxEVaI6-;F!i0-Y9OQwb}>LOZnNC|fp z#q(vLhv~yd^+pIDbS8~3q@t7#P#+u7CrP>v_n@e7YZcF7~9+Q?P2sqrDfxMih>`czCdLNy@yh!*EW3%CPU>u^$7HH~~3iHz&#h=>!T zbv$yg($K1Ss_1BBhtBJDnu*j}t5oXLV{;P|Nf_Z*9R!2gM9g6w#-e6XQz;l?H91>SCNdA`kRx_U8(3TTyP9iRsckMEDka`G&$i>X&{Cd(UVcuNG7A$Jv3W{nK>LzjTB&w{SUIjv`C)b znyIizp-_&hRrbiEpZHyer#lNNXmDjth9~Q9OLj83Pg=+7UQ-iFOs6t`c6z5t2Y`WlC3<5m;~$sHOjDO^nem;z@I zkpOtWZX;~h^4dud%@HAFZE1=r93r7h;Mv5B3w7kh;sIWjlWA|kT0_)e4wAfy;h!7XXN)D(B#YSQF zo~KJg7Z)E@!S~QpncN8;f#Ck-U>pi(BaK=)$;pc1-hlc#uy0Mh5;P=vFz5;ymTOHi ze{yzWuD}Tvi6)p0adj$zsW#SZaSFGw2J$*#1Xux?=EyyEm%?XYBoTrT4&AmM6T!>p z7~bxu+^1D^pF>Ts2uuX(GF%k0M&ex1D!F9V#~dkQdYW|2u9m0yw$}Bu<1E}Uwe=AW5 z`)Okz1h*ysbh$BT7aq?%6rg1#oCV+=Kl z4U>5afynJ{U8w;zQWhtwoeYn`1Y~Clk9H_+6&iF%mhM)4ZQaXesu>Jaf%QzZaw#eg z&(Z_UfRh9YtG)j-Sun=cfrqFbZ!Gglgpfdn5o<%twsBf=(a`>mGbqCgI)scC5AgvS z!I&1D6!W29o)3qw0-hwq32`Vz2-?wV?N$ugtZNBKq&y9SN(l<7Bv=_lxmbvqv3x+PXQ^rm`l1){v4N_1+=> zrh`(XV4_jh2Qau*3PHeet)GPy6~;agAv%laL0X98;Zq#FX-3#F&DuOesML_sXT@np z6>R$4=@AU8Z43y#aj4BG)JZHXrG}>HWLX-BENXU0oTLRX#3`82{oDhrqq*+tRDCJ( z%ov6sNyV436dg?eavf_{>}09|D!{%;gwEjB$qSk^t0f5{Qaa^`lxfF4OlA@Tfzb99 ze7LHjq9g1nsaq5=+&dL1>zYJwk+)&aCc_NI3!66Gn6^a4d@_WEgyF!F5-7ol<9NA` z3q85|WF}}gp%##RX&DwjjC2~+sp*J;Im0(Xz=>huJCKdV>dXvyg9Rl~XNFnuRI&lp zc47TZG7Dldyd$BzW&>miTnS=95aJ+%FyC5y3bMG|BAW8@9fh`>f{+|mV`;;qG-A&b zoj5m)PK?k9D33)LOi5J;k7+P<9!7e|!eEdNK9tcND|$q;S8PD`B&D1iQ^Yt!a8W`y z<*#@2u}Qs6IfL%1qB4m@aUcp5!DEie6y1eYBSJgqip1&-_9SD@Ht9vM3JJnwZ6Upx z0!Ee*+#sycscLkUh(rjs5e+PHIwwP>UQnFwM9LY!^&~5@OyXfjhKXY&+C*YWMwsle z3my{ng&a}MVSBXccuWMzysV&waK9uOD+e;kP3G(<8HC+`14Uh8WvWx?Be0V_Av zf(F{;V+v}{DC)c`I>bC$;(~<0 zSYjX>VGT)xH0)%dg~SPBL_8-fGRfl`1KW~=t&2ph2P1;d*eGm!x3n;n-1Fem#o~O$ z(>C8I#aaUs>e(=Vl4ouMK{T9Z$lSUg1wgoTO+)SwDVX-iK4BD?&1>0z-82R_52TmtrcO)QV_ z8Gq%62oXN5%!js^VStBD!#&{NgZQT)uWXpLsGpb=Y=pTS(G6D*=G}ZBf|;o0PIV_dj)An#$&2|_ih)<_nx0HK&Vna=k>bq^XGhE>rr zbI`E+zYEIyNa*l;K)xf6MRu`mdnqylBZwpYW%y2z@1q#+5q~lqN7o~|J8UGl05B*{ zih(I8auBAKI~8e$NCQa~OOY4O{S8AVPN}O4?q1o1^5{n?Cj$*NE88xw9mac(9IQ1I ztiz7Ml)ZsYbs_k7`4h!oBF^yQVBax;?t$^{=p{Te?*Zr@^yUfxw^s(2F#pQ0V|(CU z5boIWc44(kSwvieg`-?6Dov7Erbd^A!(IhVL=sohp)*O@X(_kLEFUUI=7&)SG8 z2i&E=vhN6%(LBC5l=cX+tRUG{qky_YLPZ2H$_fJnzqU08;mlo8G z@Ew?EWea*XsebU->x_l#3~c>!pwwk)_sqySV%Vy~yhVhMjT(x`!l-p|@acP6sPi=4 zEn8eUv~>dt+DctzlREGMvnY0`Dt1vyj>7e%pyxo6%RpPd0I2#N(oVR&L(!J+Ic&i; zIa=Ym5axPP(yuAhx}rI$X>z4pOKA0xxX~Q$KXlN3z^LlkKj;upM*&`0*z_7sx-F|I z_V$tx(ql+_ChviW?#!&3+qsr_F@0sA(IfaTl9C)obwdNAJLC>kfPkwJJoHS-l-H!- zDaCZ5D_j~N`p8-=TLM2zK}%`5i0I09!AjrT{cuAdsE;DQT|dC-3SW>dPp-p&L#g4W z=lL)1l;Xldi+7j|Fdzvo{k`q`;j2?bw!v$WAChWaMWM-|alM17=P97ZAWuN?w3mXf z?(m#F_+-sHJH$XqQRt}7mk6{T{uEkRP7s{pil4Z6Aa%LdkQ1;yhbb})0yi3*dJd_v z=MJ}-@Y7R76XJ)LQmA31XOF&?)KR0k0a8kQge71`Oevd6BUZjJp2ZIiCLP66p`{L^ z5cq*y2Vn2G#{(HXqvlmu=;7H7OUHwsCL2T%Ps3QODyrcsL8IpmNzqa7hLrxU#ALS^ zZ58qY!0P5Uijuri2GQkbGbn$fvXKK6z>A8Ag#Bxm&`bmDa3Zc9fl5Rn* zg5S7qK+0=8VjW;rf>JQ~23@aWIZ{}*!bt+l=Stw0`^9@gmMb0t16_UH?|l^Wrq}$g zGG@F^&b37`kF1&N0>B*eqT_uoAHUqOSGz#W-;*D}07Gp6o~AZ)WCe`KS?Tpy(cc5{ z{2HO0?+t2RLwvSp)K=pPQgj5&e9#R_kn-#ac))5w(63^UC@%}td`}GXtAJLHuSw}! z(5?`n=@b*_DxN_7m!#{AEof9b%Uf3-n>@yirMct;3Ow@KB2FI|4tYdYR$*XOWQ${) zYLeTIG~|^1tB5Z7AnbaT7o29z7y`H_h`6-rQ$9sG3%HCx`r0V8gYiR;JN}UX8kb%V zRcK=Ng?$s|MW)V`Kp(GSB}2DJ&Ot@0Kllem{>qw`oKdJL!KH>_L01%t9Dh<0&M{|@ z(0r-*m z>|hmPtD%_)7JMJFJeg-49lhsN$;LOQ;9M?<`Ne~m3u;mMi~?k^87XoD5j8IzwESJ+ z%HJF%;QP~_7c&@YYIgkfV*u_DKIYO`9?VJm4+x+ zMfQdz2T+Z)52D?!GB`P=;cE;+ZX`d#pRPUJ_`9NuS0RcK6?Q#fi8CgzEnK+p`GjAc z4ZAtQX)LWjQbYX-0GjI@Alw=20k%l&=oNtmPj*#VAFxn_36@Yu;3AZgoN&Oahz&ez zWI$dl{x{m3u>7td@^_VBq})%1uT~kP&du2i0vv*1fTYX7`u@nEd1Lt=Ny6TfTMs!4 zditnw{^HQSVc_{Gm33K@tnvJuganWFIKQy!sb!1;YHzs`$?l6yp*kZXrK}6s$5US zuiGKty#P|UJOcK8T+fi;wE>VD+tPcYjP=aW3PcCv6j9I&;wy|AKAL1tV=oQSryT*2 zKvbMgWsBgIL<=_nST<}LWT1E-kl_g$%_FB=GEDf;tdh}W9ZB_mF~j%hK?kNX+~Gem zD*@yd(Gc0Oo{`Hg8Ap82NjgF}t_0F}f_MeQz3@_cV%&fg!(Q9S&)v4hAO{G=;T6h8n%p4p`6}wX*lJ=e!B+fndOu;Qr{JaT(V=bZCx?cae)=2+@GroDjqRviqI!{_gce?r_7|Q z2P1yzK;fZl8iC9PFMgBX7GpwrTo(rnK1`=S7R&GK1r#o8TNCT3z@H}^xaoCs?gt4OUP~p7z8T_y0|yCIU52PzcIIiq0IwACM6(>(sWfr>V3ce|ewCN2 zHB@2-2ZyKD7N$hJ_PDL^z~4Xqx0v=W$5v+Adr@uX>V*Nr`N~m1@C&g5g2@tup$#n8 z15)@X_O?STGlpAV!1*J1;b=KS_cKe+IeddPjxPl<+(=3_*zi5tifF}*3wi-iaU8dG z0P*OtON0zh8lAI5Y!x-Q*`)!6J27a8q*k*aULD+U>YP%4?XzaRc^u`ChI#T7b6!<>H~Z4F(pAdS5mKcgXZwPsri0lt6xy zR?0el)7Juo`${2h*Fm)R(2w@;WhX<^MM7=oPz8)f8G`FNL*HJ0nk-;4J=d`{)zP=> zHP4t>R~T3O(h#*XSxANhC8lGRV9kS2ViinqSt#3KKW3>!ISCxMU|iAwa-rXL!)>Do zDaDhN+kM>aDp&I&aJNJ2&w~k>R}lk(< zvcb160dqSo49J?-EIiG~yj;-jD!nRDwr!JDuGz|^qipYh*Jiy8FQItVVYX9Foq#kt z1J-A~ia^>%r%=?O-J; zTrs@tj|xck9=O7kiHYBS(VnO%N3X;WOA zmNVT1=QN@Q@jV3-$2;6wl}8Zd)mR1{Zclh}gt*|*y#grN^7lAw2c}LVlsGhtQ{0F$k!{jbWIVfR*K8nSnn5adLK+W zp~ie>wv&7Rt9Akk~guq8O3qw5|mankCBq5n8Rt=}XA|sp7mVv;*++=vMfVY<K`cnf{Bf`DYAWMb+P@6=)q@4rP zmqDe45x24k{G}aPeJxv;))h4A#ktx5I44=RQZ9xU(p+iv_y&<=0xF=qL`sHgI-3`#Pl_wwVq2wa0WifW_b<>EF@8q%}nD;@KZ*F%E#!n8V8mz^_^dB1dWCt5%-j7pziB;@_JBFV%R$f1i?b#re#zHaR zNWTb^i^YoB3G^bb)b1tTSxC?V7Wl;5c4)D}n7kK)QL9|-NM0K0`>@C<^aI0lv3|aM zdS`;9rb-P&6zLVdyV53BNzofpH@cxB#A?x{WIox@)wYeYAwCDjcbSj~mV*@r1`!O_ z{JzBtihVfbE-R1%wkor*);-^jref9;lf%-OHf6FRyc*WZnwq`GD&EE3aL6@!rAaV? za16m=6-O^>EWeB*O5H(4cV&fs#gnt#+}2wK1!u+3se^i?js8OkC#a}lJBygC0(MF` z%cf_F2ukK-uW~NmLyk`e9Ywf^c#sCImGkKvYv8i)1#x`Ep^c%ojkQ)=KCKd8?BaS0 z3;l9&VrKj#e#!X-EHLHcGn3Pg7q#41ue*-HUeQy*23Y^D*WErJaW`7vy=a|aEgWRR z!DbI#I)!3DgP19(0@o3|@jk9Gju*TrcExy{_b_%KM(kQCHsJztauC8FJpKnbT?EgnqHgltyx4(dKe(6AVSxa2y=n?5IVW z%SYv31%ohXS^s>eA%$90r6MR81NzD`tuUxZ*Pbp??wgkw0+EF2BU*!MNC)9?=5gT? zD!oWpr`cQvuNRjuS8OewZSvvF!Q{k-mzg~+p`dTImItg_oH7eUh>7eVCAO%*ixo?^ z4^(XbIqjm3+lL|UcD$|#I3r}o7shx2!qtMK}9SkfngFbo)sZ-qA_A7t~0 zYC)7TGyAM;9sBsgm<{?gDW(_EpajpEBpRE3_CgQFS`+G-Bx6ffmw*)<>!D$F>JHYB z1In|lcDqo&=$SHVDcNV+6iuc>`VngCq}|Je29~LRdhFQ3;FEIT8UsVR$2f05iNq%8+E&?G0OX0YmR zD|eb>T7bT%At2@p%j=ylt_nmj`VMorw~zjtc&kwm`XzCGuxN=aWteuJ<^UEksM``4 zPQ#2}tnA&*9_#5zYh+$9LDYH0KKifX-14H&B%rJV0sv4IIykf=RI6xNTJWQc{u>r} ziHk*Ru|!lQMiCh_JOEY5D}+E6^{pO?HekfK=FHj48wd1PE)axhO_Toh0sSi<&-}^x z*@@|KDbM0^n;k3}8w8apUQO;a0lu@EHhR+r3(%M)hjy$rCIgwMjeSBBe{%y_3c#=> z3>BvT$pqC{Yh$=z^-%@bDKp9%RI*G3V-wJov z2~=jyzSg!cjhbXm#>K6QSSe9jMW_i8>gV8CGjuG~;g>S`vYpIMG@~5sg#W!%INuKx zzt=unV-{Tz5Z?C$)s;5+K9F?f{QJ;B=qAM&a^K|R3<`5$sNA!*GKP9$vxIXBCZ`uB z<{le6HsJs)A%2=`m`z98nWg|3Iv*@VZV-j!zqv8cajyah?g+%KBM1@-YrAP{h?3Lf z{u+W8e}pk>p$mGlvm-$%|A(SEc(`;AK3``7JqGWa_q)Z>14wI;k z!fP8{Aa5dFCc9uEvw`H@Kz{+2?wcf0g+Z)a;zcql``8(4*r6e4OU7<@S&Ic( zwnB_u?y;UDR*&}LdBxtX^i!Z)nCLqz00fjaXzH3UwHN!au_+Ak284~hMu@TRA1qc* zt+|Pb#GS>f!-(ndcLx6`_Uk^xD^`921!@qlA6gJsaw98GXs0m#MVM5zDm+TKLKm(J zgx0+(*`PHyKV6u;;vXZ?! zyqt@;gX7Zs@PQIAwMMYM96q%G4p@=>+BL}1VH`shk1W?|slZ#LN?9muC&ze^#NKlX znmX6)8MOkj`2E1CUOm86@v#tIiTvv>Z<5Y%!vLmAj3?Z{jtD!Um9%fsK)(LUpJP(E z){wc0kYb{qS+sEIl|MQC#PrPRX)6^&_j=8-9+}z7G_{lysT}VUEtNp`P0$ZOBqhQq zdCSi_nyE;BHJieUvo?!`>48Y3)^=0|sl|awYc`B|sAB60!(CpsHznO5GOfzoSNr1m zld}_Zg@XQ&!H8~BdoU%E_!jT4Wv)lO=s=k+So^LTeyT0*Wv98Nd45(?5>?G;eo35@ zs<%F7OJyYCgsSSi(u4#-0xKrT@EI~VmNy&n3KBCaJ2q+cJoCc^pXv;$kU=G?DwL+p zu!0~}MlC$vW8V+vN9v#pl@u#K5w}TBe=rk>sgAq&V7X1yP zmV{D+-xfPdw7yc^>t1Xxz9lm-x(rdK4fzUVxG21c2bzZ^jg2h0`#)nJ4vLekn)n^W zQ4tbAPHr!@pn!(e6!9DyK~GLUIvMT?0{hVUvH1kUWirA`8fTkCy5b-@ztP%8HlP_Ru0;+nl@=re^Uqf)D;!|h_S1T!*3jVT3oa?ExSW$$!lThh^IyvuUb4~st{~Q95XO>Ow^n(YImA)AOakP@RVfO zghcQj%>>LX__(Pofh*z%!OQs}!PjY4tv1G+MFJ}K5l!XKW+vNSY0GZ!oRo^_p9<82 zY&6n;!`XS+$fmYPU2{BBGL+A?`Yp+G`n~~JK8ho$MUW`o+F~_UJ5w6)FcoeaqM(O! z9nAD%U`nygZ;eDBX{4`s4!k!=>2frFUS{va*qNebf3vd(0g#J{MM}^H(&M(KBk}r4 zOo3h040bsyDpCXFa?m6Y3a1`ZW2zUzD&5TiA{4xKTv~M!qd!m-(+>!;wAK=dM)>(_Q{jJ3f8Q-_dfZ<~0*ZZ{m z>;3xofc`z`DH{@0OL2pS1n9KRHTqlWex?JF=WR$PBOcI62T|#x($|D)CW=c0g=O5q zVymr(JEMp1Qy9nW+{EnIoT50;MNgj?n|s2%KugQd9Xna2(UIMbh)|_lF_1<2^=h7@ zA&Ghj6jl{#Z&`1&X%um-JUF`>J|Ohc4-rPGGXUy_QgK zOsU93_nXOHGt^QvhXjd14IFcW0t~b7grpfjC<=V;x0HiP*r3>b-{aT9DddusABM6i zk72S(qimvwI6xGB@lix6l`Scw$`}UZxf@#3sh7ft-{T9d9i18+jLKXno=17@vXmhU*bdqB=tyHdTuyQRVKN)juHdw(t zrR8FX^K@C7dA>Uz8ZP1!RIFb2fkwpqgC#z5I0v-JtC=vYNqI**|p*@@2xY5%IhmfAD-5dV>DBTE1rFlN> zqmr(!0b)Z`Sx1Juyb?VT*sw=tJ{-@wP0a6puTgpBu}0u8lWmp!YrGZ;PJ;wsk8gE> zQeg>b`&qFiL-C>RW%HS^Ze)_QUG`*$5bF(lgqD<)ouI=~q7Hssn#az&HWra-c1suq zB0MQ|tAdTStxiVX5(>C3Pb}X+-6Mgvav|H*fkP!s63$e`$YMg5+{!`h!e(t8-b^5K z9#n0)UE(3m;Yh;ChlOPr@Nmq)4b{pXRs4fQ3Os*u4H0vvK)VkXxiqlM>GH7gh1X2% zhDg4)7(s#8tz6q8X%QQ|ljmRvE0~qAlFM%?8xw(FKu^ds2V39RjJ3cc!)~}5fP5|C zph>-s(==cXuul;Z3A@0zrNw5}u=9tkpw@~A#JWCtL!*@LoD2r%X3R=}b;d6a`vLw6 zq}`BPZOgJ;Wj}`)v&X94BFvgW4#p`EjJ*K)`XYgtAcuNH;_R!ezRYsj#C)e?nG&K7 z!4x=7hl4RvynNZJyG;LZj5P2irnMWika$cWX|_uN^dcK>>bWZdV7ilpcy!{wX4!uY$0QoEG!tDx;Z-3ydHR+&Gw~H7L{Ugiaz)(u4!P0qyup@JG3OP{(4uza*8| zq&_))YHVt9T*jdQ8n}T0O%XGiy?rcGq76C-Lfydt=W_1zUjJN#CJ1{-9@mX7NnYo3 zq+=cuv9yPsDB00F&*+e8+ag1RKcsk1q^X2ni|mF=!(m4o#CC&Dl;WMT0PLIbjkVUH z5`(VsjpWGa7r=eelE-+p!WR%~h?%f~dcD5SK9(tgxHMvfHa$SjjLm0ur3%{<#nq}NL~u(3&>~qP z(1K$T7UfPfx&X4lwux}pD&A6txBA7r6y_?XX={O1UfNU5&MH9MSW(cyiXOpr!sG?$ zl9+hK8y1yCaTbBGEBqjbG1RCMh8Y>%hK3l2I0zb42yBWWrwZg44E;Zhc)-hSoKsAn z@NKxPMJ~ePva)BYI4TS5Imb8~(zBKJdWS5Hc1PRRVBQBW-3Kqt3nQ(R1k*}Mkxx2l z9Jo*WYaOCu#qu@7@LMWRZfMR1LIWV$qCv`q06I6ARK~=7SMbuErkT1yv)@=Zux!L8 z;1VHkOj#ep+{^IR1hOwdXp39JDa^`=jpgx3u2^eXNjp9E#6-Dpd`@r$LLR`zt17Pt znkTkfq95;F>#jHNU0!RFYt*@S93OETX4}7)*4W(sXAj)-nR_05;GX{;hcMY-#?9l6 zP9_5`AfXt@$q#&hBI|`yC9l5R(910=Y^F3;Py0>sHnb9nggL2~`@p6f!0Bk!TBY3} z*S2w$WwvP-cI5<#^|N8V@{Vk*y7lajSFCGq%LJZe7AU_BbeLBO(#6i2a#L%V4jZeA zaAZ`;kZ-k7G3G^M6Z3zS`E3qY9I>4#(d>rMu zD{)RU%?^<38S+$;A^mXW5Kfsp8(7mdy~Ogp93j)yx=m9-+iA&)irvd>n;`Gydb7`M z#jct_x6V;gDGe&zw}QWOI1W7zv4gd5b}|Bx5^mlD)pQ@s6q!tlq`kJ7ZI$RpLlgXB z5OhSUp*JK!5n>(-&=zwK`Af;SUry^7%&!5}iWsu2Xr2tBf; z8X1?O8mPz-6ax8JKOdSpEupjo8lzf?IxwyiNHQZFq+OH^r6)RMY#Ek8Ad^zW)C)Ku zFdC+m+|Ek>A$v5rSm2wBgRT}nPSCG#&~>~h(iJdRUWNIV9IB}2o(V=Eac&c7IS78WW#F$VX|*SDH3(A zLOqmgu&SJUd^q*IW9Wgjw0$^J1q;?1KsJ2}yc!}3 zV{ty>U|_K-BlRoHqc7&uYYGI!w=Zo1hFwMc>|>aY=8ElOnKF=oBj^!hQ!X_Lm8*$6 zvoohB<`8yd=i2CY+vH_$62k`?Wn#z<2qUl$%L^hCeoP^Ig9SEEea~!mbvy~{+ z@35PY0!TO%rZ!QE$^+keRI$Xf&7RHmf=+h8;Vu*aW&L|OzI`myXg7DBgBer&clH-k z!lYPV9fKoMS}-(Pzv6yF(KfHHE5>zQpqrkRq$#HRU|J0b3uPTOVhCuU54tKiru*on z`{di0ZFBr=ec zqgR`NFGH$nVJ}aH6lap&Zugtbvjsu9Q6IYGTR+qqbNU*b9;FLziN%32Tjqphr)32=q06M|_urG7Xm!TsC~VFo4!}MR^eSZog@# zJS%A+bo5v!_9Fvb3X&Q@@YseEh~Ykz={}UHnTcHlG6e{pFl%M~Hg2Gyi^xzgb=+@! zb=afBA{!n_rCpOS4alAHxG>>*={Q-dW*&R2)avF^A$oCfBkOC1(~{(^scyprOLaO3 z0mB$ZNKi5&!DnY4Q6-~Pp|Qjz2r%5>v8CKl8OPL~S?e$Gy(&KZIz%v~dZ*_m7bYGZ zV}-cgAf};uT{?Veq;4sM_kDtvUPYwRD-KRtCYMSqdvR5uN+VTk#78ect{hdXVHbYZ zcDJ*7)c-~hZm^UP{M1+@WlE+CCntH~C+35!A~{=|sDN043V$B}mz-Q{B0ON&h&0~K z9!?@w6U2{E$CbTY@Y0M>8b)jhZ%D9N$^^DX>kZ(R6eL2*?v~f{qYGDB!;1}v`jx{h zwei&w{62c=H9;>m<05Lp(L98xVDn-oI%=Ytg&Dn!xhmt3!=004h(+Z#* z_Rh*7=Ey*$@}#I9ad_#AISRW$26baCNR2exdL&_C4>4ASHu_{*j@*!-(4`J3FK7%P zuwXAP-C;d4lAG%el&QLGAFgyCu9V0qB4du-Ab zO`#qrvFbwwQ%aJR*CV!(&T8lD*&x!-Afe89zCd+z%|#c4~s) zMnY;a6sn2|23e$@kw5C#4@@k9b_&%Et9L22EbI|`Wb7m8MDG4Q$Qxwt2MpKo$;Xd7 zsJR%a$m25tK6OA)#6L%VcMV7f6k8Cq_;Wr&M%ZNaDdndqht+%F!GLlZdhRQ+OAQp5=jGCQZd+=# zv2YJjP-V~+WbcI6YnUO@DfUhSnpac^T{U2tohvY82|R+(qTvGbH^7PkB&$HHlj@u# zz!Zh<@1teIq7rYPXWa<5g2YmXX3A&0CHK|*)YzjqOy(wzO^r>Su*-xdcDx~yXVY1< zX`$x`sWHNx6@EFK-N{z*M@GQ08DrlD07hl$CQ`n6&Th1{(6rafQ-OnW z3pG&Pp_2x<`A02|@3*b(^pqUO1mK0w}gGEk<@Qh+RNLYN#Z zOG72C{1HP!a$99;u{BX|%g7M6{0%Yks!0%&Cc7JQlSlI~>x%MG;#Zt2QS)-Ls>tH` zq}Aw~hj9;nZ?qQSYHe03$ynOf=-0Ze7mgAnv?mXak<;J23|u=~Sv%zHTT>}ZKy}ABeg|JJx}4bnhPSYsD07(0p2~VVqUVvhUVa@7{_Q(kKGevv$Mhz zU?iN~P-|gc#teoDiY1}hi}ha^5B?aFDvj6WCQD^v6pmEi=w3aePXG5{-;5~S*2dIGKqk`T^H zI8C1}u2)TP(OB6^TdS^HptB{cuv!oD&8JS3pPQKuS)jzwequh&Os{dp1s-j&C^PIH zZXe-e!q_4}>U@?QD%m%MJdiVkF~Z|jv-r`m`3WqsG7K#ewdR>-B3m7cEGgDc*#T@v z73#4P{H#X+)3*{*hO=f@l8l-(fT@B8Oqa)IPkK7368)H1qWucBORSNhvIJd=mW}K! zNNPoIVsxqTO|ml)RZGDyW#QfgeWaFjBucHgQIa9Fx{*XD)tCXs=cswKOfGRCYl0o| z&>hJQBX!KvqMV(XpPy8C!sF8?j~+Yv&^@2N=K<#ao~HB|^;+IAuTHBM)fo`)u5-u; z;21)hrP&67E8>fo4C=Cekbm;N`Hb|Ix-+ac9(hAR?!@`DUj44+6M_@Q>J51~8?(cL zog4uc=VIu4)Nn^y^flwSrixgM84*i!$5q55qcZBwi%sX_L!OwJo1T~|fknd;#qURF zPEH@2sF8$36M}kH^~=?Ts|-kGcKw3UPR*Ro0Ixi*wz?|SUyn8(88M@ViX@E$m*M`Q zmy92k6k(oeTEo$k(^Q_(Q%*lN&tQzyk~~c8(ipC69Wn{chdtD3@PzzAp#ER?K z6x9%?PRt)0n~n-F{FTj^iM#LMBlcPey%O(Y8m6lu9l&84Wj0O?MQO=Sk3 z>YTei%@u{eLi*FnUw-^3eXh4s38kC$SJjaiV;~|`j*P-*+96$P36JS=W_oIJdO{y= z8MrP1kBBR#2JvmfjMr52;UqJ6VcsW4X0<|@2^vX^n@uwY3kqcA937$X;>VVglICT> zsmkWj$kY3i^pVGlqzGemU#yWB*JL(U^;5Q%6#N}#J6L?#<$bY#M91^rE$kd9W>wtk-FX$CVmnl9 z9De04cJ9tUDE+64bp`k3^X$gCqR3}IR%{eEed=(&BK^!)snnI1`fh#0Lu~pcm1knV z`X-(KEL*KYIyCP?Px9Y?x*`r$)y{`@)U)@7Y!ry|at zs-OKCKWH@-arR6;`%8B8LVvY(e#1XDUp}avxVUPf+c@<5Y&R8yTW`AWcVEd5(Pi6g z`Z$&E#D3NAI{$4pK2C*B*FH{XU-F?RRm9n<`Y&=wH@Sk^`Ct5l3Th`Vt}6Il4*h$! zofXt&)Xo)D`E2Z071a6LIYtHVNT+KR)Y+px`=kope4wZ*cq>13lPjp5-}etHsGYdD zs^HxmI>xrMg1YQ^HnpJ2U&ek_L7jh@jS8yJ=~@N9kGLpv&H2Qx#OU4|%_;g3jN{F{*GIg-+M1aG0Mu>?&yIQ~p5}v=bLsRk)Kw{{!33 zD(JEeHdR68k;C3Un#Y;Wzs#mqNT+KZp|juh*(X)#<^x4FNp$vmK0Bu(&Q=plXSaQJ zUPYX(CdrE&(hH+~+4*<=agO$7CoZl&P8a{e=YQq@eMLKQel~x^s~q|Zww)iZ%WjDe zcDWt%8VcS^+UG^-S+F#}E9~*6d zo&OFSRZyYRwf5K9H+}X=6>+v|f1UlI&(5icvsL@Qz#%=-)z{8n`Ufqnow&HFzAiq@ zyAKt#uy*2n)xtmG{NJ$c{5)ND2b(@m<@2#$wXn{AfsM~oq0=?~a928;_>-5(dz zZ}NWiQ9A!iHXf-$r)$GTXW#MJCsoAR>I;6(A>HJ6dxyI{s1C6c7gxPf-k1iwa?SpZ}{w!Ds*#g$UVzX-Q)^t=im4TJXFk|8`=kopT&u{f9MVm$h<5Jv56GW(;^L~M zZs(A$IV?%zrhN5b(d(OZ`KxR-%Jp-8-tN~`lc~+24PP~{;t$zwE_%hsi?{zt#gq$f z(QOBdnO({l<;`4`!E zqzav`HNSqo&ZfInewMCgznaE6{{|a(tN0IWBX8Gv9XwDx`7;XX9?Y)86t~3gLlk;w zZO;9W3;!SAGpi!bR-Jkq7ymZf!Q$L)xrOw+TYc=lS5)4~#sgK{6}u|*svWQSInO^> z-1mygsN1XxJx_;K#_Ov&_+B5Z%OCOWUv@eB4@MhI=cm|cFcmsooAf#>rI6-QG4I`3 z6>(uDn=Ei>5NB0<&%397LUFsFc zG@FXJyP9&ZaY(N`Sls`LUaQmE&)t&G-&}m_izZU}qUu1t^7}mH2W&7+6@SULi?ZpO zcYE6loUbaLAFKoamhE7%S?CM?OWM!p-{H4vRj+nFwyTzhx$p=ZwN&vNY`bcyYj!?R z{cwg&lSt*^Pk6tg2|C|qV@zzM)3qt6vpT%@Sv~94c%IAU*srFy&fm$#-74<$?!1ae z*bWziA0DXs>$Y^X_VUki=y5h~SD~lZ&R)vHb?aI@Nky9tPWZ-i)!TJsz@}DG`O>d> zzalj{|7|v^qC%%@Re6M;^S)!NA`748_ZeSyO2rpqS4G@h&5U<{^sBt>7T;Tq{2z1Z zZ8i}JmA_zPRH*nnwnIh#k6zKv$9-ER2mm^9k+f6}4v4&m%rGtK!$#px0AXC)~z?JJ?i1m3PJd zttwyqhr0O7Kge^Z(8Uk2QC$@}Uwf6#KJ2rV{pSon*L-MJMchy|>J*1&+4LQc@T@pp zbO^s^mP6&*enuj=PkC{hri9wzhOg1IDFHm?$EB@R+Ag`^RB3X%a?w`l{uO#qw~jo z%d85W-f{Po&pxRl&Q_!3VGil=!Q$y#RnB{VaI4C=wEC(qaOm4?no-r+iqma#=moZe zMgKOH&$||%%XQRy3JzHv)6OkEKda(a@19X{M;ul0g*d8WIgYAm$59mO_W{bJENyxO{WhR+ixALM$Y9Nt+S3d z_k8N!M}M3u1)DiDBEshr^#{Mr#Xn<%$f)>FY`a*GuF+T4@B1t*8SP%pBMpL=*-V5e z--ceYe>8Wj&VP@MQSnwfT^oFdx%!CjxbGE}FS6065Scng2*!Z~LV`dgVp-{*`}i@JoAt_nUg;X%%n4^k_a6KlEA?exGkRRDA1==d|RyL|R^uJFyp9~KYX*)Kjhto7&Kq}D%Vi*p;rC-vj6**@-z zzxC`VKfdtypVWc3*=WX}Q+(E+d1h9h7P~*9(3jp^JQJ_bk6ZlNXO2=t3!KRkny=4Lo^7sW#Cu2DqeoXKCNu6lS!_q;^QyzG9SRq8&&Ft zy`r5M1W&!q?mKJ;il^R5y`v_1h^~3nJ#|_|%$w6Heh^1R15c^A!%h8^ilc14L_2r?6W_W(@vs~9DHT8Eeay)>pS#c-7yO!U{opz6==ogz zgXgrP2l|H|nV$253qI$IRGF(^e@;8;Ij`5B^ZIkO=e&Nw=e!=zdF?svr02X=f6i<5 z=e#!Zoabos?QU5odd!C*2wQoH4Gn!94 zKsVDup))I?0+ARHkx1F=qMgy=u-%WU9qvGw!fmCOlX82rl2AkO7? z{*vci3ZuG(7u_B&6K#4Vc9$szv6~-U@G~wvbqBi|i;@B;o@EHYr&MSHb5w;U>Ve{O zDt;V8>qk{1>BjV@`s&d;>}m`T2UlySAM= zxyIyuJ@>pX2ENS$USOlQRm3Y6>Q&OAL&cG|s&S?Frh^N+4jwLk^{wZ39p(PrmmVx0 z*mdFP?cabOebYQ?R>lA1-AbZ4!q0!qMkn2&@-Ck~lk2Y2Q$BtFD=N1~Pv4zRhrsI&UMm$u2Ef<9v}IF{MmaST}Tap)cC#UMx^_EMo&IM z3j_(e|CML?{@2;+Z~P)pS!RPVt5A#Hj3hhqJYAy`y6?8y^IqKJdEcki|B_8TsPd<5 zbupcv>J(RjGB`)o!Pl}sE`5}!((l!S@1zfmr}MG?+xw{cMh)=(dQd%bI~zTyLJxdj zJ@_UMNQ`C3Dr*Oad`}0(hHyS$h>E}3g+qp&5B_=qQ@rWd;nX+%=54=!*MZ_Uf1@H7 zy5`-42XTN9-)eL#AB4udI5aZWj@AfQ?dTrY9xOgxRV7oyQOfmAD)3!495O2YlI>7& zZm8SchmaV;W37TZxLYvJjkU(vHXFA1eCYY~lo~_Jhwy)5i1@*Q-IrGLCtnKb-+k4t zcToM8s;Aw702_jBt@`;Oa$$bn7rAbktybqjy0up4d?@PtX7!eQy!OE1p{mZqLsgyg zA?p0S>S=$g7yr{8yi5m^s*&sb5Z64+cA)qd`HJH@f3Hq zefPWy-Gu=6>T~%%o!7xyKMW83i+t5*(^Y)aJNa1g$Zv;)Kf<5$LByYY;j>)#JX@_F zq#S(ThpKPVq0kqqZ_0<_o4#Lt(>JS2t9J|!Rb4YYRCUb@=|(<7F;($*-_fG@AKAnQ zRL-*1yh1uHb}W*rQf#Sq`o`x2?eu}8^2XjrpG^(${`i2n@i*Lz^D5M$?~4!o9S@M6 zZ_PwnrSwPtDAHfP0>gAZU$aq5?)?!PR6#{p4^AECAxGGtqAK))8rfLj!VTXuui}N+ z&31^oCZuC}qy|uaxrK^cIZ8z$$SkK)bejF!^XcR4h-@-LRcw3rw2JR|cUHy!&31%u z=I^FYo%uP%J8ayd;#Qu>kiC!M5%12b_(B|2@r~H!()i=&8XJ!Oqa1i89d%K!>1R1Y zO)K}BF1VeoMoaGF=R<7zIF)O$e=CLmbp99{x2VwRnv$WjdI^+6MVzhlgK-Yc`s}Qz z$QNUm|Nhg(&$87j^AbP5!=}opRJ*WWRYvFEVB;1Q(QMW0UQK7wSbf$1#c$+^LS5gL0VhxmxyuNwI>Rr>`twV%pwGjZ$fr}Hnf z)w)fGzT-nrs?Z&^CjDkQi=WF^DdttprZO(An5r(F^84<4MdcYkX;#I+yC+q|O;y9b z&P@t_tqAsyzsU#)uU7aaH{8&gHa-?LTSyv+T7$W|T570lnj zlfHXEAFwd`rhNWgzA<0o%IFb_c&(}DNBQ}Z4^=XtUh)MWnpLr*4ZfHT)md*ohSza+ z#E#JB;tfA)Ud5gtscZC(`U6$TcyHBN!$Va==R@$<-=jS%{+f^1K2wMOEgL36MKtHX z*V%uAO>&0HAFv^Dt59UI?fKgINgU6&{gj`-LzQXN*Q*}R2kTSdNHwgg`KUv>w>BS# zS5=>uugX1}->lo%Ki+9_mt>TQ9O{DylpJU9VG5oqw5)si;Dy zYc2X64*dtVgT>ZuD*u+PM%MDpYFXX=bDut?BCb58BA!`Ixt%xt&^Ilp_*v|#i2E0Y z_g8KE1J1@hvp=ownXTH654a`1(dF~8f24l?s6TR6#cA)(uTkjA8jn-0Z}XuiRm9n< z5;`0A&JFMV|Ji%@c&(=P|96&B2qA=(7CNC4l8{762&q(vPOFsCaYYeUR6kW z)E6>s7qWA$@T<_rNTmz2FLHa5%aw()db?Dtu1%yq%3X~)f0`DpSn7Hrs&F;tJeSFI z+-j-Tgd&}cue5A(v~`jAmh**yWm|-5i_g!lMXxvd*5re2c5tnha>r7?EA0k(k2e=;QR9roS`;g|c%~C8qdx7`-z7E( zJ)M8YGu3VK7E4tbRtsy`$=F%TCY#YVXf*v*ToT)SrHRJrrSB2?L?rn*g0t)}cGKYTSf@HDbDsSv|ZNd13RkJ8auTOXi4VRl}eZ`h zkav*l^M%T>IyR|;Rob*2E@PEW0=ZR7b(zjsEVG5d zUzZxPj!tqLdx3J|Yup`-jiI(Km1I~g)Rr?WQ?6glR-=t*c$y8P$J_<(6uFoY+;lLa z;pu6k{U-;{YpI@`mu#==ZauhY)F3>#u(pLfZ{wViNlu@Z^s2dgeFQY4<8DT5LATU$ z1MSlR_vP#XH`Ql?<#|=E{Z?%&r{xa74Ww$Q#nqclwdlH1sC)iW&FDq9UBdo+a%;@oAM63vBIt--6Giv)BIe8sZmamHn&8c`fE`O z40mp>1^Ghdo@cs{E&r+dQt}moFV3|u2x+ych4vTM(j*MM-2T#CzI%pl&0XkOHCc;} zbcrr<;%}4`ZbxSDrz#Bv+vILytatg$eL`xQc_xro<#vNs4ERlYF3rgHdwUso2)9TC^7%i$gNE zYegiFPqH%`J2U<)`kj7zH^0zoDxHf#I=`xPDxFri0aduzcAm>*R^)f`;~yp3U}r6U zao&u^xglWVQ6am@OmmDDHP0wRZN^f$o2(M4Y@!S7e2itf6f?Bw&|uuHWs@_#{rLTU zudeC$>XlY1{+wS`y3FcsL={(8c_kq~H)0csF2d?6wX>G6x}yKOKRW9dT z4-)ejEn1(26`Zg=#l|UVn^~fpo7s3xBu2|ze|DG34GcZwgo|gcu=1+h3JluR%7t8C zc0WsX+RyqIoD`yqdiWW%qyq3+Ab7x(ozgc%$ z`TCb@e3>*Z8M`_4QON~zt8beXT0FeX=pwgSWvdXH~S*j2lDPs+B{tXMRX6=?BfIL(Z>L48K9uatdi9jb>difTwCYZe2=d4vJH0_mrnl_S zX0a<$pZY89Ojp>ZRExX9^kXPBV4^T9CXG2E+1XeWwZ?|1HM}mF1H{5yZmtJyQ5>u~ z7<*~auD0Of+(xN^R=acTP3@Xe`FkVoF>`)Q=SIBq{Uk>XHk_SlM3ev1+!o4hqea&U zD?*}ADBYn%7!;DH7=Cag_i2k-NpvZNCRQYyJ7s%qrnH!kzb+Tsk{gw_q=M8{J5;(| zuJkv$RFyQBor{NtrrJqTOwppwGH%wg$+6G2_Uzs>-EB(OG}pv*6Cw9&pp;hC@D8n> z^o^z;$4G1RkJ>U}aZKv}+|RyrJTc~kWbWKxlLLdQqdm5XN#mH1?4bX1ziLWpt&I60 znHxciB`yuB4#x73%M$(|z3VlB{<#$?)DO++x2fSu{X6aLB>b65j~*kMC+A3^?+-UmT&*a-E2$}6_S*&aN({%b; zS`(!`zp}p&Eb$nLxsP{Za%xtmnX+V7l2!3Nzaa%Wl;>xao)bld$7gkY{9QIFr(~6J zwy)CU=BzSUhT46#muqA?vC*ShrDjJ8vmGtTDhKI{zpClwtS-*o`;JsG!OLCH=^sCK#BLn&3MR70hx=U^r2g`=D#eS*?-L^rGT*~ua9c^{B8 zZ-nNTkT6(656wKNjX7FLf5^KuJl*a`<0eZxwEyT4>2|wGvc9pZ4+U$U6l!`#y4*+Z zs_V`&|IypIm4bQr_+p&=dYv@o=SVzR&rhriU;9hWmQ-#M#p|MK#E^dabZeZkWj?C# znZ!3F#OYb^(N1^4nyYF=-?Pr~=U_{dPEus%s|qtr_~@BvYPP<;{DF5(6<4g=gOa|z zN1i2d#NecLPK=)m9h8%Uwg14G(zI!vG~ok(;cMwWr ztuB~jX~;Q42le&bL&<9{na=NcT2YeyT;l_J%e0SYrw#kqh~yo~>8z~1yrYC!i+(87 zmL}h8=kq@A??WbkDpwO8hS7GI-UapKheL*FvpB6`<_`wZSX1e+yk1EE$%nTxKxgNextqO zUK`i0PW{l49K-gLq)yg{F-tTToj1}TYetVa*L|PdY9XB)kRMG5RJE}j_wD1+rD}GNG&FzYX^|7dSm-Npc>JROLrTV34c|;tD!xYP zcxDX!eDZ!ejt!3rca1*uo1C53C7prmcdrqBle3%Ti}}bKlpjeMzWA-7*GtXS zpm9fhE_MDBth?`@k>Vr`$#Dm01#^>0ER+;JKt58Y=~riWKQN|yl)4u$PNmF;$k$m{ z?hD;-*p)vVJ-?~Wf5V5292(CBdmp6H=MTZ}(@clVA;Sm8NjpoE6H=L-aGd0lzJq#= z)@&WNOYW0Gs~2WSNWKrkx!N5MJy;bD7}BSAvhonEpDg^v@L1W6&0}8asHFFyVTgF3 zrhCoPQVmsa<<5Q04hwrmI+s|P#L%hgW^bnC2`l1xEv^w6!;_zs6ZebM`3MbA%`~Dp zm*QU6r?o6REw;9$PC7}oqkRt2k^a2CVdm84l4HJ3ivHYq*S4ubAAm;pNflaz(^J|d znxjfz>wQEcz9gPadmNu8H5+B$;l09qY)S2tygB?m?vIrk-m7H5sCbMDN1wVKR9Egu z+g(z>0Twm)g63H(O+JujfCo}C{A8s(qq!%$`y&;?E_qZ(74w`1BL?;uHd0?jPcH2g zG{Zcvc&PjFatiGf%TT$1`brIKtxNP_;bQDWr??n8RcU{`Jl4E6Cxxnqch)+)&gAJX zDiVD48=_A->%+YITKrjE$JNGN7N(_I!jGIPcy2hBcDtygX2v7+n>eN&N;mX>-;f1 z+qMnLE1Y)w;Qm3=G<MzbWE0tByk4m;sEBa`|Bv)Fg$!jw84m>xi z;&-T%k4HyQ>olT|>_#NBF34z-SCQf*6iKf!F;il=l3jwVsXIJSb31FT3!|O&$!9I2 zz%GC0MF~^p9O=n92IRyr9YbkO^wc^R=cF*b&J_~#v!#5M%j~4tZ?3;Mb=%3)tK2TJ z;M>`Im!%56ZU2faxN-`H$!J*=&Kz@JUK79G-gImjiD3edBb3&?P`U4Jua>rOYJwdv z33i^+BY!4KF3l;^vs8z?D()vWcS&uMD#Lwv8>V@ybxMCnh88mYJzlE6pUmgFak=)4 z^z;K7L$jpvw3cz#^*q^q#}{bwM~0-?gqWktx_+9WB9pU-oc!dNnaqsBoGVF}WBbd;+8942gGnkn;d?H`Y~KNg-fMUiJFm77u24UF_~N- z%J)rDsC_+TegB(tO318>X^CB)ln0U z=+{mT<#pWc!ESt*HNyvJ5`avZKd0z05Kh%kO(m7dZFNn~NpSkBYM@8+)z-f@r*w!W z>?eJ7m>H4Gy)w;7E|ihSQ~x3QjC_8pCJVCqbR;CLr)8{jTREA5I;Zgj(j}U3Ntf5p zl+R1PyRQ5w3HLsso!eAtI>bsuBw4X#iQH7|`uerPP9`Q&8`@s8i~-s8e9?lc-bb zN2TQAFGIz)te}IIOm`F=5iGVWGk<;E5y56Ap`|00&O`*eNz4V?FgZJ`i!rj1Sryk@ zWd%BvS7w#mL|&iOr4hl~vdVayQ<@Zn{_-)oC$qL`L~walnMMTP$SR4{eVEmGGnXdo zq>8BxO0n91DH+#x%ZlEmbvYBRGk25}B7*gmh!Md9l!_6-!~ku(PQxP-zO;4*14A-~dO$L$If!~j>yEF1Dmj+a?h5o3U* zg@uU$UMp=r=zG5;uU|ZhjR+s}ixI)D+iUEcMMSW-gnUHsW=Z8Df-QC2%0&c+NGKl> zoF-jiL~vbsjc)8K)u3cSMDV0k>xkeWgyg54qOBu>4R(&{5Cqv%8QF;73}wcM;ARTr z6+{FNbzCnS5gaCk#$A}9eNsNH{p21?`H0}_E}2FIPcPCj+;@`koHt+5ylh19UCH5= z`q14yV8eV?YxhW#*{jCcb=7o7nO1EU_x}(bd{^3dqdlXZhfI12@Pks8r=xaQ_jSLb4@#};Z!lg?7)V-HtK zD!6w{hV7@TO7~;(TN9Rj;ZCiC&Cid`~<$~D5 z=Gp?`ChE#|O5|e?cUZJ#aGbfb+Ng}6`euV?v*pnMO1|M=l@H zII1Mtg-h+-6nS$iXzrzb)6heRXk48WLqy}ooal(g?3@%L8V^X!M>MMUOC33)@kCy7 zMB{mh1rd!C&q@_UG=7jpK}6$LSrkSzUe9Y{MB~){VSI;(Mv2m!Ml>o6$a&QyalQ4} z`A}(OR~XT#dv;El9{NY-Rq?iEmwZIy59QI;G%itfpsrmD;u235YBD!eR}YG|o5m$- zoD*~MHy$xf99FyWJ!%vCWWz_Q$wHt8&V4MLJH(d|cv= ztfZage#zk_w-&onTG+gzaJr=@YgqBosVhyDnAa!z_0Nm7f@? zJ>d!4gQ*cpRk}o~{1de*=W4iQp0Mp9nI~**a!Hk{G%D!B+2+`MS~-V|4ms%)w%!sq zeOflxM!BbDkJu)E$^KDJ3@4ka=W8>?r)B#qS^h!Tad}oX)U|DCe)` zUznOxmW%71a7CJv)K-M>@8Wu0vikH$ntYno=8lp{%WI>PoF)_3>r*~2xpvwn)_&I^ zc^7>MF%s9Ca$U65$~mrgAEM)Ww_l&j^24bsZ$gZ5y+@;%i{yQhX2(cg$qd@?w~@U2 z$t9Ba8)7DsSNj%~S0wMvTce*$B=7#28eN5vyf>sOAIW>{wyZAM?T)ONM)K~}3H0wn z{?Fd7A)Slyy|{y8d~@_7+sga&XQT?pg&3bs;Yuh#r{jt>3ejnxSf!NOWSzov4@R9* zi=s}Ux>ur3sWnQ;#g~SP{V2MS-d7AUzO6*Z_;#`^?qL$i@>`FY7+-6N z)ibN&-ezEd4&}L7C84dcSzQ|Ao0L_?OVrZjhO9ClW%K*axkjcjzK62PG{*N-R!Qvb zg{;oUkkasFo|yVbne@z;O2)PQQK@|G+KMs8x4jZE##c+J7~}J+&(w3ElJr7LCrKZx zG#$~|>NLjJLqaabceVs#d?S^NF}^aT(iq>BN@rty*Go>1rD=@sN$GMizAq$XqGnrd zmWnYj(KIKABjzB9g;BEyrOBUy*GS4l&Hl)V;f%bja%fB@p6FTK%EuE2qKnr({`x_= zc;W+5m5nF9h$>vY{YOGUJh8V0tZQ*-meM%R9o(b#^s;JnWPY=x<#hxy~@6O#B@AqPD-Ur znCd6%%7v-c*ps(j#dp$#0>@e52J zNC>Zi?OrEnlc|yMHL%4JV*IgwT~g^AiDyc&X*_Fmp;mACN|BFeJt3(e9+BKuUsqEh zp0)4ZN~Q6vM^Yh-?%yO8#5xbyM}7)kt{Jg!(BuPL_m)#=1U-x@AK*H$k;Y93aJ6(Q zJ-R8K4{)u@Nue#h8){fN43#{f%i@A4l^@P_-H+_-pmTICSf(%6^eA66Y>T#von-=C zS2WdHZxZ18PTGGAaGlevTxN2}A>{&G{d5YC0j}XksLL_|uJm3dRrO)6ySR7sPX}>-=ik`a!u=&8PCb+){+Wdu9>WzIve2X(AM^w1h{4e zbsFHB-2$hXu+?6^y9tjEGRjBVq~0^ikK72aY&O6(?*#2p4sboHL>k~)qI536^?`(3 zfa|mq^8v1zN~Zy?T~4x*16+rtDfw)xbi8^90j@_SW&>RBr82iD+ja1PE)(Edbf_Aq zOM&E2<&+C>`L!;qxF`7R)F|cyT(eKlXp%RO2ypf79y8Mb*K^3_16+F$MhgM1Ur&yO zXm0N_3!mFelN_Jh%nT`>+uSQ5|J>#iN#&l~Oz5GpmcGgTsD$#*ZB|QH_}pgyp5-(; z*tVB0lq`5|b3>~2bDISSN%KC@){iC5CLK0WNpG)1xU>lGTzsp{qX+fVA8mvn-fuZE z1o1X6Npl^<+b$=CAYPHgd=T%#T&9C~4f>`9!)r-RB^Ctnp2#T(;`NlGAc(hBKPf1q zXEAyy_K3VD2J!qNUFM0<=KVF8GVh4Dk*r-j#Q089dea!+dTFVY7++o8AZ!xjtFC(v zl<9f1XI>RAs4DH2+9b=AS1!i4QmVoj-}r$AnoO{+%b=LEX^d|*Ir*E)OtE3-#A4~4 zX*P=YGkJd>lRfiO;LhOh3Qs!fP1GAEj7w1Y&V|)+A zbU5vQuXI6-?~hcG#`td6$t1-1M%CUV#@C=!8$J``>zc~3N%{^;xK54l^S zNrf@K9UXv6V|>S0NMn2*B^1Q?&PWyc7~kNa%EtIcr$+f0pM!<@7~iXsvN67OG1qU= zS35TtDyhC(ab6I@seQYG7+;0aAt#OT?IUs17~cpRaRF3vwnsd`l2we3wc2H!;2krOw3oN?K_HImXvyjD}Jg zY>e-IsS09zbuSKMA&v13kysGpyVr`p zjq!b|9Bsl(jIXF%jPH+2WRZ#S-8IffqkN3-b;$+qjej>jRpeuQe^jMKoRJn^7WS@8 zjPLmgK|_r1fQh~kBgS{PgiMU@Ly4If-!BEC##g1weR9sl_^!WFVlKuPB7QM548YwL zz_W2K##c{@!WiEuG~t5rkE?=x=H0zJttlVl>pxi=B*gd{Od*wt@!cyON1))87Ygk( zck7c(otiT$7vtOUiZmzrTtu9k?%uxT^ODo2 zZDJi_e7B*`#`wBj7j3n&j`58|bd2xp>vLI-@pZZhF~;~V&Wg#sQOZU9-b!<0#INfN zTJ*OOzuU+q;`cRTCgQg}5x?cPMn9Q|-)%EB)(Rtj&q-B2;y3TMtS(t{dsa*@{1W{< z-C)IJl!7^p?)`5xFBgpaZ#0j;;r-tn&HKHg4o3cqk?_>+hDzZen~Ar*DNXr!+u@a? zE?$FlkyI|;Ha4oV@iu>}RaUWxzw25MZ)>`FypGBJ4et?BY!YuGs__8xPQG`6=?LSbz0RcSJzywarhb_EJzd+*6C8_G*gky%y|V|y1B7ACfLqqO0c zJ8X&($-xTN#XG;FLW(=T6C~vC{3b{$cjvdaj$64qztbd?zw^6Ty23lZRpm9h^ZO<( zS#alfXbt@N&aW#%@^8f*T#N7gcGx+l!=2yO%E;dNU8c+!G5b1Ar4h5bHN6Egf5Yq9 z`O;YDdHJ-i8m3vwzp?kEOQvt^wJp*GNdAqzn`_B5bAPr}atMXi-Q8m_ys`J{9%(Wg zm6}{vO?N2t!_722(@^MAX=5n#vU-`|XYy25A{6>+0}ZiUDD-ee=|U)UN5%BgTe>@} z%)PN!X&{q1DZb{5H$IKX5#}36&faopvng{A8o3w9|D?7oFbt4veNm0X19YeKej=X*vCwcS`Qo9eHq^9D3vJ9z0-D9r{$oIM z#^L2MlcRMbQ}D)Kacy;EI8a{HRy~vnXntn7AfWl3wnYeNp4(1|d_ePRi+>l;{6rc5 z6wq9DZ25p@)#HLD8_+!I=#1xNybKBhn#b;`(UW;&ulotM-z1>vc%vG~UklD}jnhn+ za=)YKhU_lBW-v2O~my6%cEsWnaBqaCue|vi_xy0|DMa;zS zKDSD5?A@|y{O;UM<99dzP5f?bVf^lf+y5zkw?Ox86_Y!EsF>WbQ<9vmh+cf-?$Vgj z%X4Z=c$w~QQ}Vw;4i^bJ75k5cmu7X`FuYozL%Bvu%6zXR+CQ8m?N1EG*S!3B(%frX zhf2r?JNy^3<-!^FNtFpz_zRzf(TQiJ*)+A!G$9g(hB|@TsRXU@gy>7aA8*+ z&72Owg&NAp1{Y>2GxJz^ZcYqWnvdi}Uuiy*lfsqe3W@nE%|=yIN50bZ)G5(zxYArJ zF(3IqU~6rg+&%s*N#P#9Pc{r!`Eo_gJZ%BEUcXi0znq@SVno26x;7C#%9t!18;^tWE? z^{tjcJ8FYzNq?Sd+PbA$HfouuWtJA(jMI|-{;%4({HVVv|9@BCUp~`y$oj9Qh+TCp zHMIE8a?@W{Uo)fcsdR~!{#wTTgMLs(zd-4QS{7+p`49TV8NFvrt)!)@mLe^=Uq)Xo zqhG1?DlPA5S^p3E)fv5KD_@~yrIvTJq`y@6yLG#1n~NJW`LU$aR4sm1e}H`P+CrH+>L_rJ>T zDcce)p80%erd(BpUaM>IgyY3p(%(PnyUC`z7SBfBKV!c}>9txs3HZkUfxdwvy$!W^ zD(+TV(wV~3`Wq@j)>Mlp;BKQO{r!`EsBB8LjMFkvOFBz;TJHB^eV=;|Nqg!zq$U0R zlivCB_lj04bF4Q~?qj_tz46R7>F=NPo_D20%OEX7Gxn)&oOF}4jM7r3#Wtl{(qD;Ag??f*R7v2MX4`=_bleFru6Ul=BhofvHb$)|m{Qze6m#ajeWO-oNqw zy0{z|*THv@dM$25Xm3u76s}SVb9$ULbWoCSaa_%~8eZYE29Ip)hY3Rl_vzcXwEut+ zJ>msKw9BI4L+-HT!Y5(DdfMp2_i_sz=vhO2yn zJM~dEPuEddQI$FRUr-rM%8i)+MM4Li#0Lsp|At>v{Xa#|9MWI9Q~IE;YpdL^#cP$5 zcDh12SQ?kNop(qDYzzD?m9O+jq^w|P*42{rH}2EQVYYPp^8qFGcbU@J_Dwsi@Q9YS z&+X3o8}nJ^q?L5`=L1OU?--@+FWm`O%HN3833fu54?XK|k^C)`-u`rfpYwN;(pi74 zTS<}mInTfTT9h7oNsx5ZY!&+}J$R-~C{cd4-qO!2hfn^y-YvDH>v5sd*?QZzk|Og< z>%CsOY`wPgc1jPbX}#A-m#uePrd}W5(t77AovpWXt2lGL)Zv%byFilD2SjzU=Ex-Z zPv%JJJTK3}bbGw44!zwO{L+z=2+4Y#F^(dCk{imCc+9O!7ugaKMpML_ho*Z`dDE*`)eNk<;Hzc7b(@g)Me_=vma#r)sVjqvUB@< zVV3&yUmSY>OINX|Tb$2Fs_;wwb&;LxPy3~n>>8$-(x=JOWv73+pY5{0G|zvoC|^U< zJlpM;3Sw$^ff7zPA#aH6-Y#e7{E675S#5RToRSKnZTuUjM7Cc_)~jEncfZup;`Q)) z>JLS8Wh5qV$zQW{B_*f+{5O(We+%TVf%5IIo|e?#1LgcxJ5$rzY?=0E-rwAE{#MK1 zJ3}i3fA*XDd!n4b&iyw_D(x%-e##C%PqL7vt>|{~X2~;l#4pYBpJf)T#~D>ZpL;#_ z)soixK{{_lE7SfOX-WP0&ph=nw|(bp_V@?2zUj{?FP{1# zuT_{wm$6SCpIYVf{Kul%^{Ax3O0231U9ZPbT5r|NK4UMt52~EB=;T!VrFD6diLAeB zldI&muaCv4Ki>hQW$fWJy{_ennbTjI=R1R}zozo%9nkIbIXCsE2V%K>%|7;du5z-E z%BH{6pP5l7O|P$#bkGjoT>2B0X@AwVxX%1&(|+(!m84-NLXr9#C%YmIexGkD>VUk^ z)QNHtTx`neO0m{U6_Qn!)xSP&x?BVEnhHrz(d9isiOctggG`m5CEDH*Q`>)Gz3d$s zwf(oyU;VSa|FYNitxVZ_HX+*&HDzB4N13vpBieqkDf_k7%l->f_UqxdrtFK=Ikxv5 znC-iZw(n`mz65GFi~hyn-<16Z>t(;ul>P6}8^HdXYO#HLQ}+F>m;E49_MYv?EH$-w zqI=t~F=g*NINMhCNvxX^~?qbo@3dtC;)`Jz2IhIv^k>y9#52DL2HC1joTw$ub zFIa6~(^P#O#9G5Nb&u$B-AtA14tts^H%)Z88K%DexX@Hoe3hx-_gb;msoK7x{rGi6 z`}r1bFy*JA_5u58Zcf&AHs!Co`9y^bnA(;ZF!&%S~f?CRVWZ308D1uNlp+e%RT-_g@FWB3Cy4klvGS7UXLbBY{ zc6Y?Va&=wvT5e*hTr1K2*2dKOw1bXLSRNzV&QXSsO(&kE2I>|IQ)xOSR=ugxA345AaKhL;n zeShfbHZ2c@{(h(BQE&__gPwQO`HMxb*BVp(w88AC{nAuBD(U9P?W!);D%1Wax?MF* zl`n$DrrOm(w7+hq`e&Ny{lUCR+uM9X$2n8u|97*8`bAGUivFd3F;#CXQ`@J+RK2C9 z+A)UwiK5#v$y7V0Kz}OK?U*Ba|6E~u{Y!)j$B7MT7yQ%V} z<`^A+O!=LG-cNCCHwXP9^vg|6hPK)qr1dgqX#419(fwW1RDX9c)!&0m_4f=@{W-^! z-=(J8Z)!hlvvZWE!}YLv&8V-cn?l>SH&wo~srHtjA7skUH1cPVzuZ*2R+ws6B|Wup zyNXSO-=c0W4azw{`#A0_dN0!lkcY^E?38teK%A6ILN$K{b{OSmYe-lZ;^Pi z_BV5-_GeS|twg`UoT+iBYftC5GL^r=RJjf4t1HTH{VG%SCJLB2zosd@BmFMl4Y{Z| z+O;s%53Nk~!zfezFwImy%r;eixvBLn+C!B82If@dBY$f?sO`OHWRaAYsjZWj9GruK(-OpWUeqK|_cO^wyxO^xSdugFT~VjZtdjq7UYt0UJyu4#I# zBNxLuumNlcTfsK4ojG0GAGrhU47u+|~agqE|I0}w|WpEsv z2q(cQrs|nys(+@VpJ8e}XCcpqbKpF<+MJ{Fjp*xzs&#bSSg!3Sx_nd1+HTE}TbSzi zRDl*CF#nUysZe?Pr0hatq-ivyz@>i7r>8ZnUdu%B~0&o3d*!+OE5) zaXQp|LgPlPrSUmUbUo8em7f7;nJWLSSaeZ^5H#>Ot64AlD;9nIR>zcG15@R@k>B4` zePyQV^T&$4KWsGRuWEf!{)$btuc7F6G%@9;DQs@ae+yIfwL;%rwErol{LeGxe--+* z<`kWW8pQktrt;gFs<)@9dQ0IrxXM)f{OM%d{f@ro-m!f}rrJ|%s-1OU1K7~ib!-#l zL8ATn?=*^@(|U>?H?1tM((%F^q3aEEfc97OGPQeOv6r^5sqHU zTL0;$)^ENT#*Mk9#tmF#s@)qzmv7K8j?Y%2*Rz``{UA67`pe6%XO5|QmYS+(4RWPM zaU4|_U2hFj_11(%ruz%I4r~A$!k(h*A7kqLFv(QCi%r$L+El&O8pn2fZZz9>FlE=@ zl-)Q}b~D6UU36R&-LBcD+BFBxGu5v7$m>P>tFd2XH&|-Q|8!IS7nt(Diu_7VqQ2Oa zzM-k}L<>{>+QF3Ho~F(xL(z{zKg&E@_aEq2q5lGIge~@$oyJjnQ+`WK`5k2HzF`!c zfqtQ>eq3&<{p(G&zv=;^+F5K$-^6@eYF7jEH1)Ts@-4)oTeW|S zwPfGkdfAV%Ui~!DvdT>|Wj_T@GqpZTMcb`1)i2GPit3Nfruu7?sr+$b=oi!d0;ibn z7v!a)?bn*}x51RZng>O>i7C0gDgQ%F*^d$Jzs!{Xad4t3|C5l{h((uce`u!l6`PAi zuWLM*7wfoYYMe|m<#)R1{+MCjqy55^|3zZ0dD_pAYbfAXbg9OzIbP$|l%FzFekO_b zGsTpjX{P+l7i+zu{e%3aqSyOdQ{%9j0)JlL2By}xsaQ)v>Ya7v;c-=>thb74xQeDK@qL z*D=r0xH9k6xHWZ-^VG=|pOG{Da`EXikv9wKBtfpIhY{|did)6;QSnNRS7ckdK98G< z*Q4(l`_cWRe<5GD8Cw6?pA|=|U6$3^TIG-*`c?U%UzH#F)f>b4>YRf5b^J@~w@Jkd zHSSHd&)cn{IyKZMx!AJKbD=)Tp}yPW_OyMdcP{lx4)qSu`3ZlmOdW^YAgk-cbyj=i z4yHDCXXI|?YdTLL_cX`pe1zQJd_m(Md8m1tjz`Es=$Ej*TDh>EqW%SaST701mbE{G z_0sx=^-@1Hv0mFJ^rN=hG|M$K9;k zQ}uN>7wi7RRDEMi`3d7v`5P_o>HqXkvfs3Fes!}*`;}Q&+sCY}cABzlWA3i=i`z3? z$9=o#umAMhCn8CnkKe-u+`)RRlZJ+^VUxt`FQ%JNV+3YNi%a0;9bXTdpeK3tfg+rJoj zIa~?ffotFw@Y@Vsek1bc>Z*#0rBpYit7&TN6`MNl=`&c8bY_{aG=T?Oa~m5$<8?Kiy7hKS>f@ZioD%VOJQAD=IetS*Ms_ zcL6MeSHWxGOc;&>D*p)bGw>Do23!N{dA(%6KWqmT3J-c6N&@@Bp-`vfpx3Q`;8ZvR z-Uq#%?f+S*OQayb3)jML;IFW9I9}*o7PvFq6E=d)VQY9IJQbF}A@F=S9!`Nb!~5Y9 zxShAN+Fu7A09(NmVP7~FPKLL@xo|mr3$BGfz`x+u9#^V&AJ`nWg`Htj}>*Ro`C72f&W72OJ1JtC`z(J-i)02%m)Ed8X`EA+Ld7!$07$+JWpZ zJl7OGy_w|-RU)^6MQ|VJ=aRN-3;nTU%R}Ksa1y);&Vl|D7u)+Q{pKpT7Jd&aRE_!7 zVQttL9uC{X)8W~0Gz`x%RnG$CrEnEo3pc z;Y|1dd>XzAKZ4)Dzu>kyaEJQge(*$iCL9bef>*;^;r;L__zL_GehvSG+iV@{-5oZD zE#ZmqOgI=`1h0m-!u#P<@D=zW{2KlVx7mjJVPn`5o(Ru`gW*N+R(L;r3cdnAgkQtT zy0&mX?*W^`Hqg&Yoqr}g2abk!!Uy5g@MZWu{1W~I{Xr!A-38Wz&0uTT5e|oAp`VAk z{4H=Ed>Xz2--T=8H}E&Og)R*2XJ=R!HiiCLx%1D3;kl+{&s1o==O{FvfX~3^;mhz1 z_%8I^J1)1`_L1Ac_OL7TY5ne|RwT9F1O|<6sBa1$KwMVShLTUI53!%ivWoJhzp9 z|Mi>exgYwk;4FuEFT{1op6t>3?O-w74|>{1=XZyL;Q8=!I33;%AA!r@oA5_iSr@4G zyCbX%4}wR-Q(#{>5{`%0!8_r@a2fPGl&+@qFO!+j)a%OscStMz_g!2AntrL^T; zV14Mn9JIb2>n#G_Jo6>-`{ZiuYl9xU2p+h0$0Kh z;d=Nh++0DKY`!Dzu?w&=oh#*JQyAgJHcLX z2)qzp32%gV!-wIs@HO}m{2KlNcdHxQvkyE3wu4<^KR6POgV(~_;lJP#_&WR;eh(|w zi}h{~_k@SQqhS}=8xDoz;Z!&i-UoN6AN|*b;k^lsr|_PHcpUm}@EkZA&V={Ehv9SZ zHTW_78vYKqY!K_O3G2fn;R&!CEP?02@o)yb7cPX)LBEgT{p43zb?+$e1RKG_;IXhP z>LM#FZAp^?zc6^>&WVuMPKw{s67l z{}|XEmcgsw&G0e!CHx6iY8w4)5ATEz!YAQN@Ll*h{1NVRQ1sIb_Jo6Bcwa^By#jeU zybCUXOW;cQAzTlCg;kry`u2q;cb#7r-mvP4F(b0KN)8 zfM3C1V3k8+J9dP7!TsS8@HDs#z6L*lU%_8sl|%6ho4}T^4;%)|;AA)xE`~3|)$l9$ zE8OC+SYJ(8A07Xz? zA)EwnhWEn9;BxpG{0VM;c&vXXSP!;^U0^?WE}Q_bhj+n8;B)XT_!;~OZr+l5VLjLk zwuN0_KX@*j0I!F4!AIb8@N>8URy-osTOBrphr)KS3oL=2y3fbmGI%wd0q=#6!R7F6 z_!;~WR%sRe?E?3Ohr^R#FE|vI!6|S)TntyjHSk-Q9LajaV%P+>h6CUjI2qm!ABM}| zoA6WkBdmN>tZzqH7ajzUhNr;3a3mZLuY-5Ohv72#Cj1os2rIXyepnZ_huvTa90tqa zWOysQ4=#c)!S~=gxDi%q6YJjz)`d-BYq<5%(Qa3`H#`Kkg{Qz0I09Y*r@~qA0r(Vr z8Loz3!C&DPZDTuX!uqfoY!AD^zOWQt3a^2;!A0;FSoxS(&mr(=crxq(&w&@f%i%-t z8Tcw(3#+z^{%gQucmQk(kAq!cZ+H=$1?R#?;WD@iegeOT6^@PdSBJG>V|X}h4^M|@ z!_jaeyaCyiST+j8~zI}hVQ{I;LmXL_ObpQVI6oNJPMu+d%_{`B6t;?0q4TU z;S2B`_&NLuRz4xNqXygy9srMm9bs=c99{yifw#kd!6oo@_%Zw*`kh;!x3-6S!UJF_ zEIujPwS!$?8N3?KfcL_M@Hw~&egeONf55Fe#Cmpx_22=p6+9810SCbI;COf~ybV48 zKZIYwU*Q%f$NFo+`mh;18g_<#;0Smzyb9h7?}3lPW$+F7Z}<)T6K>g&_P~13-}&)& zYYk6=XTX7QG`tL62k(Fn!l&WO@O`)r{tPR3iuLXQ_kjDs!{PDpRCpE~3CF=H@K!hv zJ^`PDufsL)Yxq0dvNQbz>%pe*DA)m>2}i&(I2qmw?}LlrOYlADIXJu>Ho_{WM0qDz z7dC}$;7RZ_*bkP%OW+iEE1U-(hs)tx@Kg95{0nZ~CAMofxHmi)9t}IeUT`S95Ke+O z!+YUk_%d7#zkO_SZ1@md0$+n`;5YD3xb_JPCUSU3gFg!jXxa3%Z{eh2@6TlR|W*a_BwtzdUJ z3|<7Uf-~S;_&9t4z5_ppKf%hqW4$%tUhn{TBoyVMo{t4uu!PtKkB;7`_a@f?M>9erv)8 z@F3U*c7na(Fjxj}gm*$uYUK7l1z&>i!5z+u`NeQQ*b<%qyTgI-eCQdF?Egntp?{RO zg|%Qq*c^IVB$w+1`@{3#6gUGu441&y;2QW1+-*Sg+W;O6+rm>|2^;}0fm7iu_yBwg zz6@8x@8Mr?o3ms6wO~Vd7(5Q13j4$J-~@OboDCm>OW#? za1y)`&Vi4@=iqAi??KV;Gs7aQ4v*XuHi0c+dw3e`56^{DVVe=r&q?q!sHua)I2j8k z!&~57_!xX1z6n2p-@`v)wbJN!SLnIeJsuB+t>MYA2RsK(g45w$Z~ zIx^O~6RZOdfUV$(usb{(dYX2(dm_96-UT0qOW_;vWB46R&W(Pyg}cK>umv0hN5hHm z26z{I7%qixz>nc~FgY*QyE|+ITfpPt>2M&t0A2}ihI8RdaPjEq{}cEP`~&WCe$1~A z4}z`X$*>1J2VMX#hd01G;Y08l_$vGWeg$v4AlCl`TnSghFX2YG`Iu;51MUf%z?QH# z91O?6E8ui^7hC|Jg|EU7;8*Y$xch~%9c^J}*c%Ro7r{yJCO8K^0++(q;TqWEqFB$_ za3m~)SHc_Mo$w*}415)S0N2Ch;^=={xI1hFTfpPtX>b4>1uug)z&qfp@O`)r{tWji zi}jxmC%|d&e)v61#zy;tU@O=jo(B8FbKy964V(qz7*T7lu3HUsG7k&zVfEC8Y`nQGG!`t9}@Co<= zd>eiWe}EOn;}6z?`@%!uF|Z#T4$I)xa0a{=E`-m)Rq$i@E&LN!n-JTxD{KG{hHYRc z*c%RmWpFaQ72XG*gfGH(;TP~{xcOzV9XrB0@IZJJ>t!SHid8YWOi+2Y-UU!-|*3_Ev@4 zz#4E@SPbjIM(_}L1UwqHhh5%kVV9qa;2;50Z3E`l$@ci?Am1FSeD)>j?w4jaOo;X?Qq+-hnpw+pNf4}z`X$*>1J z2VMX#hd02d;Y;vc_&Gf2npp3V@I-h990V_bSHK3>#&QS2Hn1}s4ljaN!0GTV_%M71 zz6w8pU%_8sm1(iw9pPT^0N4h0fM>!%@O(HC-U9D|55R}v6L1N91+Io)!i{kA>tg$A zz&+uCunjx~_JilaiSS0a5Izszg5SeG;jY)mdYi+x@Dx}AN5D(qHSl)$4g4KeyCM4B z1vY>O!?y4gSOU+56X6Z;F8DB93g3Vq!|z~)>9PK8;qI^zYyppl{o#3V0$c)Lhabc5 zVZ|F`J=?=Q;Q{a{*b(-Hqu`bBR`?)X3g3pG!=GW5n_|5?!}{=Gcns_c&w}T{%is<0 zZulsC9=;7fhd;wAH^=&Sg^ge<*a`N7qv7Rn7W@!?34ey0&xrnaf_uRu;fe4Jcn&-t zUJj?jyWt~n8C(TFf#1Ulx5WCZ!`iShYy~^Quib3H%;bm`QtKZFoF94Gw^#;AL<&d0ZxOr!};(jxB|Wh*TIdj%I&dT zJHfiJDQpcp!d`GFyck{$Z-MjR6Yxd&F8l)i3^%_cwqr+lAZ!iKfCJ%Zcm=!}&V!G` z)_9@@}05%9pD~tKX^Di z9-a!%f+OLja4MV$?}LlrOYl9o4sL{1?uzZ%8PHMVRP6To&>wYv)~AL3w!`Bg0I65;1_TMtb9+bcRP3>JOU1dH^Il?JMd??)4kEp zL9jC%0ms3c;XUwSxCE|*AHa%pqu-ivAJ`W5g6F`i;f?T4xDKH{r*y>I19~EQSqXbJzx+4Ew;L@O(JItf0RqfmfTgljH{S zZ%3XF7sF+y%Dn(zF?Bq9m;A4ge<1&7_#63^=12Q&P1UzMYzSMxBTdzFG(65!J*SZ0 z9l1aGgWyo|$HB`@m79iqBl2vsQj$E4{F15qUWMQBn>TinN1|EyPGxDj(CCCGiOHH+Nw5j%82rnW3DpU2{h%!K%Ptf1Mng8pNA_<)%!N`YUIyN)wAAIJ>S9~$xj}N^%R*ZU&oYP z1K5!KR`6(3b{&vULGEd)p1!8a4}gQoA8l%V#v@N9|2lXh`S-zpnX2bW5z*7N*+Q4!HyQonbffdyzi~c?=wHs=mwN3^)tkZ_58-Q|()heg#}f{#v-sl-&m8 zUyv(3BE8n5wyFI3rs~}n?q{l=*02-oX3D+~a)0Czru>aEEmxdZZP$UTq; zAP+_!ZK~c&Ow~65UIVX(bKpGqDtrTeXsUhRApZcjT^RlD0PC2t+Z(wNJPiG*rq-($ z`o3@g`NPS-5P1UmSD1Tfe?qxE25}t^@E9{BB1P(zz3XX-7$e#jlgLlIDrrP-!Twc@OAX>Bd;}8?hCjPeT7A_+?J;Dw}HE$-xD@M zzdt-29tlr^onTK>?dgYnHoOpyg;P!0-HbdF&V>)aXW%mUnyGT{!B5bC4!=kL8?5}K z?A5PZn_AE9;EtyJ>n4ecnbMFO_d*nTuS~ZIEMW3#ir_AW~$y7;49?6YpUJ~Pl;;p7N+dBhP$AzW6EwH6_kDFSLr%m~N7Oo)wEmQv2pkHh5q2oUK4ak2WSA9DAJJ{Sk zNscn*w=F!*tgZJpP350~+#7ii@(ASfO_je0UV(m^SvyH?LcYtC-M#RBv$n1`;4APA zQ}up`ydEZtqkbz>{ZYe|znZX)SzE_L*bE*<{tF{n-?Vg7`A3lcuDdZ(^C0qs9nkv5z`9JU{^nW35 zwj{Q98&mc>!y@#>@L+ftJl>Rj2jtH14D|hx2f(SL7hJN}CPPgwEU=zl9y`8y%kfqSEGihK-mN93-^y-jWJfo275XLAqT-;@1cf+~x2~&29k(a{trrPxm*JQ2NBAe) za#^f@CsXUWE8N{w`|Fc`0P>OWWY~rLUda8BhasPfJQjHZ@>JyOk?(?!z~|sw@ZYA| z^BMAY$Uh-hcrNB|ZmNH`L#_?$px+OZIDkw?u^_6xdeF#aw+n~$m5VFo0SxY zLcZBlzs^Fw8+o3o@$@kI#irKpMe<*PAEN&R`E&R!`d{Fm=qo-S>)Y0pza5cxf%VWg zL2e3Lp>L1e!BqQtq8|WEzEL|3UaT`A?DmBKkMrJLvyo%Fp-6 zzmZ>QdDK@m)xMgh)^ktv_2B+yjU+h)`Ec05l>Mp5XTSmI2O|%M7oaag9tW?1*TcI^ z`JIdW09=Uv8RTVfCHi;ahv+|szra7>)-Oc=+nef_onUSB`ye-lhr*Vy1MCcYnriO= zI2`@Ca4h;O;Em{SG1c$)AwP)x6!H?}*OA{s{sj4R3z5gd$?#fuhpF;&kmtdN(LaT}1ip;^E%-kAkKj-6 zSGeU%(f_ulw&xD82z`Czec{3IFn9ty8J=OPz5U=2^dsO!=r4m)P4)9lrjD0)qQ4jU zVdN)F*)2uC624FVzsdg+{ZFvMirAhirq*vOSi@9(waKr8ydUx*rtA+lRqqMtyTBgg z_aT1>`cd#g^w*g3a|7}$^6x=^ANnWJKaaf9RQoRQ)fae*?aQeuF8yjmTAB zk*s#^Y)Zcy+!uXQcsOhePl9K_vrLsAXsZ4T(2s+cqrcOX-95;Uk-r@M3b-2mr|@g| zGfZBUAGLc6xHH_tl>fS>+Hny2masMY9;WR2Adevb67&<`_2_59Iq*UFID8hq2H!X3 z|0DPf`VGh%VTF~l(|T-f%Krag=`O>qs@gVyQX(A!FNz=`NOwp`BPmFzgdm7C64HWn zBPl5ok|H79(n_PWQj(G)B_#si-rpR*#&yrR*1Vs!&N;@pbd!KDGc9vPja-*sF3eKa zE6LUPf%V30X1x{rav;Y?jhsJ4p2m6Bm&vQRl|S(~Px5lq$a%N;$ohYL@le=L#@C`o zopdAH?ef#Y= zm{T~9dw81n8S99-n3mc3Cf{alHeoyVyHS%wKIdKjIBMkj7INpPk?VWQBcevGA0tn* zKVM#Hf1UiZ{a@wNQ4__8abEu0{v-K?V_`o*)X4m)qekXQD`$@ynWvy!CTe7!x8>UQ z8_KQi_mRJh8b9*)V|j)Aqr68xBA?^UsF67y%5jcIa^lGEOQS~Sd^Kw1+$?ed`7OB$ zKVWNi;~-AvJg(pt?&nEf?tj2Mi#+BU4pLvj{ zc$s(jA74BX=6IQ}GY^Zg0^el=HfKln<^Yc36wcufT+g5QD^K!I-sTg=JsIYHg}K>; z?fC^qa27XlA5ZWK}K;Lf`+GmYJB1d02?G`4Kl?GxR272KMHcoXUmVz`Z=l>-?7q{toA-VGb5&Eq=sy9LTYp$)&u( zhm3v8`(t|MW(ii|M{L6$9Kwm5#iiWD{rsI*80WV4$=8^h#aM}5*q>uKor}1hyLgP3 zc#pB}cn{3W(tMYV*@1mIhBLX8Tlg!_@)n;n>D|zuo_SfC@3JvFurJ4OCYN#xf8|-; z;&Udwr=NLQn(wkPJ8%qVat*ihAphWB{Fm|m3BCVg0hVD6He?(2;1EvWY%b$wp5b#Q zydQc~GYbo`3>&f!hjSulaVa-(A5ZWK?=$v;(4U;SS%Otqm(AIk{W+F1xP(7)A5Zcc zAMwS9-aoUj5X-YRKW0bv$4@hav;ZXCf9QpkMmFd!`T1oXGZ2@Y1UvPe#%}P!LPZ1Yq^uh zc!~EI>q(d+IWsap%d!?f=4b5Bah%2F+{QyZ&pV9ypMKWibH4I4>}O*kHe?%4;A}4A zX71-nUgbl^er67)XC4-3Wq!cH9LJel!j0U+OT5e2&qHrYW?>OF;iv4$VVuOdT*0mU zg{OI)j~F*b%>VzrT1sYOK9*)R*5?wg=WZV51>WW}ridB((la+puqL~(KgVzh|KN2# zV%*3tC!@b7?9PE4$C>2t7%dmN{6I?f5x|aw6w&Ik)ftPw^Tb@`bpe zKLs-~FH5o->$4@hav;ZXCYSI>?&k?!mzaTh_!g_O9$T_A`*RFu@O!T24j$rJ-sBU;Pv|`{3k$L=Kj0_q z#Qq%1nf!s9xSywZosStWkvW)^1z3_*SeMP&nf*D2)47Q2xtm9Mfw%dLi4upo(l8r~ zumbC_2|KV4M{y39aSMOp8UDp5OpqkZQH}N3lHE9%6F7$}xQz#SmVfgp6D19OuQCUV zu`=tjXR>hpP)_1JuHp_J=6T-cb0$e1&P&JQFNIu*AFw&Qa3H_p1^&(dm@`EzF82IQJE1x-#oWlfJi)7c$hc`je=25XL6&1JHem<$;V4eyB5vRw{?03W zz!zQ(b7Wv{zQt;6z}D=+p`65dT*Vzc%=5g>=S-3|%#n_{Sb|kqpRL%PLpYIhxrO_A zir4v=@zRC<)O>@5S%G!fl%KI5$8ZLh@JC+Y-+aPXUJLzivLZj=C+x)j9Lt&ffxCEw z=lB=@mp=4mW&xIA4K`#O_TUgs;A}4AW?tqaK4ZcRp+61lun9Y`4@Yqt7jXmkuyDq3 zZdty|M*NgLIEdr9fNOb>r+J^TGKHSx%)q?-kgeFALpYIhxsuy?i062V&zSi2(4UqC zSeiB1h@Y|-NAPPd;9BnFF<#<5#>(vZnSps(iq+YWqd0@hxSuC@l@A#=i|1w5H$u*z zGuVgOa)n%wrC6WM*_r)0hSRx->$!`^d4ae2jEQoG{#Timg;}1p*n<-}i)*=^zwk7# z^AY3b3B6fakRPxqJF*W)@oRp^HQdgF{DXh-U&hND`v1qwEWk3X!G>(Z9vs36oWm8| z#)CY|zxkAj^7%S22aB;X>#_yAaUjQWCO2{qf8(FL$C&v;e^RDnP8MTj)@2KJ*wVtLl)$Lz?yoX*AE$h|zt z>-?7qiiG|&%)zQGT{P@BWqW?XDV)z$+|GmigMaZ~#w+IenVAJxhBerbZJ42WxW72x z<%ev|?i|eVoW-Tw#Pht#CyZYr^rdDN7GycrU_-WH4^HRLJi_z5#iva8R_J|&Sy`Cn zS&NPN2e0uTK4*fG-aj+50L!oj8?r6?ax|xNF*kBAPw*-qGHxkzFcWLA0b8*fzvpAV zP&%BGg1Pw_`*Ibxa34?b3hy&^nQ(4$re|)JU`;k;D|X{V&f-#T;y#|>74|C|`bTmB zf8s%&<^^8m3+2qu^eoPbtjAB-fxY=9zvg#b%^f_%v%JYCj9)&?^D;BD0L!oj8?p_1 za0n-GHkWZT_wyvL@d00`5avnA*I9sNS(A;~fnV@TPUZJp$6Y+mKlu;iyzT4649v?? ztj>mP%bpy;$(+yC{E0_+k+=DrNh*eU(lHlHuqx}bHM{W(4&X43<^+Dj1^j`lxPe=_ zllys?zw<0_@D3mH8RJ(9&zFj?Ge0Y`HoI{!$8rvrb2rcP786zueg9()7G@RJWpjSP zp&ZX|`2&CCUjEL@{D-lsggKHi7mKqpKVUOK%6=Tf8C=32xsNA#jgRj^nSv~Y5VmfB$n|zyf*py#z7{_xaS8ywTDFfk8x{--sDWjoGi|Ye2<^71AB8Mr*H=6aXGi}08jB6A2L(z zFkc?N#j32w7VN?S9LsrJ&MiE^Q@qABbwY1ZR$xtj#826i!?=UL@-dUW7tYPff-K91 zY{MQL!U>$sW!%jDyux?h4}JC6jGfqzqdARh`7OZSmh8@< zoXqdIi@)&-AM(Zep)WPF@=aD^UAAO*4&`Ki$Fz9R zxsiK$f>-&FaX$>bshF7sS&p^XgdJF{VYt5{-)D1nVt|a5Vy@siZsyNC#G8D=_)WZbW?^ww>tFZxFvj>NA z66bLhcknRJ^ERI|dFL?C>)gWqJjLsL%=lfrCuU(Gmgff?%1NBZRoubDJkQ%q+cos% zWN}tuJ$B_Fj^}JH=T`p8KX{Y>F=4mRn}+#VlJD?Ce$Gjp$5q_H!+gm2-9t|*zRHZu z$~-K=Dy+-q?9Bcg!|7ba4cx=ud4&)7LXR+CO1{nlEX$f~%=YZfk^F`Wxt_cE8!t1? z=lYq4Z?P&rRsO@*`i9=OScM(fi$gh{Gr5?XxSN0QK4bR_ zJ+Cq=3$iLZatOzB1{ZQ8ck(bV@^3z7(*B`8BXhD68?hDpa5yJ$CKqxg*KrGX@*@A? zbEX;)=E=oUtj30H$-ewDYRt&zo$(v%^P{GZe6F~>*8WCrvA^5?Vfh^Yw0=u|AU}&5 z>5DZmm?UcC|7&|CYNYQqIeXMNkv|VhE)g|yUul+)8oB-*`ya?3%FX3Aa@VMl^ZLuf zqejjf#c@$1=S{UgPhQD&)^|jWoO4#b5;bzp4c>|xIVbj@V7#c2=Sv~KEWg40Q6uLS zj~Y3r6sxiZo3I%Nawxxw8tGjVHPW})`gZQL|Ev9z@>%)1{4bwdPcS%~n>1?V+%$4} zIY-pU`~{;%=6^G4#>nTDMvcrDWdAekJvopgIgvBCF>0iLXVgf~UjAbLJTFI$ zTz6Z(FF%*#3<>*5qDJORA*Yiw$+@FOo~uaINMCWj%_{tmjoF`rIW}sfXO=uKYUKT_ zvc8GC?C-OG-1=EwFI>0kgBk$*me1i}9go%fR`;xN|i?V#w$T{!H_1Mb# zXY9$o_6KsL^@*HeeKwbHId^au4@ZskpW-F!S9#C+e~dpoJWt}Nk?)6eQ6u-i!MrTW zvaA?2a{aqFU_jf>+mD%P1&BEIEceIA!_9O>6~wUAy-@9%+paL@AZ=XtNhD;jM3q|7otY4 zOD3n1Gss!wd~#vAOw`Ext`ar!o~pAx8?ggBb70iSbByFf>tA!O^(9oM$$CxJXH&Li7xs=C z=^4T?oEkMU#~k^)s2L;A88tG;7VhS8o{Ac|?vi{fYUKQTe8yPg!g@-+%&bu(=jUTF z>m^y)dM!4z-h^%0f&Dp{6QV}WpU(N#7jm`r&D>-C08d;0lh>{P&3Iph=Smbc@*ZA| z8tKc-JoXFNFKfLj>#zko@bjpV_t=}mIFd6sn@gfbde?A^^&R}h`ft2s{VM;l{*-aY zhw~Cfjm(jhFI&&Z9Mkehp3VFF_6QeM&=kVPm$-y3*B%h8Nd9FXB zMxN^$??;Wy^RN7jFHQ>UsiQ`&f0a3`7m|yzJS(w28?jZ?NY7{NX}u4JTmOp7qeh;4 z56|--#+)4Xv#=;@@gufn4-V#6oXI8J$lW~73sF->{yj>*7d2Vr`$3K~CFJ-~BXehA z{-}}nUP7)EHF1m>AIt5c#*YzWs61YtE`QI}Q6uMUk@rQ7oO4h<9W`>!13A{$A*YQR znI~J+$o#qGVo@XWmy)Z>@5&!WO&Iy}vgOaBCW-uc4)Q?zqvWafXUdE1uaS4y-z^`r ze^&m>{vG+5{diL&y^;A-MUC|5kl&0NnXjx|!+ssPiTyTmcl#sdukFu~m)Tz}Z|ASP zz*~IEWZ#7OUSm!cWkuFu6SiY74(BA!i5mG@{t)%m$nP_(ujeLiiyHa){F!^Ari~Hf zu>EU%!Wh#c`;qsVm@hFsGc!MnuskcX0h_ZEyK@lt@)-Z(V?Ja2>0z#vOwSxF%rdOS zhHS}B?9E{u&l&ulYq*g+d5EWZg?IUs@n(d%Q}8urXCanmZMNVzF5oI|$!`^`6vHj%Gus8bF&!hu^BtFFGp|^XLA|1FyS1}#kt(UgZzVk z@n6Q98}84{0xZKCY{)k3!J(YQ`CP>vJk0aF&F4%qFU*mSxmbc#*^NUuiSxOJ$M`4j z^M(1LCl#}>Fe~#zw&ys`;&N`|A)eiIE%}7Ej79pHf%#a5P1uqBIF{dX8F%ptA28E7d##<8lQ!qVCu?pYkC+x&N9Lbg3!c%<8ct3=`l+3_9 ze2Z0Ck1g1R12~q8xq-WRoR@f)F_wlok}@50u>`BKK3lOnhj1e2awWI(5YO=zpE2>W zFi%?MWN}tuJ+@*G4&xLq;5zQ+@4Um9%R_H+W@LVrWi5Wp&)A>iIE$OPm%sBe|6!~Z zp+6a4V^LP*`)tO}9Kdn>mP@&r2Y8w{_%GwH40F89tSrK}`5r%EC-&!9e#>Rt%7Z+| z+l;Zwdte6UV;RZso5$%O_0mQ<&owX5*Wz$oJWdojHKx_$`-mGmr8d|K@*8@N<~s zWxl~eEXSH`%(ncTLphOixs02+pQm_*_ZfRa5@)pJ$LaK zFY*qbGx4r4S6XIc5msOwe#AEH!6BT$*<8lW+|QG|$_Gri+t-a*S%h!%J$}MY?9Z{B z$sf3h`+1sIc$d$ZXiu0Y4YRQbE3h`3uswToI45%+S8^MF@3PkoXj~~&U1Xg7Y>H=US~m8V_i1qRDQ=b z{Fz62k#`yMQ0Pg<^vuJOe1{*h4L|2FPUd$0@37}!0hVP=HfDSF=16|Sg0U<{Wyj*xP(7)A5Zcclb#CwuQD4evKc#bAjfhhf8ZwW=PCZf7^g#DV!p!i zti{G`$6g%H$(+ZP+{RydhBuhvOz6+ToGi*p?8i}@#zow~J^YF7&2lP8MesHs+`7#S#3P z3%Hg$d5o8MkFm~&{^ZQSye!4)Y{<6k$>H3Z)jotOC!V_y&FCuKV3WHDCedu+;%?8AB7&R=+mxA=tdZ-oBT z%))|vk4-p`V>q3QxPd!)loxr6Pnqzq(EkdvvM|fD78|o2dvQ1?a~@Z68xQg<|K?LB zx*6tql{r|9m06c9*p-7go^!a2o4KD?`G9f$4*f4N1M~1LR%Jc5U{?;}c+Tc>?%*+A z;bSJe73N6CTzre~@Kb)lk(|cG{E_>4nt$;*v)m57MOlp>@iX@4IL_j7ZsQ@I=N-np z6MB*}BlEK?Yw=@##{L|~SzOL-JjC;S`EKaV!a^+1+WeRu*_Wd^or}4bCwP?)`Qp9M zo0?hqCM&TnyYtig;l45ahTrpN9^rZ3;!`Gk5YBmpSy`CnS&NO?j=eaXlUe;?IJYIg z;4n_&T(00&{=(C|&Loe*xoMbbCJa+;nu7k~0I# zusR#DEqih}r|>(j;Z9!W1IB$CdjH2aScDb%0b8&ehj0?-a}5(e3+KPe94yYNY``|` z$q}5&h1|fsJkP)RlqsHv{tV2^((J{rIhRYhfj{#Q&+;apFn)|!|Nq~Crsf+g&MK_O zmh8sCoWMC;!EHRmGmIZI^rqtL%+F?A#jX5>SD7nTIHx!pum!tt0LO9$7jpxT^Ahhe zM(og&glUTfoP#-@v$&L-xQ{1zh4&fz#V}8Dre_`& zXJvlCX6(d%9L;H5$aUPwqrAY|e9lDi!d$O12aB;X>#_yAaxlN*EH2{~{=zf-i%*y! zewZT-v$6=^=6n2vo!Fma`7M|5NABZEUgKlNP2l^6nOTtKSc^^AfqglWUvUa&a4r{e zIXCks?&U!q=V@NxRsPNUjF~Vz&x=gVluXZ@EXGP~$W|Q5Z#bXpxr=}BAzw%o=E%rg zEW>JS%y#U>uQ;9Ga}9suVV>jP{ErC|hdEy68!X3~{D_~jCx>wo=W+$N@)w@wbv|O; zBw>z}%*1>w#dp|%t=WT0bF*i%HIvcSadvg@0a}~Gp5YO-i zVb-$zhztxm>{mJjH(*FHJZvHQ!(n)@3tx z<^Yc4w_M82{Dr4@osSvs)zJSkv#=1$vksfE1N(3^r*RQCa1Vdy6+Yk#X~P^T`8o@* zENikcdvg@0a|t)`3~%x&6Q>Kk>6n`(S)Gm8j=edG)47D3cz|bklTVrWHT}%ZlB~`~ z9L=em&z0QHLp;Y@e8$A-LvLEw4(7WV!Z{7umc2NPlR2NO`4f-u0`D+J z#&CX8zQ){qi`CeGt=WU4IhEgW4S(iQUgR_8%M|8l#*X}gBRGZgxr%@AFaFD6x1)Sd$IehCMix<2jp4xSqRs zj2C%_&zU$&nCn$$=bL<+b@(wmus6Tt*WAo~yut^3;f>H+fMr>ejoF^PIg;OSA=h&^ zf8%97VBD;s_kS$ScUYVC_z|124Lh-aV>Z8SDxZEK4ivhVZPif!78lF=IqS= z9K-2c#Pv*^J)ED0*;$k|*nq9rjq|yJzwk7#^AY3b2z@D;iTPNHOSqTGbB6oUF(-?$ z65r=1{EU4$ir?^i9^x6^;A2+G75eM22|KV4M{yd9=MMK(;s#k9 z!mPt4?7+Sp$#1xj>$#i1@iOl-&YPh>1v4=}%dj?^F-FmFUt*?ZP8MfX)@2KJebxAP$X;9q>g1aF18UST%A$%=fR&Dfa(IF8?P zDL3-~PxA)7D)hd@49vr~Se1?0mfbm+ z<2j2(H-u}g<}k~2MXvjnTKE}OG62XGv}D&yv%~ndR(qLAjV*A!=lv%KXUwC-&RPU$DRR zQJfMra{n}b8#VIYS8`p{$XwgyUGgFMxO`6jQ@$ntBmWyU(i8jb;EPPnSD7nnr0-3+ z1S?su6*V&72Xb@!t=YwXFZ<)Un47ql*LXW>WWIm+C~Bl9X2md1!l;p)GHT?ym!oEk z5#x31+2s6kah8u7xxNxVu-;hygzc?&XCLbWIF1uJJ8EQ}#qu(4RFlN=rIgzhlT&Cd5%)!De$4Y#UQ#p@6au0vu30~qY{>vAtg?W-O zBXjXhmSc6+<0ov-&pCu&auR28G1qcC5Ab(h{n=QQm06G7Ih2$69oKRff8%vNWwJVw;SL_* zMc!lV_d-t!zRrRy&pP~sojH)>IfpB`gGYFg_Za(q{d}DTS)O(H2|IHj$8!a@^Dr;) zE@OQVdS7BD7GOEnW>a?J0Di^UT*2);%nQ8BSatO?6AQ2$YqKdkaR9&KY_8yT9_9tc zs;8HkSb*hNo2@yR)3|`ExSfZ1hVko%zEpgj`B|DZ*nq9rnI%7=XE!_c3eS(uag`6f&9L$+jBF5^b-U&36^CgR%ad7XJa;JTYkpw?9G83&M}$sE0c%HYJxT*KatSrKEtjXRS!6}^2Rou>l{DU|79}|8O z`qQu|E3+P3u?L573Kwu4ck_2%#CXm1 zGaHMtGV8GwdvFRDa0~bG1h4QuW48#s$(f!dScP@joSoU9V>q3QxSqRsnekeN-jvM1 zJS@p7Y|f$liZi&7>$sCgd4ae2jEP!>InuBQE3h`3usy%v2!74)xQ0LTC@=CZW3~?c z$(WvbSd#DXL$=}P9LC9<&(-{iM|gpE8LLg0<0WQd0hVKJHf1k<$#1xb8@Z3Cc!N)v zux;pnl{s0N@3AR6vJXdcDi?4&5ArPk=2Is6R6ldD7%Q_bTd*q!aXe>pIk)mx{=u94 zj|tm_Inpo(i?b>lunl{11gCN#H*hac@;d)zg7*5^knuW%^-Rpql5Eb-oX$mD&s{vm zi@d`a9YaqdreQX|$?~kl#vIM5T);K_iHCWUPnhVl(4UTZSemWbl><4BGr5Etxre{; zPu^q9PN6p`(=jKDu`=IdQ?B859^x6^;A6hnIrODvHWpz8)@N^y;1sUm72adaE}n<| zIFeJjfNQyfzw!)k@L$I58qQD2Ow7kpti#4^#}S;wX`IakT*_m-#Q&I}TbScz7UC!D zz^}N3>-ZB7^BiyS3FCJUJ*k<61zDEeIDlh0gNwO=yLp_Kc$YDHgx(}f%N#7qihPev z*^zxXl2f^WYxpyd@dEEK#^+(4q#{jJvp>ghIu~(0ckvi6@(!Of z@fTsPSDBq}@@>}P$Lz>2ID%979anHO_wyvL@&V)Y_MVu5dH5EqvN1npFOJ~XT)?&5 z$z#04dyLg5%#oZKn2#k`k+s=`?fC^qa0=&h6}R&c&+rBx^Toblu2g)T`B|FP*^sT- zgF`uqi@Bb=`5Q0uKI8NYbEM#V{Foitm!mnIi@A||d4gB@ka7EaZf0gdmSZh8;lKgm zzOkIiAGnG8d5YKhnDGXNb5ipSmLC+>YqBxhvo}Zb8{XhUzA!kPQ;1brpWQi>UvoZJ z^CuqR1>RwdA)zNJUt?~*#cFK8*6hKdoWyNRH8h-`iTPQE@A4zI;}`srQ~5pDaTkyC zPyWN$!$SXx;la(^$CJFqM|^Qaxc-04!a^+1+WeRu*_Wd^or}4VdwGJl_=L&640EJq zHWp@CR_BN8&hcEp)%=M^c!75qV`S(}%Ga2iZ?PI1ur+&dC?|0qS8)dq^E_|!Ig^YE z^JHfczRmae2|KYr$8sir;3n?pDPHGe#v2{_Q}YcLW(C$^Q+~#N9K#u0!reT^OT5Qe zV?uv&W?){HVs$oTTlVB|PT_Z4!=HJB4;g1{=+DG5e3y;+DSL4Qzvcq2z{AGwbwd5w?w;>6JVKW1SGR%Ttc zU{?;}c+Tc>Zso81gE#pf6HfB{%+8{$#1Ghkm=orBnQyQV%dr-lumk&W6lZcd zckmdm@G;}f)z56K%zA9a9vsFgT)=hQ%~OmyFZ85jRu*Sf>l_T&DojR7l(7ovmTqV z6Z>&Ar*R?IaVM|y0plzQJufi>^YATJV_i09XZGiO{=(C|&PR;?&)AnUxRC3(lSg@hw>f-e=%2{t zJirtDlQ(#WNmhmXGcXrRu?pYkC;W_kIf~!#d#>frJi_z5#b->gI?VGj-(Vq@V@-a< zPuY{hIEiz)f?N43PxA)(%Cjc0g?xA=td*N5j!&0H+XhHT4j9L~x7fxCE&claNZZ3um@GA~QA8k@2m zKj#om;A}4AX71-nUgZP6v@y()fqD2AtFj(junPxpEN5^rH*hzP^Ahhe#*bl+BuvX3 zEXK-g!LA&{@tn=&+{$112XFEz6K@K0q+@QDWOX)TI}YMl&f*eo{ zYq1gA@^g;nRBq)y9_JO_W$Z1XCn?i0CyTK%o3cGW=U`6Zd~V`Cp5PVU=c`-89NGCM zYp@~Pum^{5Iu~&}ukbFPGR3yg_ZqYFZPsFAwqq}j;6%>ma&G0X{DU|79}{j5bEIKW zzRzat$swG;Ib6z3+{Y9Aiw_xlN9aw?49vyitit#C2|KY52k}cz<~*+CHvY;pjQ3NR zCnYm6A4~BaHef4uCSYTJ^DaER+#}@3u0i4c7+{@p2g%22acj(E=LM+eP{Foitm!mm@ zi@1S%_&cxiKI7~O{VDi5^RYB*@FRZ8UL3)%xqxfAlgD_8_ZVw$m?JqeFfXgK5!eJ++@HP&NGcH>}9;2f^tHXh_z{>`UM^lRvU zl{r|9mH83duservBIj}?e_@P+p{Eeb@EtZ_D|X``{=gr(muDIKP&hv+Gcq@eu@&31 z3wyF3hj1jn;uOx{TrT2T9^rZ3;!`F(9OliyTrAGYtjkZ>iM=_TlR1woxsAW_3~%r; zUpx}#NyXQhpQTxyAF?$^^Bb<^P99^dqoF4`GcYepu{s;FEqih}r|>(j;Z7dsWhOlq z`qMHKvoQ|~u{g`H65rz|?8>2>%$Z!o_1wife9DB!!+ftWD+{wcYq2rgu@{H)46pMs z(GapN{1{?8HCOBn2zQH1Vk4^X~dvX{ja}Jkt3lH!Vukj&YI34Cl z$v0SlWmtm^*@k`jCC70xr*kfsaWnVxB(L%T$!&~c#V%4|AP0+>@3DA ztk2f`zsl|gPK$Z}|M+aXY*A{n-4|ObmC9~=)8;HTk`9%ySV~vB*Iu=Iy7s2)y0$wj zad5gN2`e2!bR$Gzb1I7viX5Ga7NMh1sYEM_-{&*m*X+(U<@_K2d7M1weSN=k_nn#V z%v`&(X9~{5hjBTs#dq-&{1)r5`PXLoT`(Po;7A;gcVIPc#!qk`*5WC9XjkltDVU8{ z;b<(z3Y?7#aXD7uJGdSHi^s6Zf6aP4g)idkxD~&^AFvKj|He$;9(!UI7Gnj@#)Y^X ztMDD%j*a%3`6pl!o{tydNcjSccPZ4lcxH_%d$9f8%aEh;?|{0rm@?iy3$s=Aa)#cn8kMC-6ml z1OJU*;Sp?f&@8_tcERC4n9qGU5f|eI+>AR^`8!3s@C#M`-qb$IkC2a%V-A_}Q&ssp zL@mgz$Y+zglKWv6pARHoNghESsm57Wfhy}$h!r>;@5hJK&hqz^R9W9=aFZ(Q^|31R z*@3$#-$VI9@{i=-$c+x0>6@xD-vn|;Ro1VYD)a4$X{yw_kUS8F@%c@vtWOAM;XiQ& zet=)%ag0A=rccDq*cY>L7>>juoQQX*r(4z>a;18PW&M-9obuJ=*C^je{s=$E!}vQk z{n4!F+1Lj!z{~ME%*Rr!z*$&{Zuwq78=jIZJbRrbdl__iv4XKM@Pd+=xc4dafQ z^*tS1U?=Q}8F(S)VgUb!<#;#VkCpf&K8LU4e{eVM$K%-fC$pX@I0&!B(O87#_;;L- zFW@?S7eB=R;4b_U_u^4Jj;H=?)+-TH@nXCTuf(hI2D};lScIimj@bkGJC@T#i-v z4(`RH7*}i7rzLjAWV{%M}&)X8E144_=7F@Me4!H{lN4 zi^nkjxS4MoJQw@p<#+>*!%27#K7uQ-8n<8#?#CX#n&l40t8o;L!w^oxIk*s);mf!Y zKgPZIGoDgsmYay@U_Ts)BhZH>I1OjvgSZ4=#MkiytikWF7Ek?+^}#Nfg4uW#j>Za{ zgNtw_uEWh(gZr@#oBnQ=-w}Ib77oQx7{m&kgNtw_uEWh(gZr@#oBqM_u{UPnP#lFp ztiUmVX}h$II|q z%)?T=6=&naxD?mnCftT!VNASPZZqtFJ+VJthS%bLti{B}Wq8sd`h4 zb^H{|zQ0}8Tx=wNCtLnTuABna(N^a3^+}X>HzrzQC;7X@s@xa%CMS~zk%y4SkPFCV z#GPc@=pRc{6zrc^}!5b&RQl+sN`Yuf2Tv zI?!IebhoB`R9T;n#CecK&L-!ObIFs* z732lvN^%u>9eF3YhHRZ`mKUe${vaoj)5w|Rq2v+dAi0cONnS)=MqWwYNZv%=N8V4a zCD)NV#?v0E9>3&daxQrkxq>{MET^SCoiwj)Q*41r*cH#i^DzT2z)SIR%*9dY$8k6j zr{Y~W6BprPT#C=&i}*6WhHv6F+=;t!4<5x@jF&dlc03*1<5}1TQ_$(BhLEqqYf-vv zdw!#_6vKE6-iG(${kRYx#b@yad=)p~JNQ0+il5^FJdAdKDC16lcsl)1b8Leh@H{*p zGw=fZD-OdP%*Amy9z!@0@4}fl4;SE*xD;368eEUBqut-i_Bs8ne9dp~5Bb{G_9)6@ zs-5NXZ`%~l#5UL+dtnNu;~*S@SL1a!8uM`img7vEix1$#xE!BFrys8(zk~1Nzi~VM z7r(_L_%r^2vGlhsu{HL>zL&oSh3&8prr-d)5QpK_n2V!uJeJ~QtiZc)Cfe6a zX-DUJxr)!%;5w|vt+)+$;TL!ikKix(8#d*-*aF*N2keD?u|NI=2jLLB0Y_p17UCql z1@FcC@ezCspU2hsDsI3n_z~9NZu}m9z~8Y^W7F>?U@Po|oiPQ|aS#r{tMNK4z(Op; z2;PY^@Ls$hpTMW_S$qMjaU*WQkML9c91q}OJVl=2^m^X}6R;I_!=9LoX?Q7Kj>GX9 z%){wH)8=7;;nc)-iHt1a(otF!nOD=ZozH16Zhix_$&T_&E;ocy8q9_4tO@6kEwV8 zUWCK&YRtt^=*Mw55vSrzoQn%ox%qya{1mRiDtt|qdhe4z#O-|kHF+=ojK{Hw-016e zH^WZY8GB+MybuTC2+YBe=))2W;S{_T@4@-F5Ff?o@I_pU>v1z~#hqA#`|%JS!(Xv! zGqe3Iunl&=F4!IWU9#W)zRz^m~(EWko6#V}6AX?PdT#7bO*&*1a8 z0pGy)@k88>pW?T80DrBds2kye}@F4z#zo3<1+93{GV|(n3-LOCY1uw=He*y<2WqC z2v*>9oQZRB5iZ81_zbSYYTSgIaU1T$Z}9*g#afI%llH*&coufUo|uVQI0%Q}4LA~m zScbRbUHAY#jF00}_!6$gYTSq);||=7d+-1rMk|r?0h{BQ*af>|U+jmM;9wkvSK}Bg z!0}j$)9?~KgJ#S4St6|;xYUk8}W0NCfE!Uu`QmB=U^}F zi|IH3FTufh9o~oqScqYqgm>dCoR1IUQ@9-eg|Fd9_#fPh-{Y_N2PU*O$44tX7th0N z9E3TTi$3(@WURnBI1eAgC-E749$&*Z@jd(iKf^EaTRebAu@?Wp*fwT6TViYMgq<-N z(=ZFO@hZF)Z^F@7j1zD&R^V*B7azh$@JU>XRk#k{#CPxm{5S5#J@_LY!&Bu4h*bRGPD)z^V@Dlth4#QD61`9EW6*wLLfwOTwK8TOv6Sy3o#Wh%k)wmJg#}9D_ z?!vF|8$5_dFs7YpuT!uYCSZF!3;SRSW?~jzikD*!=AsY%ScVb23uodyT!4?@WB4?# zz*q2J_y)d>Tks?N9KXVE@c;4#q3+8oVBT z=*J+I;S{_T@4@-F5Ff>*_zbSbSMW7_6W_xRa0l+fJ-82Ru?}P9od9j8cx;Ouu`Bk# z^Dz}Kz>9DQ4#n&7CJbU3PQqJoCeFo0xEPn>Gx#FDjBnw)xD~hIF8l(&!SC=e{)BaC z$-5QWPED{GcElt+SCwb`RC0g39IwP{@dg}+<1vI2@m9PYXW$&XA0NVHxDr?6EBF?^ zi#xFfzrpYDDAwX17@Nd-hG$?W?2J9IH~s}L#u1o<0W88>@HU)>3vdZ8!&h+wzJ>4N zPOQN_xDSuvuNd2z^8{OCd+drmupegN5FCov<4stAg*X+b;S8LE58^^xiL0;**WpIo zggdbY58@Gw>teRIF`k88uow2l47>oZz~Oiu-iRd_!l^h7@5WiU5Ff>-aRsi$_4pRP zi#xFfzrpYDDAwX>=a}t31KVOp?2f%K3$yVG9FDm-3QI7AQ*j#Jjk9neK8mYw4Ze-< z;cnc6`|%LgVjVW^YPPopw!sdVjA@vK**FA;;wT)06R;fb##y)!AI0Z!HGYgc@N@hM zf5c1!8FXoD{wfD#(a$6WV{Xkjtj67m*caz2CMKLd>=o>&+z~r##6eR z?P-E-u_K;`=i^0q30{jgU?B$a7Q7Ab!TI<&K80&>J#NOW_yvBANAPEiKi6!}>DUpI z@O(_gOK>n=hc{v&25~yxiL>!uT#QR_HNJvx<9oOZzraIy6k~gs?TN?M*dBXgAI!pR z%)wk7hvRW7PQ$r)A3lLk<8$~TzK(C<7W@cz;~qSSN3ag9o@P5+VrxvouGkm*;UFA> z*WmRy1`BW^PQ^R$ZoCKQ;}iHaR^dAQ0RN5qa6cZ!TC{qZ?To`jY>Q{(IhcuAI0%Q} z2+Y9(EW`;|j(6iMybmA1CAbWq$JO{MZos$jUEGN^_%-gugLniRooCwPR6GM)Vi&cM zWp&5C*bgtk!8i=B##|hQejJA->hc(?oIC}mk-3 z)>hn!HF$Qal*d`t6{>tkUzlm~gR10DE;PB#MJDgLSezJRJu%SagQ_g&R7;faRNCtI z{9>KBds8}7zExDWSZE!LqWeT6M!}YhFD8}xx+QY>MuRGhFD8} z2<#eS?YAf!K8UsChgYs4R(}}d8e%Q^a@RG)>X(&p{*x(ve#Ja>XvBz0b;KF3zBvEHS*64F_tcGqZ6h62(s>3XL)*WVulziPeu}3 zSeAYLmijuq-m{n?#tO-Z=1TeJOh2anFgNw}9>5GS)*UjUd4}lJ*K4pDOntouJ9)m0 zXueZ)>IdcgGlQwG*FGmdCL@|Bi%xyL7Ma1+*K3iJUyu>a?)rLdaLRRi_1fU%*U9$% zptOg!ulBuWF!OILeS?!fkP*#gqO(4Qu5z8f_JL-Iv3ARd=Eb5@zj1xHVCJvy+?XN8 zIv^vO3q`H}i#T1f?pJ5}YFB+--d0!E_xUt0aMjPzn|*sQ%PVl@_EKN7yS~1I>8@Yv z%I8Xb%_Br-ebO37*VlI=oawba^<4)i>-sKmWi8)b-|d<88+1C=W&2ZQITe!A;~$J{SBZ-?vQz&P$>+K9KFJqI);k5QFMn>y z?hBmx$)CZnM!V+MO0r%boc8G^dAcj7NuKA*mr7nNS^ICD|8U7kvW!BqPjXwy+9heZ zzE7${lKhL2wZ2{J%eWqrn)Q9sG#NMT)!bStIa~5Ml&_cUm+{NVA4t~0Y+r(PP_mAj z`6XCQr7zdJ3bX$c?E7my7R~-jur8DGt6b9uBnKp$_D!&+OP(mXt^CuwgXrVEo%Mv2 z>!4j^jNEVO`<^;(>bJA>zBfs7kn-s1TUy(rrf+E-VR|#amY(G$TFvEJp@Z4JM5_~7 zXA>h!ik^RK>m16>{90R=O4e~F=SkLm?d01f>$*F6k>n&-j-G##wL!{t+4|h0%YR?8 zKKtmPd50(K^twDV^s&B{a%XVv$Mk1bW-$G0jVHH=amqWH{>)W=K<1}E)5?@8&h;R% zt5e_fe{Ee^*C*4J^}NuZQJEpe`c>wqd9r-q%x{&eTTA{d)s;Q1>zC#! z?_GZzZswot%DrU%nrme`Xa1||Z_`cvYFF0fwdf=Nu?Obo%38j-FU7Ri8duixJNreK zSG%&7C#6Q0C%dwi4|QeT-Vv^>kUcPon_F&e((v`KmBAsGc|H0Be`W=uy zX=#6Von-x+08W3Z_in2t%dd;rNr~ zCp9g9Uh-chJM-Hhd7R|#ly8x&@9OJ%YW*6?`rU^<8EXDs@)pU?`W~0O&sE+eUh2g) z%)hPVvn8Ly^yf;xM6&5G;w^p8Sl_W1?D-FukrgtohmiK~qa|;XaqVL?ha~Tp@gC&c zCF{MSx!yOo7D&EF%H*qVsh?m~NnR%7X8Hu{Q_0nm^+{ICV`N1>lks!O{Upc9{JN9# zCHInS+BdE&*CFjcgoc=#vzCze2*_5}l*Him)GbCE=rChWAi;@5KlB{)|tm~uM46UsJl*?kI zerxMy$;mSAWPNWp)0Ll=obAdxBoA@r_|xS4aODiixvqSptkO4R4d889`%sz zm;cH7nCnrJ27BmZ-6GRFgVW#7bDcl8OS$IWQpxFGs-(Tl(8+pO%GXJG4&_fvZjllF zJX9&!4CZ`Y;>xc{ea%Ty!I^)xt6b0jjjp^^>TBNSsy|0>Fztc`?oh8{X+3C;vNS-e9GdaP!T(aIDI`><; zzJ<=>`=q5OCwcM!Paf>a z*L!lFWPP62{nt{~Sl^r0>#^=b%@26$KjF!%$)jYO66C7$x~Kd-$$GxbV19cf>-9W| z+^D|o&GxnP|l2@<>lEm8{SA+P1nq`X011=x6tO^5dSof~?ONE#-N4tz`Wj zgUNP|v9^2a>wC}6p!5IQlMi_EF;9-u4u(OeZ!cNzzsjV2b^WtF<<55_TkY~#YmBFS zk|*o?%$2e~l4RaGzsDsf_mO)t=D*2Pf14+N;mLPx_CY7f`hCU_mZ$GA zJA-bozQ61YnsYr_-(z+LEuSFSzQ1FB_j<~okgWIHZ7F}%Q~rS`@ABkY$$Eb|M3$xP zrSB~}gN}CbWPNXWm7K$Kq)h7%@|0ia$zwb@=*iPOd6p+X;K|E8`DIUj+mk=^`#4f*%@@wKAxQB$pbz4CQmN%WPNYh8Fc>BCF}KYw~TB1 z&X=suJ9m;-dg{L>S)a%1`ya_Y-|-k)YUvmvVNbgKj+sx zTe36g{2r35-^UM?aV^*Ph4uS&IfU)}ny3DUp1jkOzmlxa)A~J_&hJ-G`5CR8rJM7! zgC|?%;ru?~K&U7$*w=4$&9lt7&z~0x6$L`RP+n0uP+)Z}a0&_{@?j+GM1NskDC{dL z@#U9~9UBNaAD4wn{l3z&KuOdG;lk2M&IggAQh#wc5Q)m;8ghOpkT>2bEH8-^hDsxm zV8Hprn`Lg1pi?+0R1^vLLZzj}QJ*-Wpmb9GdKKoCj4Lm5N@RU}kwB=psI*}NgQem6 zrP^CGz9<;tVK~tIFc6(y5~?-QWSCLz+}lj-`MgJzt7hPHnB| z>~B5#$C@e2@SB^|63&>}>DOx93voV;ARi2Og9uifzB(y@`ElBlD;AXGF_`lO(2j3pZx z4ETbj{_*bf!ql)AIHlOr4xvE(mYh)5uq9@HnSJH#vGL&(Ch#=s3FT3ZdP1qEZB8g} zXqyv@w2yJxhU3j{3*G3z6zK~xGV~BNCz%{@pL#J7YdGdnY-)kL!?eicCi; zy-_G)jSZHE3w?Pd1=7QX%kztiw5!W2@Rf)1WpVXAQATpq>6Drh)gxp?pNi@IqR;B+ zbH3kzsE)~;8TAWFPm4Oq)A~on^yH`xB6UF2f>QfMoyDmsQKe}qQT;_)s>X)%SX!^3 z+&-!sKAR|~L8+c!dO}hm)j7GzdU~fiC%2iv?x%DT6YUzh-X}SWon7KOicdJxP>9JNnuLtHYk>L3{A1iOiP?> zDtC!{Dp?_wk3IT z=TX1TI%3*7Qdksb+pTa(SxDAutb0LnWJ#OU&(5_9&Z1nUK3`rSFTcoFUNWgjE^hv^ zGU>pR?ZxU{cm4B#X-wV9{L<2(T|PEgRK|mkv`)Ct{&0LKFjm{jULj{4q-FHh#l4bF z75i}am6q5~5S#+KV0j`dni{a|+39l;muY9aT^n^`r!GgHzfAY4?ofLU_5(yXFu@lL z2Lk4nNp3>)9;(1z>++KSv8qn1ouuQ?ox&57&tFjdX`BIC&puM6o_#lgjcUg}#z4*H72J_Np|jw&@&0 zq5lh(z7&gz2g4_oaQr$+NLO zUYuklz27aJq>Agb)U)2THfFz++vlD=bFN}~@;6+?bb^MH$n??L4HR(YvcK!mv)rFo z;tvFU`X!DpJf+0na6oc!+lQdJ5;^CAUAz7m*RDYJjOPq+ZIhm8`UGIly0E-toUdGt zKg(Q;U0cS%9=3{2QCKb$^3{WMt8y!Fl5d|H4h-|fl&AUi0p7J1PVM?H*yO0Qj}PbC z?!MZ{#+~Hinc|+Gx&89q`M4J7G{3V2cIW0Qcb!A7Pn}c3d?QdlkNS(R^em=%-0R|O Yo4G^fbTW66rmu~<^3=DJj%W|{e?@4*5C8xG From e2becead4148cb7efa8e2eed509ee79c0d8b1aab Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 21 Aug 2013 18:12:46 +0200 Subject: [PATCH 109/309] [conf] remove zamboni_pattern from navigation_extra --- conf/firmwares/subsystems/fixedwing/navigation_extra.makefile | 1 - 1 file changed, 1 deletion(-) diff --git a/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile b/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile index 34fd909690..c9d42eda7b 100644 --- a/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile +++ b/conf/firmwares/subsystems/fixedwing/navigation_extra.makefile @@ -19,5 +19,4 @@ $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/spiral.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/poly_survey_adv.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/gls.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/border_line.c -$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/zamboni_survey.c From 67c4a9f9fb1423aa436723a651c3b2ee0fa5f214 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 21 Aug 2013 18:56:29 +0200 Subject: [PATCH 110/309] [modules] add missing zamboni_survey.xml --- conf/modules/zamboni_survey.xml | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) create mode 100644 conf/modules/zamboni_survey.xml diff --git a/conf/modules/zamboni_survey.xml b/conf/modules/zamboni_survey.xml new file mode 100644 index 0000000000..75acfcadb1 --- /dev/null +++ b/conf/modules/zamboni_survey.xml @@ -0,0 +1,16 @@ + + + + + + Zamboni pattern survey for fixedwings. + + +

+ +
+ + + + + From 65676964cff6969a1ca08c77eff64241aead8751 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 21 Aug 2013 17:45:36 +0200 Subject: [PATCH 111/309] Trace Serialport --- sw/airborne/fms/fms_serial_port.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/fms/fms_serial_port.c b/sw/airborne/fms/fms_serial_port.c index d42bedfd16..4e20792050 100644 --- a/sw/airborne/fms/fms_serial_port.c +++ b/sw/airborne/fms/fms_serial_port.c @@ -28,7 +28,7 @@ void serial_port_flush(struct FmsSerialPort* me) { * flush any input that might be on the port so we start fresh. */ if (tcflush(me->fd, TCIFLUSH)) { - TRACE(TRACE_ERROR,"%s, set term attr failed: %s (%d)\n", device, strerror(errno), errno); + TRACE(TRACE_ERROR,"%s, set term attr failed: %s (%d)\n", "", strerror(errno), errno); fprintf(stderr, "flush (%d) failed: %s (%d)\n", me->fd, strerror(errno), errno); } } @@ -38,7 +38,7 @@ void serial_port_flush_output(struct FmsSerialPort* me) { * flush any input that might be on the port so we start fresh. */ if (tcflush(me->fd, TCOFLUSH)) { - TRACE(TRACE_ERROR,"%s, set term attr failed: %s (%d)\n", device, strerror(errno), errno); + TRACE(TRACE_ERROR,"%s, set term attr failed: %s (%d)\n", "", strerror(errno), errno); fprintf(stderr, "flush (%d) failed: %s (%d)\n", me->fd, strerror(errno), errno); } } From 846ab96374ea49e6fa497ae8bb779794d80d8947 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Thu, 22 Aug 2013 10:07:52 +0200 Subject: [PATCH 112/309] omap uart problem fix --- sw/airborne/arch/omap/mcu_periph/uart_arch.c | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.c b/sw/airborne/arch/omap/mcu_periph/uart_arch.c index 1b7af017bc..d363b400f9 100644 --- a/sw/airborne/arch/omap/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.c @@ -33,6 +33,9 @@ #include "fms/fms_serial_port.h" +// #define TRACE(fmt,args...) fprintf(stderr, fmt, args) +#define TRACE(fmt,args...) + void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { struct FmsSerialPort* fmssp; @@ -48,8 +51,13 @@ void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { p->reg_addr = (void*)fmssp; //TODO: set device name in application and pass as argument + // FIXME: baudrate B9600 defined double printf("opening %s on uart0 at %d\n",p->dev,baud); - serial_port_open_raw(fmssp,p->dev,baud); + int ret = serial_port_open_raw(fmssp,p->dev,baud); + if (ret != 0) + { + TRACE("Error opening %s code %d\n",p->dev,ret); + } } void uart_transmit(struct uart_periph* p, uint8_t data ) { @@ -66,11 +74,13 @@ void uart_transmit(struct uart_periph* p, uint8_t data ) { else { // no, set running flag and write to output register p->tx_running = TRUE; struct FmsSerialPort* fmssp = (struct FmsSerialPort*)(p->reg_addr); - write((int)(fmssp->fd),&data,1); - //printf("w %x\n",data); + int ret = write((int)(fmssp->fd),&data,1); + TRACE("w %x [%d]\n",data,ret); } } +#include + static inline void uart_handler(struct uart_periph* p) { unsigned char c='D'; @@ -81,8 +91,8 @@ static inline void uart_handler(struct uart_periph* p) { // check if more data to send if (p->tx_insert_idx != p->tx_extract_idx) { - write(fd,&(p->tx_buf[p->tx_extract_idx]),1); - //printf("w %x\n",p->tx_buf[p->tx_extract_idx]); + int ret = write(fd,&(p->tx_buf[p->tx_extract_idx]),1); + TRACE("w %x [%d: %s]\n",p->tx_buf[p->tx_extract_idx],ret,strerror(errno)); p->tx_extract_idx++; p->tx_extract_idx %= UART_TX_BUFFER_SIZE; } From 0219f9bfa8d781d98c39459b73baaa8d08da8ee4 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Thu, 22 Aug 2013 10:35:24 +0200 Subject: [PATCH 113/309] [ardrone] Read zero baro altitude at sealevel --- sw/airborne/boards/ardrone/baro_board.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index 314a6f8f63..4ab4845087 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -56,7 +56,9 @@ static inline int32_t baro_apply_calibration(int32_t raw) x1 = (p >> 8) * (p >> 8); x1 = (x1 * 3038UL) >> 16; x2 = (-7357L * p) >> 16; - return p + ((x1 + x2 + 3791L) >> 4); + int32_t press = p + ((x1 + x2 + 3791L) >> 4); + // Zero at sealevel + return press - 101325; } static inline int32_t baro_apply_calibration_temp(int32_t tmp_raw) From 0d57fea8c2305f2b48a19b95adcf82879a7deeee Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Thu, 22 Aug 2013 10:17:29 +0200 Subject: [PATCH 114/309] [omap] B9600 baud conflict between uart.h and termios.h --- sw/airborne/arch/omap/mcu_periph/uart_arch.c | 37 +++++++++++++++++--- 1 file changed, 32 insertions(+), 5 deletions(-) diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.c b/sw/airborne/arch/omap/mcu_periph/uart_arch.c index d363b400f9..2e8b9b4964 100644 --- a/sw/airborne/arch/omap/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.c @@ -23,6 +23,7 @@ * omap uart handling */ +// FIXME: uart.h defines B9600 as 9600 #include "mcu_periph/uart.h" #include @@ -31,11 +32,31 @@ #include #include +// FIXME: fms_serial_port includes termios.h that with omap defines B9600 as 12 +// Include termios.h AFTER uart.h. This OVERWRITES (without warning) the paparazzi uart.h B9600 #include "fms/fms_serial_port.h" // #define TRACE(fmt,args...) fprintf(stderr, fmt, args) #define TRACE(fmt,args...) +// Convert the paparazzi B9600 which becomes 9600 to termios B9600 which becomes 12 +// FIXME: not all possible baudrate are available yet. +speed_t baudconvert_drone(uint32_t baud); +speed_t baudconvert_drone(uint32_t baud) +{ + if (baud <= 4800) + return B4800; + else if (baud <= 9600) + return B9600; + else if (baud <= 19200) + return B19200; + else if (baud <= 38400) + return B38400; + else if (baud <= 57600) + return B57600; + return B115200; +} + void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { struct FmsSerialPort* fmssp; @@ -51,9 +72,9 @@ void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { p->reg_addr = (void*)fmssp; //TODO: set device name in application and pass as argument - // FIXME: baudrate B9600 defined double - printf("opening %s on uart0 at %d\n",p->dev,baud); - int ret = serial_port_open_raw(fmssp,p->dev,baud); + // FIXME: paparazzi baud is 9600 for B9600 while open_raw needs 12 for B9600 + printf("opening %s on uart0 at %d (termios.h value=%d)\n",p->dev,baud,baudconvert_drone(baud)); + int ret = serial_port_open_raw(fmssp,p->dev,baudconvert_drone(baud)); if (ret != 0) { TRACE("Error opening %s code %d\n",p->dev,ret); @@ -75,7 +96,10 @@ void uart_transmit(struct uart_periph* p, uint8_t data ) { p->tx_running = TRUE; struct FmsSerialPort* fmssp = (struct FmsSerialPort*)(p->reg_addr); int ret = write((int)(fmssp->fd),&data,1); - TRACE("w %x [%d]\n",data,ret); + if (ret < 1) + { + TRACE("w %x [%d]\n",data,ret); + } } } @@ -92,7 +116,10 @@ static inline void uart_handler(struct uart_periph* p) { // check if more data to send if (p->tx_insert_idx != p->tx_extract_idx) { int ret = write(fd,&(p->tx_buf[p->tx_extract_idx]),1); - TRACE("w %x [%d: %s]\n",p->tx_buf[p->tx_extract_idx],ret,strerror(errno)); + if (ret < 1) + { + TRACE("w %x [%d: %s]\n",p->tx_buf[p->tx_extract_idx],ret,strerror(errno)); + } p->tx_extract_idx++; p->tx_extract_idx %= UART_TX_BUFFER_SIZE; } From a2d33c7cabd3d03b314252843df3dae3a564a814 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 22 Aug 2013 13:38:10 +0200 Subject: [PATCH 115/309] [omap] rename/move FmsSerialPort to SerialPort in arch/omap --- conf/firmwares/rotorcraft.makefile | 17 +++----------- sw/airborne/arch/omap/mcu_periph/uart_arch.c | 10 ++++----- .../omap/serial_port.c} | 18 +++++++-------- .../omap/serial_port.h} | 22 +++++++++---------- sw/airborne/firmwares/beth/overo_test_uart.c | 4 ++-- sw/airborne/firmwares/beth/uart_hw.c | 6 ++--- 6 files changed, 33 insertions(+), 44 deletions(-) rename sw/airborne/{fms/fms_serial_port.c => arch/omap/serial_port.c} (87%) rename sw/airborne/{fms/fms_serial_port.h => arch/omap/serial_port.h} (66%) diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index bb42616a4b..58b2b6187e 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -108,6 +108,9 @@ ap.srcs += $(SRC_ARCH)/subsystems/settings_arch.c ap.srcs += mcu_periph/uart.c ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c +ifeq ($(ARCH), omap) +ap.srcs += $(SRC_ARCH)/serial_port.c +endif # I2C is needed for speed controllers and barometers on lisa ifeq ($(TARGET), ap) @@ -291,17 +294,3 @@ ap.srcs += $(SRC_FIRMWARE)/guidance/guidance_v_adapt.c ap.srcs += $(SRC_FIRMWARE)/navigation.c ap.srcs += subsystems/navigation/common_flight_plan.c -# -# FMS choice -# -# include booz2_fms_test_signal.makefile -# or -# include booz2_fms_datalink.makefile -# or -# nothing -# -ifeq ($(ARCH), omap) -SRC_FMS=fms -ap.CFLAGS += -I. -I$(SRC_FMS) -ap.srcs += $(SRC_FMS)/fms_serial_port.c -endif diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.c b/sw/airborne/arch/omap/mcu_periph/uart_arch.c index 2e8b9b4964..0d4cd02bd1 100644 --- a/sw/airborne/arch/omap/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.c @@ -34,7 +34,7 @@ // FIXME: fms_serial_port includes termios.h that with omap defines B9600 as 12 // Include termios.h AFTER uart.h. This OVERWRITES (without warning) the paparazzi uart.h B9600 -#include "fms/fms_serial_port.h" +#include "serial_port.h" // #define TRACE(fmt,args...) fprintf(stderr, fmt, args) #define TRACE(fmt,args...) @@ -59,10 +59,10 @@ speed_t baudconvert_drone(uint32_t baud) void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { - struct FmsSerialPort* fmssp; + struct SerialPort* fmssp; // close serial port if already open if (p->reg_addr != NULL) { - fmssp = (struct FmsSerialPort*)(p->reg_addr); + fmssp = (struct SerialPort*)(p->reg_addr); serial_port_close(fmssp); serial_port_free(fmssp); } @@ -94,7 +94,7 @@ void uart_transmit(struct uart_periph* p, uint8_t data ) { } else { // no, set running flag and write to output register p->tx_running = TRUE; - struct FmsSerialPort* fmssp = (struct FmsSerialPort*)(p->reg_addr); + struct SerialPort* fmssp = (struct SerialPort*)(p->reg_addr); int ret = write((int)(fmssp->fd),&data,1); if (ret < 1) { @@ -110,7 +110,7 @@ static inline void uart_handler(struct uart_periph* p) { if (p->reg_addr == NULL) return; // device not initialized ? - struct FmsSerialPort* fmssp = (struct FmsSerialPort*)(p->reg_addr); + struct SerialPort* fmssp = (struct SerialPort*)(p->reg_addr); int fd = fmssp->fd; // check if more data to send diff --git a/sw/airborne/fms/fms_serial_port.c b/sw/airborne/arch/omap/serial_port.c similarity index 87% rename from sw/airborne/fms/fms_serial_port.c rename to sw/airborne/arch/omap/serial_port.c index 4e20792050..13441f77b0 100644 --- a/sw/airborne/fms/fms_serial_port.c +++ b/sw/airborne/arch/omap/serial_port.c @@ -1,4 +1,4 @@ -#include "fms_serial_port.h" +#include "serial_port.h" #include #include @@ -13,17 +13,17 @@ #define TRACE(type,fmt,args...) #define TRACE_ERROR 1 -struct FmsSerialPort* serial_port_new(void) { - struct FmsSerialPort* me = malloc(sizeof(struct FmsSerialPort)); +struct SerialPort* serial_port_new(void) { + struct SerialPort* me = malloc(sizeof(struct SerialPort)); return me; } -void serial_port_free(struct FmsSerialPort* me) { +void serial_port_free(struct SerialPort* me) { free(me); } -void serial_port_flush(struct FmsSerialPort* me) { +void serial_port_flush(struct SerialPort* me) { /* * flush any input that might be on the port so we start fresh. */ @@ -33,7 +33,7 @@ void serial_port_flush(struct FmsSerialPort* me) { } } -void serial_port_flush_output(struct FmsSerialPort* me) { +void serial_port_flush_output(struct SerialPort* me) { /* * flush any input that might be on the port so we start fresh. */ @@ -43,7 +43,7 @@ void serial_port_flush_output(struct FmsSerialPort* me) { } } -int serial_port_open_raw(struct FmsSerialPort* me, const char* device, speed_t speed) { +int serial_port_open_raw(struct SerialPort* me, const char* device, speed_t speed) { if ((me->fd = open(device, O_RDWR | O_NONBLOCK | O_NOCTTY)) < 0) { TRACE(TRACE_ERROR,"%s, open failed: %s (%d)\n", device, strerror(errno), errno); return -1; @@ -78,7 +78,7 @@ int serial_port_open_raw(struct FmsSerialPort* me, const char* device, speed_t return 0; } -int serial_port_open(struct FmsSerialPort* me, const char* device, +int serial_port_open(struct SerialPort* me, const char* device, void(*term_conf_callback)(struct termios*, speed_t*)) { speed_t speed; @@ -108,7 +108,7 @@ int serial_port_open(struct FmsSerialPort* me, const char* device, } -void serial_port_close(struct FmsSerialPort* me) { +void serial_port_close(struct SerialPort* me) { /* if null pointer or file descriptor indicates error just bail */ if (!me || me->fd < 0) diff --git a/sw/airborne/fms/fms_serial_port.h b/sw/airborne/arch/omap/serial_port.h similarity index 66% rename from sw/airborne/fms/fms_serial_port.h rename to sw/airborne/arch/omap/serial_port.h index 44a120c73c..f259114975 100644 --- a/sw/airborne/fms/fms_serial_port.h +++ b/sw/airborne/arch/omap/serial_port.h @@ -20,24 +20,24 @@ * */ -#ifndef FMS_SERIAL_PORT_H -#define FMS_SERIAL_PORT_H +#ifndef SERIAL_PORT_H +#define SERIAL_PORT_H #include -struct FmsSerialPort { +struct SerialPort { int fd; /* serial device fd */ struct termios orig_termios; /* saved tty state structure */ struct termios cur_termios; /* tty state structure */ }; -extern struct FmsSerialPort* serial_port_new(void); -extern void serial_port_free(struct FmsSerialPort* me); -extern void serial_port_flush(struct FmsSerialPort* me); -extern void serial_port_flush_output(struct FmsSerialPort* me); -extern int serial_port_open_raw(struct FmsSerialPort* me, const char* device, speed_t speed); -extern int serial_port_open(struct FmsSerialPort* me, const char* device, +extern struct SerialPort* serial_port_new(void); +extern void serial_port_free(struct SerialPort* me); +extern void serial_port_flush(struct SerialPort* me); +extern void serial_port_flush_output(struct SerialPort* me); +extern int serial_port_open_raw(struct SerialPort* me, const char* device, speed_t speed); +extern int serial_port_open(struct SerialPort* me, const char* device, void(*term_conf_callback)(struct termios*, speed_t*)); -extern void serial_port_close(struct FmsSerialPort* me); +extern void serial_port_close(struct SerialPort* me); -#endif /* FMS_SERIAL_PORT_H */ +#endif /* SERIAL_PORT_H */ diff --git a/sw/airborne/firmwares/beth/overo_test_uart.c b/sw/airborne/firmwares/beth/overo_test_uart.c index add7fb9055..572696f762 100644 --- a/sw/airborne/firmwares/beth/overo_test_uart.c +++ b/sw/airborne/firmwares/beth/overo_test_uart.c @@ -37,7 +37,7 @@ #include "fms_periodic.h" #include "fms_debug.h" -#include "fms_serial_port.h" +#include "serial_port.h" #include "overo_gcs_com.h" #include "uart_hw.h" @@ -57,7 +57,7 @@ void check_gps(void); uint8_t nav_utm_zone0 = 31; static uint16_t foo = 0; -//struct FmsSerialPort* fmssp; +//struct SerialPort* fmssp; //int spfd; uint8_t portnum; #ifdef GPS_CONFIGURE diff --git a/sw/airborne/firmwares/beth/uart_hw.c b/sw/airborne/firmwares/beth/uart_hw.c index 558747b871..2d05231221 100644 --- a/sw/airborne/firmwares/beth/uart_hw.c +++ b/sw/airborne/firmwares/beth/uart_hw.c @@ -27,7 +27,7 @@ #include #include -#include "fms_serial_port.h" +#include "serial_port.h" #ifdef USE_UART0 @@ -39,7 +39,7 @@ volatile uint16_t uart0_tx_insert_idx, uart0_tx_extract_idx; volatile bool_t uart0_tx_running; uint8_t uart0_tx_buffer[UART0_TX_BUFFER_SIZE]; -struct FmsSerialPort* fmssp0; +struct SerialPort* fmssp0; int uart0_fd; extern uint8_t portnum; @@ -165,7 +165,7 @@ volatile uint16_t uart1_tx_insert_idx, uart1_tx_extract_idx; volatile bool_t uart1_tx_running; uint8_t uart1_tx_buffer[UART1_TX_BUFFER_SIZE]; -struct FmsSerialPort* fmssp1; +struct SerialPort* fmssp1; int uart1_fd; void uart1_init( void ) { From 4d9ff0c4d0dbdcc4c8ee19898329c238a2fabe61 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 22 Aug 2013 13:56:18 +0200 Subject: [PATCH 116/309] [mcu_periph] move uart baud defines to arch headers --- sw/airborne/arch/lpc21/mcu_periph/uart_arch.h | 11 +++ sw/airborne/arch/omap/mcu_periph/uart_arch.c | 89 +++++++------------ sw/airborne/arch/omap/mcu_periph/uart_arch.h | 4 +- sw/airborne/arch/stm32/mcu_periph/uart_arch.h | 12 ++- sw/airborne/mcu_periph/uart.h | 16 +--- 5 files changed, 61 insertions(+), 71 deletions(-) diff --git a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h index 874449f7b7..eedd044cd6 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h +++ b/sw/airborne/arch/lpc21/mcu_periph/uart_arch.h @@ -34,6 +34,17 @@ #include "LPC21xx.h" #include BOARD_CONFIG +#define B1200 1200 +#define B2400 2400 +#define B4800 4800 +#define B9600 9600 +#define B19200 19200 +#define B38400 38400 +#define B57600 57600 +#define B100000 100000 +#define B115200 115200 +#define B230400 230400 + #define UART_8N1 (uint8_t)(ULCR_CHAR_8 + ULCR_PAR_NO + ULCR_STOP_1) #define UART_7N1 (uint8_t)(ULCR_CHAR_7 + ULCR_PAR_NO + ULCR_STOP_1) #define UART_8N2 (uint8_t)(ULCR_CHAR_8 + ULCR_PAR_NO + ULCR_STOP_2) diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.c b/sw/airborne/arch/omap/mcu_periph/uart_arch.c index 0d4cd02bd1..ad6e85390a 100644 --- a/sw/airborne/arch/omap/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.c @@ -23,7 +23,6 @@ * omap uart handling */ -// FIXME: uart.h defines B9600 as 9600 #include "mcu_periph/uart.h" #include @@ -32,70 +31,50 @@ #include #include -// FIXME: fms_serial_port includes termios.h that with omap defines B9600 as 12 -// Include termios.h AFTER uart.h. This OVERWRITES (without warning) the paparazzi uart.h B9600 #include "serial_port.h" // #define TRACE(fmt,args...) fprintf(stderr, fmt, args) #define TRACE(fmt,args...) -// Convert the paparazzi B9600 which becomes 9600 to termios B9600 which becomes 12 -// FIXME: not all possible baudrate are available yet. -speed_t baudconvert_drone(uint32_t baud); -speed_t baudconvert_drone(uint32_t baud) -{ - if (baud <= 4800) - return B4800; - else if (baud <= 9600) - return B9600; - else if (baud <= 19200) - return B19200; - else if (baud <= 38400) - return B38400; - else if (baud <= 57600) - return B57600; - return B115200; -} - -void uart_periph_set_baudrate(struct uart_periph* p, uint32_t baud) { - struct SerialPort* fmssp; +void uart_periph_set_baudrate(struct uart_periph* periph, uint32_t baud) { + struct SerialPort* port; // close serial port if already open - if (p->reg_addr != NULL) { - fmssp = (struct SerialPort*)(p->reg_addr); - serial_port_close(fmssp); - serial_port_free(fmssp); + if (periph->reg_addr != NULL) { + port = (struct SerialPort*)(periph->reg_addr); + serial_port_close(port); + serial_port_free(port); } // open serial port - fmssp = serial_port_new(); + port = serial_port_new(); // use register address to store SerialPort structure pointer... - p->reg_addr = (void*)fmssp; + periph->reg_addr = (void*)port; //TODO: set device name in application and pass as argument // FIXME: paparazzi baud is 9600 for B9600 while open_raw needs 12 for B9600 - printf("opening %s on uart0 at %d (termios.h value=%d)\n",p->dev,baud,baudconvert_drone(baud)); - int ret = serial_port_open_raw(fmssp,p->dev,baudconvert_drone(baud)); + printf("opening %s on uart0 at termios.h baud value=%d\n", periph->dev, baud); + int ret = serial_port_open_raw(port,periph->dev, baud); if (ret != 0) { - TRACE("Error opening %s code %d\n",p->dev,ret); + TRACE("Error opening %s code %d\n",periph->dev,ret); } } -void uart_transmit(struct uart_periph* p, uint8_t data ) { - uint16_t temp = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE; +void uart_transmit(struct uart_periph* periph, uint8_t data) { + uint16_t temp = (periph->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE; - if (temp == p->tx_extract_idx) + if (temp == periph->tx_extract_idx) return; // no room // check if in process of sending data - if (p->tx_running) { // yes, add to queue - p->tx_buf[p->tx_insert_idx] = data; - p->tx_insert_idx = temp; + if (periph->tx_running) { // yes, add to queue + periph->tx_buf[periph->tx_insert_idx] = data; + periph->tx_insert_idx = temp; } else { // no, set running flag and write to output register - p->tx_running = TRUE; - struct SerialPort* fmssp = (struct SerialPort*)(p->reg_addr); - int ret = write((int)(fmssp->fd),&data,1); + periph->tx_running = TRUE; + struct SerialPort* port = (struct SerialPort*)(periph->reg_addr); + int ret = write((int)(port->fd), &data, 1); if (ret < 1) { TRACE("w %x [%d]\n",data,ret); @@ -105,35 +84,35 @@ void uart_transmit(struct uart_periph* p, uint8_t data ) { #include -static inline void uart_handler(struct uart_periph* p) { +static inline void uart_handler(struct uart_periph* periph) { unsigned char c='D'; - if (p->reg_addr == NULL) return; // device not initialized ? + if (periph->reg_addr == NULL) return; // device not initialized ? - struct SerialPort* fmssp = (struct SerialPort*)(p->reg_addr); - int fd = fmssp->fd; + struct SerialPort* port = (struct SerialPort*)(periph->reg_addr); + int fd = port->fd; // check if more data to send - if (p->tx_insert_idx != p->tx_extract_idx) { - int ret = write(fd,&(p->tx_buf[p->tx_extract_idx]),1); + if (periph->tx_insert_idx != periph->tx_extract_idx) { + int ret = write(fd, &(periph->tx_buf[periph->tx_extract_idx]), 1); if (ret < 1) { - TRACE("w %x [%d: %s]\n",p->tx_buf[p->tx_extract_idx],ret,strerror(errno)); + TRACE("w %x [%d: %s]\n", periph->tx_buf[periph->tx_extract_idx], ret, strerror(errno)); } - p->tx_extract_idx++; - p->tx_extract_idx %= UART_TX_BUFFER_SIZE; + periph->tx_extract_idx++; + periph->tx_extract_idx %= UART_TX_BUFFER_SIZE; } else { - p->tx_running = FALSE; // clear running flag + periph->tx_running = FALSE; // clear running flag } if(read(fd,&c,1) > 0){ //printf("r %x %c\n",c,c); - uint16_t temp = (p->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE; - p->rx_buf[p->rx_insert_idx] = c; + uint16_t temp = (periph->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE; + periph->rx_buf[periph->rx_insert_idx] = c; // check for more room in queue - if (temp != p->rx_extract_idx) - p->rx_insert_idx = temp; // update insert index + if (temp != periph->rx_extract_idx) + periph->rx_insert_idx = temp; // update insert index } } diff --git a/sw/airborne/arch/omap/mcu_periph/uart_arch.h b/sw/airborne/arch/omap/mcu_periph/uart_arch.h index d5a6fd4301..24c341234f 100644 --- a/sw/airborne/arch/omap/mcu_periph/uart_arch.h +++ b/sw/airborne/arch/omap/mcu_periph/uart_arch.h @@ -27,7 +27,9 @@ #define UART_ARCH_H #include "mcu_periph/uart.h" -#include "std.h" + +// for definition of baud rates +#include #define UART1_irq_handler usart1_irq_handler #define UART2_irq_handler usart2_irq_handler diff --git a/sw/airborne/arch/stm32/mcu_periph/uart_arch.h b/sw/airborne/arch/stm32/mcu_periph/uart_arch.h index a375fb83ee..0b8346ad87 100644 --- a/sw/airborne/arch/stm32/mcu_periph/uart_arch.h +++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.h @@ -29,6 +29,16 @@ #ifndef STM32_UART_ARCH_H #define STM32_UART_ARCH_H -#include "std.h" +#define B1200 1200 +#define B2400 2400 +#define B4800 4800 +#define B9600 9600 +#define B19200 19200 +#define B38400 38400 +#define B57600 57600 +#define B100000 100000 +#define B115200 115200 +#define B230400 230400 +#define B921600 921600 #endif /* STM32_UART_ARCH_H */ diff --git a/sw/airborne/mcu_periph/uart.h b/sw/airborne/mcu_periph/uart.h index 84fc1626a6..13c1af34a6 100644 --- a/sw/airborne/mcu_periph/uart.h +++ b/sw/airborne/mcu_periph/uart.h @@ -36,20 +36,8 @@ #define UART_DEV_NAME_SIZE 16 /* - * UART Baud rates - * defines because the stupid c preprocessor can't handle enums -*/ -#define B1200 1200 -#define B2400 2400 -#define B4800 4800 -#define B9600 9600 -#define B19200 19200 -#define B38400 38400 -#define B57600 57600 -#define B100000 100000 -#define B115200 115200 -#define B230400 230400 -#define B921600 921600 + * UART Baud rate defines in arch/x/mcu_periph/uart_arch.h + */ #define UBITS_7 7 #define UBITS_8 8 From a18a74faf73f348c15e01b8314f44e2265afc49e Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 22 Aug 2013 14:43:19 +0200 Subject: [PATCH 117/309] [fixedwing] fix initialzation of trim commands, including yaw --- sw/airborne/firmwares/fixedwing/main_ap.c | 20 ++++++++++++++++++++ sw/airborne/firmwares/fixedwing/main_fbw.c | 15 ++------------- 2 files changed, 22 insertions(+), 13 deletions(-) diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 3898859469..14674522cb 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -84,6 +84,19 @@ #include "led.h" +/* Default trim commands for roll, pitch and yaw */ +#ifndef COMMAND_ROLL_TRIM +#define COMMAND_ROLL_TRIM 0 +#endif + +#ifndef COMMAND_PITCH_TRIM +#define COMMAND_PITCH_TRIM 0 +#endif + +#ifndef COMMAND_YAW_TRIM +#define COMMAND_YAW_TRIM 0 +#endif + /* if PRINT_CONFIG is defined, print some config options */ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) PRINT_CONFIG_VAR(NAVIGATION_FREQUENCY) @@ -230,6 +243,13 @@ void init_ap( void ) { #ifdef TRAFFIC_INFO traffic_info_init(); #endif + + /* set initial trim values. + * these are passed to fbw via inter_mcu. + */ + ap_state->command_roll_trim = COMMAND_ROLL_TRIM; + ap_state->command_pitch_trim = COMMAND_PITCH_TRIM; + ap_state->command_yaw_trim = COMMAND_YAW_TRIM; } diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 234613fa8d..d4c5c2b5b8 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -58,16 +58,9 @@ uint8_t fbw_mode; #include "inter_mcu.h" -/** Trim commands for roll and pitch/ +/** Trim commands for roll, pitch and yaw. + * These are updated from the trim commands in ap_state via inter_mcu */ -#ifndef COMMAND_ROLL_TRIM -#define COMMAND_ROLL_TRIM 0 -#endif - -#ifndef COMMAND_PITCH_TRIM -#define COMMAND_PITCH_TRIM 0 -#endif - pprz_t command_roll_trim; pprz_t command_pitch_trim; pprz_t command_yaw_trim; @@ -106,10 +99,6 @@ void init_fbw( void ) { fbw_mode = FBW_MODE_FAILSAFE; - command_roll_trim = COMMAND_ROLL_TRIM; - command_pitch_trim = COMMAND_PITCH_TRIM; - - /**** start timers for periodic functions *****/ fbw_periodic_tid = sys_time_register_timer((1./60.), NULL); electrical_tid = sys_time_register_timer(0.1, NULL); From fd9130c88ff9d990ec80af8a02e96fa438cfa27d Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 22 Aug 2013 15:04:59 +0200 Subject: [PATCH 118/309] [ins] use sonar only with ins_int_extended --- .../rotorcraft/ins_extended.makefile | 2 +- sw/airborne/subsystems/ins/ins_int.c | 19 ------------------- sw/airborne/subsystems/ins/ins_int.h | 6 +----- sw/airborne/subsystems/ins/ins_int_extended.c | 7 ++++--- 4 files changed, 6 insertions(+), 28 deletions(-) diff --git a/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile b/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile index 4928c4c495..e4ecf1b674 100644 --- a/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile @@ -2,7 +2,7 @@ # extended INS with vertical filter using sonar in a better way (flap ground) # -$(TARGET).CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_int.h\" +$(TARGET).CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_int_extended.h\" $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/ins_int_extended.c diff --git a/sw/airborne/subsystems/ins/ins_int.c b/sw/airborne/subsystems/ins/ins_int.c index 3dd2985273..950397b7fa 100644 --- a/sw/airborne/subsystems/ins/ins_int.c +++ b/sw/airborne/subsystems/ins/ins_int.c @@ -73,10 +73,6 @@ struct FloatVect2 ins_gps_speed_m_s_ned; int32_t ins_qfe; bool_t ins_baro_initialised; int32_t ins_baro_alt; -#if USE_SONAR -bool_t ins_update_on_agl; -int32_t ins_sonar_offset; -#endif #endif /* output */ @@ -107,9 +103,6 @@ void ins_init() { #endif #if USE_VFF ins_baro_initialised = FALSE; -#if USE_SONAR - ins_update_on_agl = FALSE; -#endif vff_init(0., 0., 0.); #endif ins.vf_realign = FALSE; @@ -185,9 +178,6 @@ void ins_update_baro() { if (ins.vf_realign) { ins.vf_realign = FALSE; ins_qfe = baro.absolute; -#if USE_SONAR - ins_sonar_offset = sonar_meas; -#endif vff_realign(0.); ins_ltp_accel.z = ACCEL_BFP_OF_REAL(vff_zdotdot); ins_ltp_speed.z = SPEED_BFP_OF_REAL(vff_zdot); @@ -263,13 +253,4 @@ void ins_update_gps(void) { } void ins_update_sonar() { -#if USE_SONAR && USE_VFF - static int32_t sonar_filtered = 0; - sonar_filtered = (sonar_meas + 2*sonar_filtered) / 3; - /* update baro_qfe assuming a flat ground */ - if (ins_update_on_agl && baro.status == BS_RUNNING) { - int32_t d_sonar = (((int32_t)sonar_filtered - ins_sonar_offset) * INS_SONAR_SENS_NUM) / INS_SONAR_SENS_DEN; - ins_qfe = baro.absolute + (d_sonar * (INS_BARO_SENS_DEN))/INS_BARO_SENS_NUM; - } -#endif } diff --git a/sw/airborne/subsystems/ins/ins_int.h b/sw/airborne/subsystems/ins/ins_int.h index dd12b87f45..c72c805c52 100644 --- a/sw/airborne/subsystems/ins/ins_int.h +++ b/sw/airborne/subsystems/ins/ins_int.h @@ -49,14 +49,10 @@ extern struct NedCoor_i ins_gps_pos_cm_ned; extern struct NedCoor_i ins_gps_speed_cm_s_ned; /* barometer */ -#if USE_VFF || USE_VFF_EXTENDED +#if USE_VFF extern int32_t ins_baro_alt; ///< altitude calculated from baro in meters with #INT32_POS_FRAC extern int32_t ins_qfe; extern bool_t ins_baro_initialised; -#if USE_SONAR -extern bool_t ins_update_on_agl; /* use sonar to update agl if available */ -extern int32_t ins_sonar_offset; -#endif #endif /* output LTP NED */ diff --git a/sw/airborne/subsystems/ins/ins_int_extended.c b/sw/airborne/subsystems/ins/ins_int_extended.c index 3215f44d70..aefa07f10f 100644 --- a/sw/airborne/subsystems/ins/ins_int_extended.c +++ b/sw/airborne/subsystems/ins/ins_int_extended.c @@ -27,7 +27,7 @@ * */ -#include "subsystems/ins/ins_int.h" +#include "subsystems/ins/ins_int_extended.h" #include "subsystems/imu.h" #include "subsystems/sensors/baro.h" @@ -270,8 +270,8 @@ uint8_t var_idx = 0; #endif -#if USE_SONAR void ins_update_sonar() { +#if USE_SONAR static float last_offset = 0.; // new value filtered with median_filter ins_sonar_alt = update_median_filter(&sonar_median, sonar_meas); @@ -318,5 +318,6 @@ void ins_update_sonar() { /* update offset with last value to avoid divergence */ vff_update_offset(last_offset); } -} #endif // USE_SONAR +} + From c5aeba2b06789e69c805782205803cf5b008b4da Mon Sep 17 00:00:00 2001 From: podhrmic Date: Tue, 20 Aug 2013 11:54:31 -0600 Subject: [PATCH 119/309] [ahrs] Upgraded GX3 ahrs subsystem 1) Separate makefiles for fixedwing and rotorcraft (so it can be used in both) 2) Configurable GX3 initialization 3) Acceleration and rates properly rotated into the body frame 4) uses float imu struct to keep the precision 5) adds GX3_INFO message 6) fixed IMU_GYRO and IMU_ACCEL messages for float imu struct 7) removed ahrs_extern_quat interface as obsolete Especially the fixed point imu struct is used for backwards compatibility, maybe there is a more elegant way how to use the floating point interface. after review: - changed UART macros for uart functions - GX3 variables moved into ahrs struct - rates and accel used in imu frame and stored in imu.f - removed unnecessary math macros - renamed variables to lowercase and removed unused ones - removed RMAT to Quat conversion, - using strictly RMAT and Eulers (if needed) - better written calculation of gx3 frequency. It is actually more precise like this. closes pull request #504 --- .../subsystems/fixedwing/ahrs_gx3.makefile | 30 ++ .../rotorcraft/ahrs_extern_quat.makefile | 17 - .../{shared => rotorcraft}/ahrs_gx3.makefile | 6 +- conf/messages.xml | 9 +- sw/airborne/firmwares/fixedwing/ap_downlink.h | 15 + sw/airborne/firmwares/fixedwing/main_ap.c | 4 +- sw/airborne/firmwares/rotorcraft/main.c | 4 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 10 + .../subsystems/ahrs/ahrs_extern_quat.c | 85 ----- .../subsystems/ahrs/ahrs_extern_quat.h | 48 --- sw/airborne/subsystems/ahrs/ahrs_gx3.c | 310 ++++++++++-------- sw/airborne/subsystems/ahrs/ahrs_gx3.h | 54 +-- sw/airborne/subsystems/imu.c | 13 +- sw/airborne/subsystems/imu.h | 5 +- 14 files changed, 278 insertions(+), 332 deletions(-) create mode 100644 conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile delete mode 100644 conf/firmwares/subsystems/rotorcraft/ahrs_extern_quat.makefile rename conf/firmwares/subsystems/{shared => rotorcraft}/ahrs_gx3.makefile (77%) delete mode 100644 sw/airborne/subsystems/ahrs/ahrs_extern_quat.c delete mode 100644 sw/airborne/subsystems/ahrs/ahrs_extern_quat.h diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile new file mode 100644 index 0000000000..2d0d4cee14 --- /dev/null +++ b/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile @@ -0,0 +1,30 @@ +# Fixedwing AHRS module for GX3 +# 2013, Utah State University, http://aggieair.usu.edu/ + +GX3_PORT ?= UART3 +GX3_BAUD ?= B921600 + +AHRS_CFLAGS = -DUSE_AHRS +AHRS_CFLAGS += -DUSE_IMU +AHRS_CFLAGS += -DUSE_IMU_FLOAT +AHRS_CFLAGS += -DUSE_GX3 + +#fixedwings +AHRS_CFLAGS += -DAHRS_UPDATE_FW_ESTIMATOR +AHRS_CFLAGS += -DUSE_AHRS_ALIGNER + +ifneq ($(AHRS_ALIGNER_LED),none) + AHRS_CFLAGS += -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED) +endif + +AHRS_CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_gx3.h\" +AHRS_SRCS += $(SRC_SUBSYSTEMS)/ahrs.c +AHRS_SRCS += $(SRC_SUBSYSTEMS)/imu.c +AHRS_SRCS += subsystems/ahrs/ahrs_gx3.c + +GX3_PORT_LOWER=$(shell echo $(GX3_PORT) | tr A-Z a-z) +AHRS_CFLAGS += -DUSE_$(GX3_PORT) -D$(GX3_PORT)_BAUD=$(GX3_BAUD) +AHRS_CFLAGS += -DUSE_GX3 -DGX3_PORT=$(GX3_PORT_LOWER) + +ap.CFLAGS += $(AHRS_CFLAGS) +ap.srcs += $(AHRS_SRCS) diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_extern_quat.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_extern_quat.makefile deleted file mode 100644 index 9a2087c811..0000000000 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_extern_quat.makefile +++ /dev/null @@ -1,17 +0,0 @@ -# -# AHRS wrapper for AHRS devices, such as GX3 or UM6 -# 2013, Utah State University, http://aggieair.usu.edu/ - -AHRS_CFLAGS = -DUSE_AHRS - -ifneq ($(AHRS_ALIGNER_LED),none) - AHRS_CFLAGS += -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED) -endif - -AHRS_CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_extern_quat.h\" -AHRS_SRCS += subsystems/ahrs.c -AHRS_SRCS += subsystems/ahrs/ahrs_aligner.c -AHRS_SRCS += subsystems/ahrs/ahrs_extern_quat.c - -ap.CFLAGS += $(AHRS_CFLAGS) -ap.srcs += $(AHRS_SRCS) diff --git a/conf/firmwares/subsystems/shared/ahrs_gx3.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile similarity index 77% rename from conf/firmwares/subsystems/shared/ahrs_gx3.makefile rename to conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile index 8ac0680b76..253b4c62a6 100644 --- a/conf/firmwares/subsystems/shared/ahrs_gx3.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile @@ -1,4 +1,4 @@ -# AHRS module for GX3 +# Rotorcraft AHRS module for GX3 # 2013, Utah State University, http://aggieair.usu.edu/ GX3_PORT ?= UART3 @@ -7,6 +7,7 @@ GX3_BAUD ?= B921600 AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_IMU AHRS_CFLAGS += -DUSE_IMU_FLOAT +AHRS_CFLAGS += -DUSE_GX3 ifneq ($(AHRS_ALIGNER_LED),none) AHRS_CFLAGS += -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED) @@ -17,8 +18,9 @@ AHRS_SRCS += $(SRC_SUBSYSTEMS)/ahrs.c AHRS_SRCS += $(SRC_SUBSYSTEMS)/imu.c AHRS_SRCS += subsystems/ahrs/ahrs_gx3.c +GX3_PORT_LOWER=$(shell echo $(GX3_PORT) | tr A-Z a-z) AHRS_CFLAGS += -DUSE_$(GX3_PORT) -D$(GX3_PORT)_BAUD=$(GX3_BAUD) -AHRS_CFLAGS += -DUSE_GX3 -DGX3_LINK=$(GX3_PORT) +AHRS_CFLAGS += -DUSE_GX3 -DGX3_PORT=$(GX3_PORT_LOWER) ap.CFLAGS += $(AHRS_CFLAGS) ap.srcs += $(AHRS_SRCS) diff --git a/conf/messages.xml b/conf/messages.xml index ab52141ce3..8a610824c1 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -603,7 +603,14 @@ - + + + + + + + + diff --git a/sw/airborne/firmwares/fixedwing/ap_downlink.h b/sw/airborne/firmwares/fixedwing/ap_downlink.h index c22d64d773..76bdf38f2b 100644 --- a/sw/airborne/firmwares/fixedwing/ap_downlink.h +++ b/sw/airborne/firmwares/fixedwing/ap_downlink.h @@ -150,6 +150,11 @@ #define PERIODIC_SEND_SEGMENT(_trans, _dev) if (nav_in_segment) { DOWNLINK_SEND_SEGMENT(_trans, _dev, &nav_segment_x_1, &nav_segment_y_1, &nav_segment_x_2, &nav_segment_y_2); } +#if USE_IMU_FLOAT +# include "subsystems/imu.h" +# define PERIODIC_SEND_IMU_ACCEL(_trans, _dev) { DOWNLINK_SEND_IMU_ACCEL(_trans, _dev, &imuf.accel.x, &imuf.accel.y, &imuf.accel.z)} +# define PERIODIC_SEND_IMU_GYRO(_trans, _dev) { DOWNLINK_SEND_IMU_GYRO(_trans, _dev, &imuf.gyro.p, &imuf.gyro.q, &imuf.gyro.r)} +#else #ifdef IMU_TYPE_H # ifdef INS_MODULE_H # include "modules/ins/ins_module.h" @@ -180,6 +185,7 @@ # define PERIODIC_SEND_IMU_GYRO(_trans, _dev) {} # define PERIODIC_SEND_IMU_MAG(_trans, _dev) {} #endif +#endif #ifdef IMU_ANALOG #define PERIODIC_SEND_IMU(_trans, _dev) { int16_t dummy = 42; DOWNLINK_SEND_IMU(_trans, _dev, &(from_fbw.euler_dot[0]), &(from_fbw.euler_dot[1]), &(from_fbw.euler_dot[2]), &dummy, &dummy, &dummy); } @@ -317,5 +323,14 @@ #include "firmwares/fixedwing/stabilization/stabilization_adaptive.h" #define PERIODIC_SEND_H_CTL_A(_trans, _dev) DOWNLINK_SEND_H_CTL_A(_trans, _dev, &h_ctl_roll_sum_err, &h_ctl_ref_roll_angle, &h_ctl_pitch_sum_err, &h_ctl_ref_pitch_angle) +#ifdef USE_GX3 +#define PERIODIC_SEND_GX3_INFO(_trans, _dev) DOWNLINK_SEND_GX3_INFO(_trans, _dev,\ + &ahrs_impl.GX3_freq, \ + &ahrs_impl.GX3_packet.chksm_error, \ + &ahrs_impl.GX3_packet.hdr_error, \ + &ahrs_impl.GX3_chksm) +#else +#define PERIODIC_SEND_GX3_INFO(_trans, _dev) {} +#endif #endif /* AP_DOWNLINK_H */ diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 14674522cb..8c1e8bc7be 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -179,6 +179,9 @@ void init_ap( void ) { #if USE_IMU imu_init(); +#if USE_IMU_FLOAT + imu_float_init(); +#endif #endif #if USE_AHRS_ALIGNER @@ -669,7 +672,6 @@ void event_task_ap( void ) { if (new_ins_attitude > 0) { attitude_loop(); - //LED_TOGGLE(3); new_ins_attitude = 0; } #endif diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 5d5ac26398..060367961d 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -138,7 +138,9 @@ STATIC_INLINE void main_init( void ) { baro_init(); imu_init(); - +#if USE_IMU_FLOAT + imu_float_init(); +#endif ahrs_aligner_init(); ahrs_init(); diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 48a914b5f5..4522d049b4 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -1010,4 +1010,14 @@ #define PERIODIC_SEND_UART_ERRORS(_trans, _dev) {} #endif +#ifdef USE_GX3 +#define PERIODIC_SEND_GX3_INFO(_trans, _dev) DOWNLINK_SEND_GX3_INFO(_trans, _dev,\ + &ahrs_impl.GX3_freq, \ + &ahrs_impl.GX3_packet.chksm_error, \ + &ahrs_impl.GX3_packet.hdr_error, \ + &ahrs_impl.GX3_chksm) +#else +#define PERIODIC_SEND_GX3_INFO(_trans, _dev) {} +#endif + #endif /* TELEMETRY_H */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_extern_quat.c b/sw/airborne/subsystems/ahrs/ahrs_extern_quat.c deleted file mode 100644 index b778af0233..0000000000 --- a/sw/airborne/subsystems/ahrs/ahrs_extern_quat.c +++ /dev/null @@ -1,85 +0,0 @@ -/* - * Copyright (C) 2013 Michal Podhradsky - * Utah State University, http://aggieair.usu.edu/ - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - /** - * @file subsystems/ahrs/ahrs_extern_quat.c - * - * AHRS interface for multiple IMU/AHRS subsystems, such as GX3, UM6 etc. - * - * Propagates the estimated attitude and rates from IMU to body states. Quaternion - * calculation is used. - * - * @author Michal Podhradsky - */ -#include "ahrs_extern_quat.h" -#include "mcu_periph/sys_time.h" -#include "led.h" - -struct AhrsIntExternQuat ahrs_impl; - -void ahrs_init(void) { - ahrs.status = AHRS_UNINIT; - - /* set ltp_to_imu so that body is zero */ - QUAT_COPY(ahrs_impl.ltp_to_imu_quat, imu.body_to_imu_quat); - INT_RATES_ZERO(ahrs_impl.imu_rate); - - #ifdef IMU_MAG_OFFSET - ahrs_impl.mag_offset = IMU_MAG_OFFSET; - #else - ahrs_impl.mag_offset = 0.; - #endif - - //Needed to set orientations - ahrs.status = AHRS_RUNNING; - - #ifdef AHRS_ALIGNER_LED - LED_ON(AHRS_ALIGNER_LED); - #endif -} - -void ahrs_propagate(void) { - /* Compute LTP to BODY quaternion */ - struct Int32Quat ltp_to_body_quat; - INT32_QUAT_COMP_INV(ltp_to_body_quat, ahrs_impl.ltp_to_imu_quat, imu.body_to_imu_quat); - stateSetNedToBodyQuat_i(<p_to_body_quat); - - // TODO: compensate for magnetic offset - - struct Int32Rates body_rate; - ahrs_impl.imu_rate = imu.gyro; - /* compute body rates */ - INT32_RMAT_TRANSP_RATEMULT(body_rate, imu.body_to_imu_rmat, ahrs_impl.imu_rate); - /* Set state */ - stateSetBodyRates_i(&body_rate); -} - -void ahrs_align(void) { -} - -void ahrs_update_accel(void) { -} - -void ahrs_update_mag(void) { -} - -void ahrs_update_gps(void) { -} diff --git a/sw/airborne/subsystems/ahrs/ahrs_extern_quat.h b/sw/airborne/subsystems/ahrs/ahrs_extern_quat.h deleted file mode 100644 index 74a415f387..0000000000 --- a/sw/airborne/subsystems/ahrs/ahrs_extern_quat.h +++ /dev/null @@ -1,48 +0,0 @@ -/* - * Copyright (C) 2013 Michal Podhradsky - * Utah State University, http://aggieair.usu.edu/ - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - /** - * @file subsystems/ahrs/ahrs_extern_quat.h - * - * AHRS interface for multiple IMU/AHRS subsystems, such as GX3, UM6 etc. - * - * Propagates the estimated attitude and rates from IMU to body states. Quaternion - * calculation is used. - * - * @author Michal Podhradsky - */ -#ifndef AHRS_EXTERN_QUAT_H -#define AHRS_EXTERN_QUAT_H - -#include "state.h" -#include "subsystems/ahrs.h" -#include "subsystems/imu.h" - -struct AhrsIntExternQuat { - struct Int32Eulers ltp_to_imu_euler; ///< Rotation from LocalTangentPlane to IMU frame as Euler angles - struct Int32Quat ltp_to_imu_quat; ///< Rotation from LocalTangentPlane to IMU frame as quaternions - struct Int32Rates imu_rate; ///< Rotational velocity in IMU frame - float mag_offset; -}; - -extern struct AhrsIntExternQuat ahrs_impl; - -#endif /* AHRS_EXTERN_QUAT_H */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.c b/sw/airborne/subsystems/ahrs/ahrs_gx3.c index 2911d64150..4fa28e6f48 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_gx3.c +++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.c @@ -30,9 +30,19 @@ * @author Michal Podhradsky */ #include "subsystems/ahrs/ahrs_gx3.h" -#include "mcu_periph/sys_time.h" -#define GX3_TIME(_ubx_payload) (uint32_t)((uint32_t)(*((uint8_t*)_ubx_payload+62+3))|(uint32_t)(*((uint8_t*)_ubx_payload+62+2))<<8|(uint32_t)(*((uint8_t*)_ubx_payload+62+1))<<16|(uint32_t)(*((uint8_t*)_ubx_payload+62+0))<<24) +#ifdef AHRS_UPDATE_FW_ESTIMATOR +// remotely settable +#ifndef INS_ROLL_NEUTRAL_DEFAULT +#define INS_ROLL_NEUTRAL_DEFAULT 0 +#endif +#ifndef INS_PITCH_NEUTRAL_DEFAULT +#define INS_PITCH_NEUTRAL_DEFAULT 0 +#endif +float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; +float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; +#endif + #define GX3_CHKSM(_ubx_payload) (uint16_t)((uint16_t)(*((uint8_t*)_ubx_payload+66+1))|(uint16_t)(*((uint8_t*)_ubx_payload+66+0))<<8) /* @@ -41,24 +51,10 @@ * Positive roll : right wing down * Positive yaw : clockwise */ -struct GX3_packet GX3_packet; -enum GX3Status GX3_status; -uint32_t GX3_time; -uint32_t GX3_ltime; -uint16_t GX3_chksm; -uint16_t GX3_calcsm; -float GX3_freq; - -struct FloatVect3 GX3_accel; -struct FloatRates GX3_rate; -struct FloatRMat GX3_rmat; -struct FloatQuat GX3_quat; -struct FloatEulers GX3_euler; - struct AhrsFloatQuat ahrs_impl; struct AhrsAligner ahrs_aligner; -static inline bool_t GX3_verify_chk(volatile uint8_t *buff_add); +static inline bool_t gx3_verify_chk(volatile uint8_t *buff_add); static inline float bef(volatile uint8_t *c); /* Big Endian to Float */ @@ -73,7 +69,7 @@ static inline float bef(volatile uint8_t *c) { return f; } -static inline bool_t GX3_verify_chk(volatile uint8_t *buff_add) { +static inline bool_t gx3_verify_chk(volatile uint8_t *buff_add) { uint16_t i,chk_calc; chk_calc = 0; for (i=0;i 180.0) { + course_f -= 360.0; + } + ltp_to_body_eulers.psi = (float)RadOfDeg(course_f); +#endif + stateSetNedToBodyEulers_f(<p_to_body_eulers); +#else +#ifdef IMU_MAG_OFFSET //rotorcraft + struct FloatEulers ltp_to_body_eulers; + FLOAT_EULERS_OF_RMAT(ltp_to_body_eulers, ltp_to_body_rmat); + ltp_to_body_eulers.psi -= ahrs_impl.mag_offset; + stateSetNedToBodyEulers_f(<p_to_body_eulers); +#else + stateSetNedToBodyRMat_f(<p_to_body_rmat); +#endif +#endif } /* GX3 Packet Collection */ -void GX3_packet_parse( uint8_t c ) { - switch (GX3_packet.status) { +void gx3_packet_parse( uint8_t c ) { + switch (ahrs_impl.gx3_packet.status) { case GX3PacketWaiting: - GX3_packet.msg_idx = 0; + ahrs_impl.gx3_packet.msg_idx = 0; if (c == GX3_HEADER) { - GX3_packet.status++; - GX3_packet.msg_buf[GX3_packet.msg_idx] = c; - GX3_packet.msg_idx++; + ahrs_impl.gx3_packet.status++; + ahrs_impl.gx3_packet.msg_buf[ahrs_impl.gx3_packet.msg_idx] = c; + ahrs_impl.gx3_packet.msg_idx++; } else { - GX3_packet.hdr_error++; + ahrs_impl.gx3_packet.hdr_error++; } break; case GX3PacketReading: - GX3_packet.msg_buf[GX3_packet.msg_idx] = c; - GX3_packet.msg_idx++; - if (GX3_packet.msg_idx == GX3_MSG_LEN) { - if (GX3_verify_chk(GX3_packet.msg_buf)) { - GX3_packet.msg_available = TRUE; + ahrs_impl.gx3_packet.msg_buf[ahrs_impl.gx3_packet.msg_idx] = c; + ahrs_impl.gx3_packet.msg_idx++; + if (ahrs_impl.gx3_packet.msg_idx == GX3_MSG_LEN) { + if (gx3_verify_chk(ahrs_impl.gx3_packet.msg_buf)) { + ahrs_impl.gx3_packet.msg_available = TRUE; } else { - GX3_packet.msg_available = FALSE; - GX3_packet.chksm_error++; + ahrs_impl.gx3_packet.msg_available = FALSE; + ahrs_impl.gx3_packet.chksm_error++; } - GX3_packet.status = 0; + ahrs_impl.gx3_packet.status = 0; } break; default: - GX3_packet.status = 0; - GX3_packet.msg_idx = 0; + ahrs_impl.gx3_packet.status = 0; + ahrs_impl.gx3_packet.msg_idx = 0; break; } } void ahrs_init(void) { ahrs.status = AHRS_UNINIT; - /* set ltp_to_imu so that body is zero */ QUAT_COPY(ahrs_impl.ltp_to_imu_quat, imuf.body_to_imu_quat); - FLOAT_RATES_ZERO(ahrs_impl.imu_rate); - #ifdef IMU_MAG_OFFSET ahrs_impl.mag_offset = IMU_MAG_OFFSET; #else - ahrs_impl.mag_offset = 0.; + ahrs_impl.mag_offset = 0.0; #endif - ahrs_aligner.status = AHRS_ALIGNER_LOCKED; } void ahrs_aligner_run(void) { #ifdef AHRS_ALIGNER_LED - LED_TOGGLE(AHRS_ALIGNER_LED); + LED_ON(AHRS_ALIGNER_LED); #endif - - if (GX3_freq > GX3_MIN_FREQ) { - ahrs.status = AHRS_RUNNING; -#ifdef AHRS_ALIGNER_LED - LED_ON(AHRS_ALIGNER_LED); -#endif - } + ahrs.status = AHRS_RUNNING; } + void ahrs_aligner_init(void) { } diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.h b/sw/airborne/subsystems/ahrs/ahrs_gx3.h index e56cf0ed37..cf2c464f21 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_gx3.h +++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.h @@ -36,18 +36,13 @@ #include "subsystems/imu.h" #include "subsystems/ahrs.h" #include "subsystems/ins.h" +#include "subsystems/gps.h" #include "mcu_periph/uart.h" #include "subsystems/ahrs/ahrs_aligner.h" #include "state.h" #include "led.h" -#define __GX3Link(dev, _x) dev##_x -#define _GX3Link(dev, _x) __GX3Link(dev, _x) -#define GX3Link(_x) _GX3Link(GX3_LINK, _x) - -#define GX3Buffer() GX3Link(ChAvailable()) - #ifdef ImuScaleGyro #undef ImuScaleGyro #endif @@ -70,18 +65,10 @@ #define IMU_GX3_LONG_DELAY 4000000 -extern struct GX3_packet GX3_packet; -extern enum GX3Status GX3_status; +extern void gx3_packet_read_message(void); +extern void gx3_packet_parse(uint8_t c); -extern void GX3_packet_read_message(void); -extern void GX3_packet_parse(uint8_t c); - -extern float GX3_freq; -extern uint16_t GX3_chksm; -extern uint16_t GX3_calcsm; -extern uint32_t GX3_time; - -struct GX3_packet { +struct GX3Packet { bool_t msg_available; uint32_t chksm_error; uint32_t hdr_error; @@ -90,7 +77,7 @@ struct GX3_packet { uint8_t msg_idx; }; -enum GX36PacketStatus { +enum GX3PacketStatus { GX3PacketWaiting, GX3PacketReading }; @@ -102,30 +89,43 @@ enum GX3Status { //AHRS struct AhrsFloatQuat { - struct FloatEulers ltp_to_imu_euler; ///< Rotation from LocalTangentPlane to IMU frame as Euler angles struct FloatQuat ltp_to_imu_quat; ///< Rotation from LocalTangentPlane to IMU frame as quaternions - struct FloatRates imu_rate; ///< Rotational velocity in IMU frame - float mag_offset; + float mag_offset; ///< Difference between true and magnetic north + + struct GX3Packet gx3_packet; ///< Packet struct + enum GX3Status gx3_status; ///< GX3 status + float gx3_freq; ///< data frequency + uint16_t gx3_chksm; ///< aux variable for checksum + uint32_t gx3_time; ///< GX3 time stamp + uint32_t gx3_ltime; ///< aux time stamp + struct FloatVect3 gx3_accel; ///< measured acceleration in IMU frame + struct FloatRates gx3_rate; ///< measured angular rates in IMU frame + struct FloatRMat gx3_rmat; ///< measured attitude in IMU frame (rotational matrix) }; extern struct AhrsFloatQuat ahrs_impl; static inline void ReadGX3Buffer(void) { - while (GX3Link(ChAvailable()) && !GX3_packet.msg_available) - GX3_packet_parse(GX3Link(Getch())); + while (uart_char_available(&GX3_PORT) && !ahrs_impl.gx3_packet.msg_available) + gx3_packet_parse(uart_getch(&GX3_PORT)); } static inline void ImuEvent(void (* _gyro_handler)(void), void (* _accel_handler)(void), void (* _mag_handler)(void)) { - if (GX3Buffer()) { + if (uart_char_available(&GX3_PORT)) { ReadGX3Buffer(); } - if (GX3_packet.msg_available) { - GX3_packet_read_message(); + if (ahrs_impl.gx3_packet.msg_available) { + gx3_packet_read_message(); _gyro_handler(); _accel_handler(); _mag_handler(); - GX3_packet.msg_available = FALSE; + ahrs_impl.gx3_packet.msg_available = FALSE; } } +#ifdef AHRS_UPDATE_FW_ESTIMATOR +extern float ins_roll_neutral; +extern float ins_pitch_neutral; +#endif + #endif /* AHRS_GX3_H*/ diff --git a/sw/airborne/subsystems/imu.c b/sw/airborne/subsystems/imu.c index 74432019cb..3d9998bb99 100644 --- a/sw/airborne/subsystems/imu.c +++ b/sw/airborne/subsystems/imu.c @@ -27,6 +27,7 @@ #include "subsystems/imu.h" struct Imu imu; +struct ImuFloat imuf; void imu_init(void) { @@ -60,16 +61,14 @@ INFO("Magnetometer neutrals are set to zero, you should calibrate!") } -void imu_float_init(struct ImuFloat* imuf) { - +void imu_float_init(void) { /* Compute quaternion and rotation matrix for conversions between body and imu frame */ - EULERS_ASSIGN(imuf->body_to_imu_eulers, + EULERS_ASSIGN(imuf.body_to_imu_eulers, IMU_BODY_TO_IMU_PHI, IMU_BODY_TO_IMU_THETA, IMU_BODY_TO_IMU_PSI); - FLOAT_QUAT_OF_EULERS(imuf->body_to_imu_quat, imuf->body_to_imu_eulers); - FLOAT_QUAT_NORMALIZE(imuf->body_to_imu_quat); - FLOAT_RMAT_OF_EULERS(imuf->body_to_imu_rmat, imuf->body_to_imu_eulers); - + FLOAT_QUAT_OF_EULERS(imuf.body_to_imu_quat, imuf.body_to_imu_eulers); + FLOAT_QUAT_NORMALIZE(imuf.body_to_imu_quat); + FLOAT_RMAT_OF_EULERS(imuf.body_to_imu_rmat, imuf.body_to_imu_eulers); } diff --git a/sw/airborne/subsystems/imu.h b/sw/airborne/subsystems/imu.h index 72f759f7ef..1d082a9f58 100644 --- a/sw/airborne/subsystems/imu.h +++ b/sw/airborne/subsystems/imu.h @@ -64,10 +64,11 @@ struct ImuFloat { uint32_t sample_count; }; -extern void imu_float_init(struct ImuFloat* imuf); + /** global IMU state */ extern struct Imu imu; +extern struct ImuFloat imuf; /* underlying hardware */ #ifdef IMU_TYPE_H @@ -75,7 +76,7 @@ extern struct Imu imu; #endif extern void imu_init(void); - +extern void imu_float_init(void); #if !defined IMU_BODY_TO_IMU_PHI && !defined IMU_BODY_TO_IMU_THETA && !defined IMU_BODY_TO_IMU_PSI #define IMU_BODY_TO_IMU_PHI 0 From 393a21b1d0e96c29bd64cdd4dc70c08a8b2184c6 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 22 Aug 2013 15:53:24 +0200 Subject: [PATCH 120/309] [ins] add missing header ins_int_extended.h --- sw/airborne/subsystems/ins/ins_int_extended.h | 82 +++++++++++++++++++ 1 file changed, 82 insertions(+) create mode 100644 sw/airborne/subsystems/ins/ins_int_extended.h diff --git a/sw/airborne/subsystems/ins/ins_int_extended.h b/sw/airborne/subsystems/ins/ins_int_extended.h new file mode 100644 index 0000000000..6d0ae9b2ec --- /dev/null +++ b/sw/airborne/subsystems/ins/ins_int_extended.h @@ -0,0 +1,82 @@ +/* + * Copyright (C) 2008-2012 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/ins/ins_int_extended.h + * + * INS for rotorcrafts combining vertical and horizontal filters. + * This filter includes estimation of the baro drift based on sonar. + * + * Vertical filter is always enabled + * + * TODO: use GPS alt if good enough, especially when sonar readings are not available + * + */ + +#ifndef INS_INT_EXTENDED_H +#define INS_INT_EXTENDED_H + +#include "subsystems/ins.h" +#include "std.h" +#include "math/pprz_geodetic_int.h" +#include "math/pprz_algebra_float.h" + +// TODO integrate all internal state to the structure +///** Ins extended implementation state (fixed point) */ +//struct InsIntExtended { +//}; +// +///** global INS state */ +//extern struct InsInt ins_impl; + +/* gps transformed to LTP-NED */ +extern struct LtpDef_i ins_ltp_def; +extern bool_t ins_ltp_initialised; +extern struct NedCoor_i ins_gps_pos_cm_ned; +extern struct NedCoor_i ins_gps_speed_cm_s_ned; + +/* barometer */ +extern int32_t ins_baro_alt; ///< altitude calculated from baro in meters with #INT32_POS_FRAC +extern int32_t ins_qfe; +extern bool_t ins_baro_initialised; +#if USE_SONAR +extern bool_t ins_update_on_agl; /* use sonar to update agl if available */ +extern int32_t ins_sonar_offset; +#endif + +/* output LTP NED */ +extern struct NedCoor_i ins_ltp_pos; +extern struct NedCoor_i ins_ltp_speed; +extern struct NedCoor_i ins_ltp_accel; +#if USE_HFF +/* horizontal gps transformed to NED in meters as float */ +extern struct FloatVect2 ins_gps_pos_m_ned; +extern struct FloatVect2 ins_gps_speed_m_s_ned; +#endif + +/* copy position and speed to state interface */ +#define INS_NED_TO_STATE() { \ + stateSetPositionNed_i(&ins_ltp_pos); \ + stateSetSpeedNed_i(&ins_ltp_speed); \ + stateSetAccelNed_i(&ins_ltp_accel); \ +} + +#endif /* INS_INT_EXTENDED_H */ From c90cd6f3354c9f2c48035ae0c25080df7b7e687c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 22 Aug 2013 16:58:45 +0200 Subject: [PATCH 121/309] [math] factor out function to calc ltp_of_ecef rmat --- sw/airborne/math/pprz_geodetic_int.c | 73 ++++++++++------------------ sw/airborne/math/pprz_geodetic_int.h | 1 + 2 files changed, 28 insertions(+), 46 deletions(-) diff --git a/sw/airborne/math/pprz_geodetic_int.c b/sw/airborne/math/pprz_geodetic_int.c index 428472080c..d66e3cfe2a 100644 --- a/sw/airborne/math/pprz_geodetic_int.c +++ b/sw/airborne/math/pprz_geodetic_int.c @@ -24,6 +24,31 @@ #define HIGH_RES_TRIG_FRAC 20 +void ltp_of_ecef_rmat_from_lla_i(struct Int32Mat33* ltp_of_ecef, struct LlaCoor_i* lla) { + +#if USE_DOUBLE_PRECISION_TRIG + int32_t sin_lat = rint(BFP_OF_REAL(sin(RAD_OF_EM7RAD((double)lla->lat)), HIGH_RES_TRIG_FRAC)); + int32_t cos_lat = rint(BFP_OF_REAL(cos(RAD_OF_EM7RAD((double)lla->lat)), HIGH_RES_TRIG_FRAC)); + int32_t sin_lon = rint(BFP_OF_REAL(sin(RAD_OF_EM7RAD((double)lla->lon)), HIGH_RES_TRIG_FRAC)); + int32_t cos_lon = rint(BFP_OF_REAL(cos(RAD_OF_EM7RAD((double)lla->lon)), HIGH_RES_TRIG_FRAC)); +#else + int32_t sin_lat = rint(BFP_OF_REAL(sinf(RAD_OF_EM7RAD((float)lla->lat)), HIGH_RES_TRIG_FRAC)); + int32_t cos_lat = rint(BFP_OF_REAL(cosf(RAD_OF_EM7RAD((float)lla->lat)), HIGH_RES_TRIG_FRAC)); + int32_t sin_lon = rint(BFP_OF_REAL(sinf(RAD_OF_EM7RAD((float)lla->lon)), HIGH_RES_TRIG_FRAC)); + int32_t cos_lon = rint(BFP_OF_REAL(cosf(RAD_OF_EM7RAD((float)lla->lon)), HIGH_RES_TRIG_FRAC)); +#endif + + ltp_of_ecef->m[0] = -sin_lon; + ltp_of_ecef->m[1] = cos_lon; + ltp_of_ecef->m[2] = 0; /* this element is always zero http://en.wikipedia.org/wiki/Geodetic_system#From_ECEF_to_ENU */ + ltp_of_ecef->m[3] = (int32_t)((-(int64_t)sin_lat*(int64_t)cos_lon)>>HIGH_RES_TRIG_FRAC); + ltp_of_ecef->m[4] = (int32_t)((-(int64_t)sin_lat*(int64_t)sin_lon)>>HIGH_RES_TRIG_FRAC); + ltp_of_ecef->m[5] = cos_lat; + ltp_of_ecef->m[6] = (int32_t)(( (int64_t)cos_lat*(int64_t)cos_lon)>>HIGH_RES_TRIG_FRAC); + ltp_of_ecef->m[7] = (int32_t)(( (int64_t)cos_lat*(int64_t)sin_lon)>>HIGH_RES_TRIG_FRAC); + ltp_of_ecef->m[8] = sin_lat; +} + void ltp_def_from_ecef_i(struct LtpDef_i* def, struct EcefCoor_i* ecef) { /* store the origin of the tangeant plane */ @@ -31,29 +56,7 @@ void ltp_def_from_ecef_i(struct LtpDef_i* def, struct EcefCoor_i* ecef) { /* compute the lla representation of the origin */ lla_of_ecef_i(&def->lla, &def->ecef); /* store the rotation matrix */ - -#if 1 - int32_t sin_lat = rint(BFP_OF_REAL(sinf(RAD_OF_EM7RAD((float)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lat = rint(BFP_OF_REAL(cosf(RAD_OF_EM7RAD((float)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t sin_lon = rint(BFP_OF_REAL(sinf(RAD_OF_EM7RAD((float)def->lla.lon)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lon = rint(BFP_OF_REAL(cosf(RAD_OF_EM7RAD((float)def->lla.lon)), HIGH_RES_TRIG_FRAC)); -#else - int32_t sin_lat = rint(BFP_OF_REAL(sin(RAD_OF_EM7RAD((double)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lat = rint(BFP_OF_REAL(cos(RAD_OF_EM7RAD((double)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t sin_lon = rint(BFP_OF_REAL(sin(RAD_OF_EM7RAD((double)def->lla.lon)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lon = rint(BFP_OF_REAL(cos(RAD_OF_EM7RAD((double)def->lla.lon)), HIGH_RES_TRIG_FRAC)); -#endif - - - def->ltp_of_ecef.m[0] = -sin_lon; - def->ltp_of_ecef.m[1] = cos_lon; - def->ltp_of_ecef.m[2] = 0; /* this element is always zero http://en.wikipedia.org/wiki/Geodetic_system#From_ECEF_to_ENU */ - def->ltp_of_ecef.m[3] = (int32_t)((-(int64_t)sin_lat*(int64_t)cos_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[4] = (int32_t)((-(int64_t)sin_lat*(int64_t)sin_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[5] = cos_lat; - def->ltp_of_ecef.m[6] = (int32_t)(( (int64_t)cos_lat*(int64_t)cos_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[7] = (int32_t)(( (int64_t)cos_lat*(int64_t)sin_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[8] = sin_lat; + ltp_of_ecef_rmat_from_lla_i(&def->ltp_of_ecef, &def->lla); } @@ -64,29 +67,7 @@ void ltp_def_from_lla_i(struct LtpDef_i* def, struct LlaCoor_i* lla) { /* compute the ecef representation of the origin */ ecef_of_lla_i(&def->ecef, &def->lla); /* store the rotation matrix */ - -#if 1 - int32_t sin_lat = rint(BFP_OF_REAL(sinf(RAD_OF_EM7RAD((float)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lat = rint(BFP_OF_REAL(cosf(RAD_OF_EM7RAD((float)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t sin_lon = rint(BFP_OF_REAL(sinf(RAD_OF_EM7RAD((float)def->lla.lon)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lon = rint(BFP_OF_REAL(cosf(RAD_OF_EM7RAD((float)def->lla.lon)), HIGH_RES_TRIG_FRAC)); -#else - int32_t sin_lat = rint(BFP_OF_REAL(sin(RAD_OF_EM7RAD((double)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lat = rint(BFP_OF_REAL(cos(RAD_OF_EM7RAD((double)def->lla.lat)), HIGH_RES_TRIG_FRAC)); - int32_t sin_lon = rint(BFP_OF_REAL(sin(RAD_OF_EM7RAD((double)def->lla.lon)), HIGH_RES_TRIG_FRAC)); - int32_t cos_lon = rint(BFP_OF_REAL(cos(RAD_OF_EM7RAD((double)def->lla.lon)), HIGH_RES_TRIG_FRAC)); -#endif - - - def->ltp_of_ecef.m[0] = -sin_lon; - def->ltp_of_ecef.m[1] = cos_lon; - def->ltp_of_ecef.m[2] = 0; /* this element is always zero http://en.wikipedia.org/wiki/Geodetic_system#From_ECEF_to_ENU */ - def->ltp_of_ecef.m[3] = (int32_t)((-(int64_t)sin_lat*(int64_t)cos_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[4] = (int32_t)((-(int64_t)sin_lat*(int64_t)sin_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[5] = cos_lat; - def->ltp_of_ecef.m[6] = (int32_t)(( (int64_t)cos_lat*(int64_t)cos_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[7] = (int32_t)(( (int64_t)cos_lat*(int64_t)sin_lon)>>HIGH_RES_TRIG_FRAC); - def->ltp_of_ecef.m[8] = sin_lat; + ltp_of_ecef_rmat_from_lla_i(&def->ltp_of_ecef, &def->lla); } diff --git a/sw/airborne/math/pprz_geodetic_int.h b/sw/airborne/math/pprz_geodetic_int.h index 9d95d52319..ddd35318fe 100644 --- a/sw/airborne/math/pprz_geodetic_int.h +++ b/sw/airborne/math/pprz_geodetic_int.h @@ -99,6 +99,7 @@ struct LtpDef_i { int32_t hmsl; ///< Height above mean sea level in mm }; +extern void ltp_of_ecef_rmat_from_lla_i(struct Int32Mat33* ltp_of_ecef, struct LlaCoor_i* lla); extern void ltp_def_from_ecef_i(struct LtpDef_i* def, struct EcefCoor_i* ecef); extern void ltp_def_from_lla_i(struct LtpDef_i* def, struct LlaCoor_i* lla); extern void lla_of_ecef_i(struct LlaCoor_i* out, struct EcefCoor_i* in); From f9b7ee211f7592804407c61c756c044ac4361a74 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 00:31:14 +0200 Subject: [PATCH 122/309] [peripheral] add ms5611 i2c and spi peripherals --- sw/airborne/boards/lisa_m/baro_ms5611_i2c.c | 10 +- sw/airborne/boards/lisa_m/baro_ms5611_spi.c | 11 +- sw/airborne/peripherals/ms5611.c | 91 +++++++++ sw/airborne/peripherals/ms5611.h | 101 +++------- sw/airborne/peripherals/ms5611_i2c.c | 189 ++++++++++++++++++ sw/airborne/peripherals/ms5611_i2c.h | 63 ++++++ sw/airborne/peripherals/ms5611_regs.h | 72 +++++++ sw/airborne/peripherals/ms5611_spi.c | 203 ++++++++++++++++++++ sw/airborne/peripherals/ms5611_spi.h | 65 +++++++ 9 files changed, 733 insertions(+), 72 deletions(-) create mode 100644 sw/airborne/peripherals/ms5611.c create mode 100644 sw/airborne/peripherals/ms5611_i2c.c create mode 100644 sw/airborne/peripherals/ms5611_i2c.h create mode 100644 sw/airborne/peripherals/ms5611_regs.h create mode 100644 sw/airborne/peripherals/ms5611_spi.c create mode 100644 sw/airborne/peripherals/ms5611_spi.h diff --git a/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c b/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c index 10994d5948..57c0ea103d 100644 --- a/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c +++ b/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c @@ -5,7 +5,7 @@ * Utah State University, http://aggieair.usu.edu/ */ #include "subsystems/sensors/baro.h" -#include "peripherals/ms5611.h" +#include "peripherals/ms5611_regs.h" #include "led.h" #include "std.h" #include "mcu_periph/sys_time.h" @@ -15,6 +15,14 @@ #define MS5611_I2C_DEV i2c2 #endif +/* default i2c address + * when CSB is set to GND addr is 0xEE + * when CSB is set to VCC addr is 0xEC + * + * Note: Aspirin 2.1 has CSB bound to GND. + */ +#define MS5611_SLAVE_ADDR 0xEE + #ifdef DEBUG #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE diff --git a/sw/airborne/boards/lisa_m/baro_ms5611_spi.c b/sw/airborne/boards/lisa_m/baro_ms5611_spi.c index bd437cd318..4e58c10605 100644 --- a/sw/airborne/boards/lisa_m/baro_ms5611_spi.c +++ b/sw/airborne/boards/lisa_m/baro_ms5611_spi.c @@ -5,7 +5,7 @@ * Utah State University, http://aggieair.usu.edu/ */ #include "subsystems/sensors/baro.h" -#include "peripherals/ms5611.h" +#include "peripherals/ms5611_regs.h" #include "led.h" #include "std.h" #include "mcu_periph/sys_time.h" @@ -14,6 +14,15 @@ #ifndef MS5611_SPI_DEV #define MS5611_SPI_DEV spi2 #endif + +/* SPI SLAVE3 is on pin PC13 + * Aspirin 2.2 has ms5611 on SPI bus + */ +#ifndef MS5611_SLAVE_DEV +#define MS5611_SLAVE_DEV SPI_SLAVE3 +#endif + + #define MS5611_BUFFER_LENGTH 4 #ifdef DEBUG diff --git a/sw/airborne/peripherals/ms5611.c b/sw/airborne/peripherals/ms5611.c new file mode 100644 index 0000000000..9956d6583b --- /dev/null +++ b/sw/airborne/peripherals/ms5611.c @@ -0,0 +1,91 @@ +/* + * Copyright (C) 2011 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/ms5611.c + * + * MS5611 barometer driver common functions (I2C and SPI). + */ + +#include "peripherals/ms5611.h" +#include "std.h" + +/** + * Check if CRC of PROM data is OK. + * @return TRUE if OK, FALSE otherwise + */ +bool_t ms5611_prom_crc_ok(uint16_t* prom) { + int32_t i, j; + uint32_t res = 0; + uint8_t crc = prom[7] & 0xF; + prom[7] &= 0xFF00; + for (i = 0; i < 16; i++) { + if (i & 1) + res ^= ((prom[i>>1]) & 0x00FF); + else + res ^= (prom[i>>1]>>8); + for (j = 8; j > 0; j--) { + if (res & 0x8000) + res ^= 0x1800; + res <<= 1; + } + } + prom[7] |= crc; + if (crc == ((res >> 12) & 0xF)) + return TRUE; + else + return FALSE; +} + +/** + * Calculate temperature and compensated pressure. + */ +void ms5611_calc(struct Ms5611Data* ms) { + int64_t dt, tempms, off, sens, t2, off2, sens2; + + /* difference between actual and ref temperature */ + dt = ms->d2 - (int64_t)ms->c[5] * (1<<8); + /* actual temperature */ + tempms = 2000 + ((int64_t)dt * ms->c[6]) / (1<<23); + /* offset at actual temperature */ + off = ((int64_t)ms->c[2] * (1<<16)) + ((int64_t)ms->c[4] * dt) / (1<<7); + /* sensitivity at actual temperature */ + sens = ((int64_t)ms->c[1] * (1<<15)) + ((int64_t)ms->c[3] * dt) / (1<<8); + /* second order temperature compensation */ + if (tempms < 2000) { + t2 = (dt*dt) / (1<<31); + off2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<1); + sens2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<2); + if (tempms < -1500) { + off2 = off2 + 7 * (int64_t)(tempms+1500)*(tempms+1500); + sens2 = sens2 + 11 * ((int64_t)(tempms+1500)*(tempms+1500)) / (1<<1); + } + tempms = tempms - t2; + off = off - off2; + sens = sens - sens2; + } + + /* temperature in deg Celsius with 0.01 degC resolultion */ + ms->temperature = (int32_t)tempms; + /* temperature compensated pressure in Pascal (0.01mbar) */ + ms->pressure = (uint32_t)((((int64_t)ms->d1 * sens) / (1<<21) - off) / (1<<15)); +} diff --git a/sw/airborne/peripherals/ms5611.h b/sw/airborne/peripherals/ms5611.h index ad3054e776..85958d5ac5 100644 --- a/sw/airborne/peripherals/ms5611.h +++ b/sw/airborne/peripherals/ms5611.h @@ -1,6 +1,5 @@ /* - * - * Copyright (C) 2012 Piotr Esden-Tempski + * Copyright (C) 2013 Felix Ruess * * This file is part of paparazzi. * @@ -20,82 +19,44 @@ * Boston, MA 02111-1307, USA. */ -/* Register definition for MS5611 +/** + * @file peripherals/ms5611.h + * + * MS5611 barometer driver common interface (I2C and SPI). */ #ifndef MS5611_H #define MS5611_H -/* default i2c address - * when CSB is set to GND addr is 0xEE - * when CSB is set to VCC addr is 0xEC - * - * Note: Aspirin 2.1 has CSB bound to GND. - */ -#define MS5611_SLAVE_ADDR 0xEE +#include "std.h" -/* FIXME: For backwards compatibility with Aspirin driver (it doesnt talk to baro either) */ -#define MS5611_ADDR0 0x77 -#define MS5611_ADDR1 0x76 +/* Include address and register definition */ +#include "peripherals/ms5611_regs.h" -/* SPI SLAVE3 is on pin PC13 - * Aspirin 2.2 has ms5611 on SPI bus - */ -#ifndef MS5611_SLAVE_DEV -#define MS5611_SLAVE_DEV SPI_SLAVE3 -#endif -/* Number of 16bit calibration coefficients */ -#define PROM_NB 8 - -/* OSR definitions */ -#define MS5611_OSR256 0x02 -#define MS5611_OSR512 0x02 -#define MS5611_OSR1024 0x04 -#define MS5611_OSR2048 0x06 -#define MS5611_OSR4096 0x08 - -/* D1 Register defines */ -#define MS5611_REG_D1R 0x40 // Request D1 (pressure) conversion -#define MS5611_REG_D1(_osr) (MS5611_REG_D1R | _osr) -#define MS5611_REG_D1OSR256 MS5611_REG_D1(MS5611_ORS256) -#define MS5611_REG_D1OSR512 MS5611_REG_D1(MS5611_OSR512) -#define MS5611_REG_D1OSR1024 MS5611_REG_D1(MS5611_OSR1024) -#define MS5611_REG_D1OSR2048 MS5611_REG_D1(MS5611_OSR2048) -#define MS5611_REG_D1OSR4096 MS5611_REG_D1(MS5611_OSR4096) - -/* D2 register defines */ -#define MS5611_REG_D2R 0x50 // Request D2 (temperature) conversion -#define MS5611_REG_D2(_osr) (MS5611_REG_D2R | _osr) -#define MS5611_REG_D2OSR256 MS5611_REG_D2(MS5611_ORS256) -#define MS5611_REG_D2OSR512 MS5611_REG_D2(MS5611_OSR512) -#define MS5611_REG_D2OSR1024 MS5611_REG_D2(MS5611_OSR1024) -#define MS5611_REG_D2OSR2048 MS5611_REG_D2(MS5611_OSR2048) -#define MS5611_REG_D2OSR4096 MS5611_REG_D2(MS5611_OSR4096) - -/* Commands */ -#define MS5611_ADC_READ 0x00 // Read converted value -#define MS5611_SOFT_RESET 0x1E // Reset command -#define MS5611_PROM_READ 0xA0 // Start reading PROM -#define MS5611_START_CONV_D1 MS5611_REG_D1OSR4096 /* we use OSR=4096 for maximum resolution */ -#define MS5611_START_CONV_D2 MS5611_REG_D2OSR4096 /* we use OSR=4096 for maximum resolution */ - -/* FIXME: backwards compatibility with Aspirin driver */ -#define MS5611_REG_RESET MS5611_SOFT_RESET -#define MS5611_REG_ADCREAD MS5611_ADC_READ - -enum ms5611_stat{ - MS5611_UNINIT, - MS5611_RESET, - MS5611_RESET_OK, - MS5611_PROM, - MS5611_IDLE, - MS5611_CONV_D1, - MS5611_CONV_D1_OK, - MS5611_ADC_D1, - MS5611_CONV_D2, - MS5611_CONV_D2_OK, - MS5611_ADC_D2 +enum Ms5611Status { + MS5611_STATUS_UNINIT, + MS5611_STATUS_RESET, + MS5611_STATUS_RESET_OK, + MS5611_STATUS_PROM, + MS5611_STATUS_IDLE, + MS5611_STATUS_CONV_D1, + MS5611_STATUS_CONV_D1_OK, + MS5611_STATUS_ADC_D1, + MS5611_STATUS_CONV_D2, + MS5611_STATUS_CONV_D2_OK, + MS5611_STATUS_ADC_D2 }; +struct Ms5611Data { + uint32_t pressure; ///< pressure in Pascal (0.01mbar) + int32_t temperature; ///< temperature with 0.01 degrees Celsius resolution + uint16_t c[PROM_NB]; + uint32_t d1; + uint32_t d2; +}; + +extern bool_t ms5611_prom_crc_ok(uint16_t* prom); +extern void ms5611_calc(struct Ms5611Data* ms); + #endif /* MS5611_H */ diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c new file mode 100644 index 0000000000..4b248ffe12 --- /dev/null +++ b/sw/airborne/peripherals/ms5611_i2c.c @@ -0,0 +1,189 @@ +/* + * Copyright (C) 2011 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/ms5611_i2c.c + * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for I2C. + * + */ + + +#include "peripherals/ms5611_i2c.h" + + +void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t addr) +{ + /* set i2c_peripheral */ + ms->i2c_p = i2c_p; + + /* slave address */ + ms->i2c_trans.slave_addr = addr; + /* set inital status: Success or Done */ + ms->i2c_trans.status = I2CTransDone; + + ms->data_available = FALSE; + ms->initialized = FALSE; + ms->status = MS5611_STATUS_UNINIT; + ms->prom_cnt = 0; +} + +void ms5611_i2c_start_configure(struct Ms5611_I2c *ms) +{ + if (ms->status == MS5611_STATUS_UNINIT) { + ms->i2c_trans.buf[0] = MS5611_SOFT_RESET; + i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); + ms->status = MS5611_STATUS_RESET; + } +} + +void ms5611_i2c_start_conversion(struct Ms5611_I2c *ms) +{ + if (ms->status == MS5611_STATUS_IDLE && + ms->i2c_trans.status == I2CTransDone) { + /* start D1 conversion */ + ms->i2c_trans.buf[0] = MS5611_START_CONV_D1; + i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); + ms->status = MS5611_STATUS_CONV_D1; + } +} + +/** + * Periodic function to ensure proper delay after triggering reset or conversion. + * Should run at 100Hz max. + * Typical conversion time is 8.22ms at max resolution. + */ +void ms5611_i2c_periodic_check(struct Ms5611_I2c *ms) +{ + switch (ms->status) { + case MS5611_STATUS_RESET: + ms->status = MS5611_STATUS_RESET_OK; + break; + case MS5611_STATUS_RESET_OK: + if (ms->i2c_trans.status == I2CTransDone) { + /* start getting prom data */ + ms->i2c_trans.buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); + i2c_transceive(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1, 2); + ms->status = MS5611_STATUS_PROM; + } + break; + case MS5611_STATUS_CONV_D1: + ms->status = MS5611_STATUS_CONV_D1_OK; + break; + case MS5611_STATUS_CONV_D1_OK: + if (ms->i2c_trans.status == I2CTransDone) { + /* read D1 adc */ + ms->i2c_trans.buf[0] = MS5611_ADC_READ; + i2c_transceive(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1, 3); + ms->status = MS5611_STATUS_ADC_D1; + } + break; + case MS5611_STATUS_CONV_D2: + ms->status = MS5611_STATUS_CONV_D2_OK; + break; + case MS5611_STATUS_CONV_D2_OK: + if (ms->i2c_trans.status == I2CTransDone) { + /* read D2 adc */ + ms->i2c_trans.buf[0] = MS5611_ADC_READ; + i2c_transceive(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1, 3); + ms->status = MS5611_STATUS_ADC_D2; + } + break; + default: + break; + } +} + +void ms5611_i2c_event(struct Ms5611_I2c *ms) { + if (ms->initialized) { + if (ms->i2c_trans.status == I2CTransFailed) { + ms->i2c_trans.status = I2CTransDone; + } + else if (ms->i2c_trans.status == I2CTransSuccess) { + // Successfull reading + switch (ms->status) { + + case MS5611_STATUS_PROM: + /* read prom data */ + ms->data.c[ms->prom_cnt++] = (ms->i2c_trans.buf[0] << 8) | + ms->i2c_trans.buf[1]; + if (ms->prom_cnt < PROM_NB) { + /* get next prom data */ + ms->i2c_trans.buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); + i2c_transceive(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1, 2); + } + else { + /* done reading prom, check prom crc */ + if (ms5611_prom_crc_ok(ms->data.c)) { + ms->initialized = TRUE; + ms->status = MS5611_STATUS_IDLE; + } + else { + /* checksum error, try again */ + ms->prom_cnt = 0; + ms->status = MS5611_STATUS_UNINIT; + } + } + break; + + case MS5611_STATUS_ADC_D1: + /* read D1 (pressure) */ + ms->data.d1 = (ms->i2c_trans.buf[0] << 16) | + (ms->i2c_trans.buf[1] << 8) | + ms->i2c_trans.buf[2]; + /* start D2 conversion */ + ms->i2c_trans.buf[0] = MS5611_START_CONV_D2; + i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); + ms->status = MS5611_STATUS_CONV_D2; + break; + + case MS5611_STATUS_ADC_D2: + /* read D2 (temperature) */ + ms->data.d2 = (ms->i2c_trans.buf[0] << 16) | + (ms->i2c_trans.buf[1] << 8) | + ms->i2c_trans.buf[2]; + /* calculate temp and pressure from measurements */ + ms5611_calc(&(ms->data)); + ms->status = MS5611_STATUS_IDLE; + ms->data_available = TRUE; + break; + + default: + break; + } + ms->i2c_trans.status = I2CTransDone; + } + } + else if (ms->status != MS5611_STATUS_UNINIT) { // Configuring but not yet initialized + switch (ms->i2c_trans.status) { + case I2CTransFailed: + /* try again */ + ms->prom_cnt = 0; + ms->status = MS5611_STATUS_UNINIT; + case I2CTransSuccess: + case I2CTransDone: + ms->i2c_trans.status = I2CTransDone; + break; + default: + break; + } + } +} diff --git a/sw/airborne/peripherals/ms5611_i2c.h b/sw/airborne/peripherals/ms5611_i2c.h new file mode 100644 index 0000000000..614e3c605b --- /dev/null +++ b/sw/airborne/peripherals/ms5611_i2c.h @@ -0,0 +1,63 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/ms5611_i2c.h + * + * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for I2C. + */ + +#ifndef MS5611_I2C_H +#define MS5611_I2C_H + +#include "mcu_periph/i2c.h" + +/* Include common MS5611 definitions */ +#include "peripherals/ms5611.h" + +struct Ms5611_I2c { + struct i2c_periph *i2c_p; + struct i2c_transaction i2c_trans; + enum Ms5611Status status; + bool_t initialized; ///< config done flag + volatile bool_t data_available; ///< data ready flag + struct Ms5611Data data; + int32_t prom_cnt; ///< number of bytes read from PROM +}; + +// Functions +extern void ms5611_i2c_init(struct Ms5611_I2c* ms, struct i2c_periph* i2c_p, uint8_t addr); +extern void ms5611_i2c_start_configure(struct Ms5611_I2c* ms); +extern void ms5611_i2c_start_conversion(struct Ms5611_I2c* ms); +extern void ms5611_i2c_periodic_check(struct Ms5611_I2c* ms); +extern void ms5611_i2c_event(struct Ms5611_I2c* ms); + +/// convenience function: trigger read or start configuration if not already initialized +static inline void ms5611_i2c_periodic(struct Ms5611_I2c* ms) { + if (ms->initialized) + ms5611_i2c_start_conversion(ms); + else + ms5611_i2c_start_configure(ms); + ms5611_i2c_periodic_check(ms); +} + + +#endif /* MS5611_I2C_H */ diff --git a/sw/airborne/peripherals/ms5611_regs.h b/sw/airborne/peripherals/ms5611_regs.h new file mode 100644 index 0000000000..6cd3eb1fe2 --- /dev/null +++ b/sw/airborne/peripherals/ms5611_regs.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2012 Piotr Esden-Tempski + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/ms5611_regs.h + * Register definitions for MS5611 barometer. + */ + +#ifndef MS5611_REGS_H +#define MS5611_REGS_H + +/** default i2c address + * when CSB is set to GND addr is 0xEE + * when CSB is set to VCC addr is 0xEC + */ +#define MS5611_I2C_SLAVE_ADDR 0xEE +#define MS5611_I2C_SLAVE_ADDR_ALT 0xEC + +/* Number of 16bit calibration coefficients */ +#define PROM_NB 8 + +/* OSR definitions */ +#define MS5611_OSR256 0x02 +#define MS5611_OSR512 0x02 +#define MS5611_OSR1024 0x04 +#define MS5611_OSR2048 0x06 +#define MS5611_OSR4096 0x08 + +/* D1 Register defines */ +#define MS5611_REG_D1R 0x40 // Request D1 (pressure) conversion +#define MS5611_REG_D1(_osr) (MS5611_REG_D1R | _osr) +#define MS5611_REG_D1OSR256 MS5611_REG_D1(MS5611_ORS256) +#define MS5611_REG_D1OSR512 MS5611_REG_D1(MS5611_OSR512) +#define MS5611_REG_D1OSR1024 MS5611_REG_D1(MS5611_OSR1024) +#define MS5611_REG_D1OSR2048 MS5611_REG_D1(MS5611_OSR2048) +#define MS5611_REG_D1OSR4096 MS5611_REG_D1(MS5611_OSR4096) + +/* D2 register defines */ +#define MS5611_REG_D2R 0x50 // Request D2 (temperature) conversion +#define MS5611_REG_D2(_osr) (MS5611_REG_D2R | _osr) +#define MS5611_REG_D2OSR256 MS5611_REG_D2(MS5611_ORS256) +#define MS5611_REG_D2OSR512 MS5611_REG_D2(MS5611_OSR512) +#define MS5611_REG_D2OSR1024 MS5611_REG_D2(MS5611_OSR1024) +#define MS5611_REG_D2OSR2048 MS5611_REG_D2(MS5611_OSR2048) +#define MS5611_REG_D2OSR4096 MS5611_REG_D2(MS5611_OSR4096) + +/* Commands */ +#define MS5611_ADC_READ 0x00 // Read converted value +#define MS5611_SOFT_RESET 0x1E // Reset command +#define MS5611_PROM_READ 0xA0 // Start reading PROM +#define MS5611_START_CONV_D1 MS5611_REG_D1OSR4096 /* we use OSR=4096 for maximum resolution */ +#define MS5611_START_CONV_D2 MS5611_REG_D2OSR4096 /* we use OSR=4096 for maximum resolution */ + +#endif /* MS5611_REGS_H */ diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c new file mode 100644 index 0000000000..bcf7d129d4 --- /dev/null +++ b/sw/airborne/peripherals/ms5611_spi.c @@ -0,0 +1,203 @@ +/* + * Copyright (C) 2011 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/ms5611_spi.c + * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for SPI. + * + */ + + +#include "peripherals/ms5611_spi.h" + + +void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t slave_idx) +{ + /* set spi_peripheral */ + ms->spi_p = spi_p; + + /* configure spi transaction */ + ms->spi_trans.cpol = SPICpolIdleHigh; + ms->spi_trans.cpha = SPICphaEdge2; + ms->spi_trans.dss = SPIDss8bit; + ms->spi_trans.bitorder = SPIMSBFirst; + ms->spi_trans.cdiv = SPIDiv64; + + ms->spi_trans.select = SPISelectUnselect; + ms->spi_trans.slave_idx = slave_idx; + ms->spi_trans.output_length = 1; + ms->spi_trans.input_length = 4; + ms->spi_trans.before_cb = NULL; + ms->spi_trans.after_cb = NULL; + ms->spi_trans.input_buf = ms->rx_buf; + ms->spi_trans.output_buf = ms->tx_buf; + + /* set inital status: Success or Done */ + ms->spi_trans.status = SPITransDone; + + ms->data_available = FALSE; + ms->initialized = FALSE; + ms->status = MS5611_STATUS_UNINIT; + ms->prom_cnt = 0; +} + +void ms5611_spi_start_configure(struct Ms5611_Spi *ms) +{ + if (ms->status == MS5611_STATUS_UNINIT) { + ms->tx_buf[0] = MS5611_SOFT_RESET; + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_RESET; + } +} + +void ms5611_spi_start_conversion(struct Ms5611_Spi *ms) +{ + if (ms->status == MS5611_STATUS_IDLE && + ms->spi_trans.status == SPITransDone) { + /* start D1 conversion */ + ms->tx_buf[0] = MS5611_START_CONV_D1; + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_CONV_D1; + } +} + +/** + * Periodic function to ensure proper delay after triggering reset or conversion. + * Should run at 100Hz max. + * Typical conversion time is 8.22ms at max resolution. + */ +void ms5611_spi_periodic_check(struct Ms5611_Spi *ms) +{ + switch (ms->status) { + case MS5611_STATUS_RESET: + ms->status = MS5611_STATUS_RESET_OK; + break; + case MS5611_STATUS_RESET_OK: + if (ms->spi_trans.status == SPITransDone) { + /* start getting prom data */ + ms->tx_buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_PROM; + } + break; + case MS5611_STATUS_CONV_D1: + ms->status = MS5611_STATUS_CONV_D1_OK; + break; + case MS5611_STATUS_CONV_D1_OK: + if (ms->spi_trans.status == SPITransDone) { + /* read D1 adc */ + ms->tx_buf[0] = MS5611_ADC_READ; + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_ADC_D1; + } + break; + case MS5611_STATUS_CONV_D2: + ms->status = MS5611_STATUS_CONV_D2_OK; + break; + case MS5611_STATUS_CONV_D2_OK: + if (ms->spi_trans.status == SPITransDone) { + /* read D2 adc */ + ms->tx_buf[0] = MS5611_ADC_READ; + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_ADC_D2; + } + break; + default: + break; + } +} + +void ms5611_spi_event(struct Ms5611_Spi *ms) { + if (ms->initialized) { + if (ms->spi_trans.status == SPITransFailed) { + ms->spi_trans.status = SPITransDone; + } + else if (ms->spi_trans.status == SPITransSuccess) { + // Successfull reading + switch (ms->status) { + + case MS5611_STATUS_PROM: + /* read prom data */ + ms->data.c[ms->prom_cnt++] = (ms->rx_buf[1] << 8) | + ms->rx_buf[2]; + if (ms->prom_cnt < PROM_NB) { + /* get next prom data */ + ms->tx_buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); + spi_submit(ms->spi_p, &(ms->spi_trans)); + } + else { + /* done reading prom, check prom crc */ + if (ms5611_prom_crc_ok(ms->data.c)) { + ms->initialized = TRUE; + ms->status = MS5611_STATUS_IDLE; + } + else { + /* checksum error, try again */ + ms->prom_cnt = 0; + ms->status = MS5611_STATUS_UNINIT; + } + } + break; + + case MS5611_STATUS_ADC_D1: + /* read D1 (pressure) */ + ms->data.d1 = (ms->rx_buf[1] << 16) | + (ms->rx_buf[2] << 8) | + ms->rx_buf[3]; + /* start D2 conversion */ + ms->tx_buf[0] = MS5611_START_CONV_D2; + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_CONV_D2; + break; + + case MS5611_STATUS_ADC_D2: + /* read D2 (temperature) */ + ms->data.d2 = (ms->rx_buf[1] << 16) | + (ms->rx_buf[2] << 8) | + ms->rx_buf[3]; + /* calculate temp and pressure from measurements */ + ms5611_calc(&(ms->data)); + ms->status = MS5611_STATUS_IDLE; + ms->data_available = TRUE; + break; + + default: + break; + } + ms->spi_trans.status = SPITransDone; + } + } + else if (ms->status != MS5611_STATUS_UNINIT) { // Configuring but not yet initialized + switch (ms->spi_trans.status) { + case SPITransFailed: + /* try again */ + ms->prom_cnt = 0; + ms->status = MS5611_STATUS_UNINIT; + case SPITransSuccess: + case SPITransDone: + ms->spi_trans.status = SPITransDone; + break; + default: + break; + } + } +} diff --git a/sw/airborne/peripherals/ms5611_spi.h b/sw/airborne/peripherals/ms5611_spi.h new file mode 100644 index 0000000000..8e0b42c1b2 --- /dev/null +++ b/sw/airborne/peripherals/ms5611_spi.h @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/ms5611_spi.h + * + * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for SPI. + */ + +#ifndef MS5611_SPI_H +#define MS5611_SPI_H + +#include "mcu_periph/spi.h" + +/* Include common MS5611 definitions */ +#include "peripherals/ms5611.h" + +struct Ms5611_Spi { + struct spi_periph *spi_p; + struct spi_transaction spi_trans; + volatile uint8_t tx_buf[1]; + volatile uint8_t rx_buf[4]; + enum Ms5611Status status; + bool_t initialized; ///< config done flag + volatile bool_t data_available; ///< data ready flag + struct Ms5611Data data; + int32_t prom_cnt; ///< number of bytes read from PROM +}; + +// Functions +extern void ms5611_spi_init(struct Ms5611_Spi* ms, struct spi_periph* spi_p, uint8_t addr); +extern void ms5611_spi_start_configure(struct Ms5611_Spi* ms); +extern void ms5611_spi_start_conversion(struct Ms5611_Spi* ms); +extern void ms5611_spi_periodic_check(struct Ms5611_Spi* ms); +extern void ms5611_spi_event(struct Ms5611_Spi* ms); + +/// convenience function: trigger read or start configuration if not already initialized +static inline void ms5611_spi_periodic(struct Ms5611_Spi* ms) { + if (ms->initialized) + ms5611_spi_start_conversion(ms); + else + ms5611_spi_start_configure(ms); + ms5611_spi_periodic_check(ms); +} + + +#endif /* MS5611_SPI_H */ From 24d30e116073db32e8679b360ec6679d7aaf3f54 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 13:52:37 +0200 Subject: [PATCH 123/309] [modules] baro_ms5611_i2c|spi modules using ms5611 peripheral --- conf/modules/baro_ms5611_i2c.xml | 6 +- conf/modules/baro_ms5611_spi.xml | 24 +++ sw/airborne/modules/sensors/baro_ms5611_i2c.c | 203 +++--------------- sw/airborne/modules/sensors/baro_ms5611_i2c.h | 37 +--- sw/airborne/modules/sensors/baro_ms5611_spi.c | 109 ++++++++++ sw/airborne/modules/sensors/baro_ms5611_spi.h | 56 +++++ 6 files changed, 232 insertions(+), 203 deletions(-) create mode 100644 conf/modules/baro_ms5611_spi.xml create mode 100644 sw/airborne/modules/sensors/baro_ms5611_spi.c create mode 100644 sw/airborne/modules/sensors/baro_ms5611_spi.h diff --git a/conf/modules/baro_ms5611_i2c.xml b/conf/modules/baro_ms5611_i2c.xml index 412c725338..c7ea554422 100644 --- a/conf/modules/baro_ms5611_i2c.xml +++ b/conf/modules/baro_ms5611_i2c.xml @@ -13,12 +13,12 @@ - - - + + + diff --git a/conf/modules/baro_ms5611_spi.xml b/conf/modules/baro_ms5611_spi.xml new file mode 100644 index 0000000000..335ac840fd --- /dev/null +++ b/conf/modules/baro_ms5611_spi.xml @@ -0,0 +1,24 @@ + + + + + + Baro MS5611 (SPI) + Measurement Specialties MS5611-01BA pressure sensor (SPI) + + + + + +
+ +
+ + + + + + + + +
diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.c b/sw/airborne/modules/sensors/baro_ms5611_i2c.c index e7e2f1c423..c87794f160 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2011 Martin Mueller + * Copyright (C) 2011-2013 The Paparazzi Team * * This file is part of paparazzi. * @@ -30,11 +30,9 @@ #include "modules/sensors/baro_ms5611_i2c.h" #include "mcu_periph/sys_time.h" -#include "mcu_periph/i2c.h" #include "mcu_periph/uart.h" #include "messages.h" #include "subsystems/datalink/downlink.h" -#include "subsystems/nav.h" #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE @@ -49,202 +47,63 @@ #define MS5611_SLAVE_ADDR 0xEE #endif +struct Ms5611_I2c baro_ms5611; -struct i2c_transaction ms5611_trans; -uint8_t ms5611_status; -uint16_t ms5611_c[PROM_NB]; -uint32_t ms5611_d1, ms5611_d2; -int32_t prom_cnt; -int64_t baroms; float fbaroms, ftempms; float baro_ms5611_alt; +bool_t baro_ms5611_alt_valid; bool_t baro_ms5611_enabled; -bool_t baro_ms5611_valid; + float baro_ms5611_r; float baro_ms5611_sigma2; -static int8_t baro_ms5611_crc(uint16_t* prom) { - int32_t i, j; - uint32_t res = 0; - uint8_t crc = prom[7] & 0xF; - prom[7] &= 0xFF00; - for (i = 0; i < 16; i++) { - if (i & 1) res ^= ((prom[i>>1]) & 0x00FF); - else res ^= (prom[i>>1]>>8); - for (j = 8; j > 0; j--) { - if (res & 0x8000) res ^= 0x1800; - res <<= 1; - } - } - prom[7] |= crc; - if (crc == ((res >> 12) & 0xF)) return 0; - else return -1; -} void baro_ms5611_init(void) { + ms5611_i2c_init(&baro_ms5611, &MS5611_I2C_DEV, MS5611_SLAVE_ADDR); + baro_ms5611_enabled = TRUE; - baro_ms5611_valid = FALSE; - ms5611_status = MS5611_UNINIT; + baro_ms5611_alt_valid = FALSE; + baro_ms5611_r = BARO_MS5611_R; baro_ms5611_sigma2 = BARO_MS5611_SIGMA2; - prom_cnt = 0; } void baro_ms5611_periodic( void ) { if (sys_time.nb_sec > 1) { - if (ms5611_status >= MS5611_IDLE) { - /* start D1 conversion */ - ms5611_status = MS5611_CONV_D1; - ms5611_trans.buf[0] = MS5611_START_CONV_D1; - i2c_transmit(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1); + + /* call the convenience periodic that initializes the sensor and starts reading*/ + ms5611_i2c_periodic(&baro_ms5611); + + if (baro_ms5611.initialized) { RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &ms5611_c[0], &ms5611_c[1], &ms5611_c[2], &ms5611_c[3], - &ms5611_c[4], &ms5611_c[5], &ms5611_c[6], &ms5611_c[7])); - } - else if (ms5611_status == MS5611_UNINIT) { - /* reset sensor */ - ms5611_status = MS5611_RESET; - ms5611_trans.buf[0] = MS5611_SOFT_RESET; - i2c_transmit(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1); - } - else if (ms5611_status == MS5611_RESET_OK) { - /* start getting prom data */ - ms5611_status = MS5611_PROM; - ms5611_trans.buf[0] = MS5611_PROM_READ | (prom_cnt << 1); - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 2); + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7])); } } } -void baro_ms5611_d1( void ) { - if (sys_time.nb_sec > 1) { - if (ms5611_status == MS5611_CONV_D1_OK) { - /* read D1 adc */ - ms5611_status = MS5611_ADC_D1; - ms5611_trans.buf[0] = MS5611_ADC_READ; - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 3); - } - } -} - -void baro_ms5611_d2( void ) { - if (sys_time.nb_sec > 1) { - if (ms5611_status == MS5611_CONV_D2_OK) { - /* read D2 adc */ - ms5611_status = MS5611_ADC_D2; - ms5611_trans.buf[0] = MS5611_ADC_READ; - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 3); - } - } -} void baro_ms5611_event( void ) { - if (ms5611_trans.status == I2CTransSuccess) { - switch (ms5611_status) { - case MS5611_RESET: - ms5611_status = MS5611_RESET_OK; - ms5611_trans.status = I2CTransDone; - break; + ms5611_i2c_event(&baro_ms5611); - case MS5611_PROM: - /* read prom data */ - ms5611_c[prom_cnt++] = (ms5611_trans.buf[0] << 8) | ms5611_trans.buf[1]; - if (prom_cnt < PROM_NB) { - /* get next prom data */ - ms5611_trans.buf[0] = MS5611_PROM_READ | (prom_cnt << 1); - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 2); - } - else { - /* done reading prom */ - ms5611_trans.status = I2CTransDone; - /* check prom crc */ - if (baro_ms5611_crc(ms5611_c) == 0) { - DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &ms5611_c[0], &ms5611_c[1], &ms5611_c[2], &ms5611_c[3], - &ms5611_c[4], &ms5611_c[5], &ms5611_c[6], &ms5611_c[7]); - ms5611_status = MS5611_IDLE; - } - else { - /* checksum error, try again */ - baro_ms5611_init(); - } - } - break; - - case MS5611_CONV_D1: - ms5611_status = MS5611_CONV_D1_OK; - ms5611_trans.status = I2CTransDone; - break; - - case MS5611_ADC_D1: - /* read D1 (pressure) */ - ms5611_d1 = (ms5611_trans.buf[0] << 16) | - (ms5611_trans.buf[1] << 8) | - ms5611_trans.buf[2]; - /* start D2 conversion */ - ms5611_status = MS5611_CONV_D2; - ms5611_trans.buf[0] = MS5611_START_CONV_D2; - i2c_transmit(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1); - break; - - case MS5611_CONV_D2: - ms5611_status = MS5611_CONV_D2_OK; - ms5611_trans.status = I2CTransDone; - break; - - case MS5611_ADC_D2: { - int64_t dt, tempms, off, sens, t2, off2, sens2; - /* read D2 (temperature) */ - ms5611_d2 = (ms5611_trans.buf[0] << 16) | - (ms5611_trans.buf[1] << 8) | - ms5611_trans.buf[2]; - ms5611_status = MS5611_IDLE; - ms5611_trans.status = I2CTransDone; - - /* difference between actual and ref temperature */ - dt = ms5611_d2 - (int64_t)ms5611_c[5] * (1<<8); - /* actual temperature */ - tempms = 2000 + ((int64_t)dt * ms5611_c[6]) / (1<<23); - /* offset at actual temperature */ - off = ((int64_t)ms5611_c[2] * (1<<16)) + ((int64_t)ms5611_c[4] * dt) / (1<<7); - /* sensitivity at actual temperature */ - sens = ((int64_t)ms5611_c[1] * (1<<15)) + ((int64_t)ms5611_c[3] * dt) / (1<<8); - /* second order temperature compensation */ - if (tempms < 2000) { - t2 = (dt*dt) / (1<<31); - off2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<1); - sens2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<2); - if (tempms < -1500) { - off2 = off2 + 7 * (int64_t)(tempms+1500)*(tempms+1500); - sens2 = sens2 + 11 * ((int64_t)(tempms+1500)*(tempms+1500)) / (1<<1); - } - tempms = tempms - t2; - off = off - off2; - sens = sens - sens2; - } - /* temperature compensated pressure */ - baroms = (((int64_t)ms5611_d1 * sens) / (1<<21) - off) / (1<<15); - - float tmp_float = baroms/101325.0; //pressure at sea level - tmp_float = pow(tmp_float,0.190295); //eleva pressao ao expoente - baro_ms5611_alt = 44330*(1.0-tmp_float); //altitude above MSL - - baro_ms5611_valid = TRUE; + if (baro_ms5611.data_available) { + float tmp_float = baro_ms5611.data.pressure / 101325.0; //pressure at sea level + tmp_float = pow(tmp_float, 0.190295); + baro_ms5611_alt = 44330 * (1.0 - tmp_float); //altitude above MSL + baro_ms5611_alt_valid = TRUE; #ifdef SENSOR_SYNC_SEND - ftempms = tempms / 100.; - fbaroms = baroms / 100.; - DOWNLINK_SEND_BARO_MS5611(DefaultChannel, DefaultDevice, - &ms5611_d1, &ms5611_d2, &fbaroms, &ftempms); + ftempms = baro_ms5611.data.temperature / 100.; + fbaroms = baro_ms5611.data.pressure / 100.; + DOWNLINK_SEND_BARO_MS5611(DefaultChannel, DefaultDevice, + &baro_ms5611.data.d1, &baro_ms5611.data.d2, &fbaroms, &ftempms); #endif - - break; - } - - default: - ms5611_trans.status = I2CTransDone; - break; - } } } diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h index cad37d60db..0e16161a21 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.h +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.h @@ -2,46 +2,27 @@ #define BARO_MS56111_I2C_H #include "std.h" +#include "peripherals/ms5611_i2c.h" -/* we use OSR=4096 for maximum resolution */ -#define MS5611_SOFT_RESET 0x1E -#define MS5611_PROM_READ 0xA0 -#define MS5611_START_CONV_D1 0x48 -#define MS5611_START_CONV_D2 0x58 -#define MS5611_ADC_READ 0x00 - -#define PROM_NB 8 #define BARO_MS5611_DT 0.05 #define BARO_MS5611_R 20 #define BARO_MS5611_SIGMA2 1 -extern float baro_ms5611_alt; -extern bool_t baro_ms5611_valid; -extern bool_t baro_ms5611_enabled; extern float baro_ms5611_r; extern float baro_ms5611_sigma2; -extern int64_t baroms; -enum ms5611_stat{ - MS5611_UNINIT, - MS5611_RESET, - MS5611_RESET_OK, - MS5611_PROM, - MS5611_IDLE, - MS5611_CONV_D1, - MS5611_CONV_D1_OK, - MS5611_ADC_D1, - MS5611_CONV_D2, - MS5611_CONV_D2_OK, - MS5611_ADC_D2 -}; +extern float baro_ms5611_alt; +extern bool_t baro_ms5611_alt_valid; +extern bool_t baro_ms5611_enabled; + +extern struct Ms5611_I2c baro_ms5611; extern void baro_ms5611_init(void); extern void baro_ms5611_periodic(void); -extern void baro_ms5611_d1(void); -extern void baro_ms5611_d2(void); extern void baro_ms5611_event(void); -#define BaroMs5611Update(_b) { if (baro_ms5611_valid) { _b = baro_ms5611_alt; baro_ms5611_valid = FALSE; } } +#define BaroMs5611UpdatePressure(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; baro_ms5611.data_available = FALSE; } } + +#define BaroMs5611UpdateAlt(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611_alt; baro_ms5611.data_available = FALSE; } } #endif diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.c b/sw/airborne/modules/sensors/baro_ms5611_spi.c new file mode 100644 index 0000000000..0b0316b151 --- /dev/null +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.c @@ -0,0 +1,109 @@ +/* + * Copyright (C) 2011-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file modules/sensors/baro_ms5611_spi.c + * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for SPI. + * + */ + + +#include "modules/sensors/baro_ms5611_spi.h" + +#include "mcu_periph/sys_time.h" +#include "mcu_periph/uart.h" +#include "messages.h" +#include "subsystems/datalink/downlink.h" + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +#ifndef MS5611_SPI_DEV +#define MS5611_SPI_DEV spi1 +#endif + +#ifndef MS5611_SLAVE_DEV +#define MS5611_SLAVE_DEV SPI_SLAVE0 +#endif + + +struct Ms5611_Spi baro_ms5611; + +float fbaroms, ftempms; +float baro_ms5611_alt; +bool_t baro_ms5611_alt_valid; +bool_t baro_ms5611_enabled; + +float baro_ms5611_r; +float baro_ms5611_sigma2; + + +void baro_ms5611_init(void) { + ms5611_spi_init(&baro_ms5611, &MS5611_SPI_DEV, MS5611_SLAVE_DEV); + + baro_ms5611_enabled = TRUE; + baro_ms5611_alt_valid = FALSE; + + baro_ms5611_r = BARO_MS5611_R; + baro_ms5611_sigma2 = BARO_MS5611_SIGMA2; +} + +void baro_ms5611_periodic( void ) { + if (sys_time.nb_sec > 1) { + + /* call the convenience periodic that initializes the sensor and starts reading*/ + ms5611_spi_periodic(&baro_ms5611); + + if (baro_ms5611.initialized) { + RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7])); + } + } +} + + +void baro_ms5611_event( void ) { + + ms5611_spi_event(&baro_ms5611); + + if (baro_ms5611.data_available) { + float tmp_float = baro_ms5611.data.pressure / 101325.0; //pressure at sea level + tmp_float = pow(tmp_float, 0.190295); + baro_ms5611_alt = 44330 * (1.0 - tmp_float); //altitude above MSL + baro_ms5611_alt_valid = TRUE; + +#ifdef SENSOR_SYNC_SEND + ftempms = baro_ms5611.data.temperature / 100.; + fbaroms = baro_ms5611.data.pressure / 100.; + DOWNLINK_SEND_BARO_MS5611(DefaultChannel, DefaultDevice, + &baro_ms5611.data.d1, &baro_ms5611.data.d2, &fbaroms, &ftempms); +#endif + } +} diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.h b/sw/airborne/modules/sensors/baro_ms5611_spi.h new file mode 100644 index 0000000000..e752e7a250 --- /dev/null +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.h @@ -0,0 +1,56 @@ +/* + * Copyright (C) 2011 Martin Mueller + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file modules/sensors/baro_ms5611_spi.h + * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for SPI. + * + */ + +#ifndef BARO_MS56111_SPI_H +#define BARO_MS56111_SPI_H + +#include "std.h" +#include "peripherals/ms5611_spi.h" + + +#define BARO_MS5611_DT 0.05 +#define BARO_MS5611_R 20 +#define BARO_MS5611_SIGMA2 1 +extern float baro_ms5611_r; +extern float baro_ms5611_sigma2; + +extern float baro_ms5611_alt; +extern bool_t baro_ms5611_alt_valid; +extern bool_t baro_ms5611_enabled; + +extern struct Ms5611_Spi baro_ms5611; + +extern void baro_ms5611_init(void); +extern void baro_ms5611_periodic(void); +extern void baro_ms5611_event(void); + +#define BaroMs5611UpdatePressure(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; baro_ms5611.data_available = FALSE; } } + +#define BaroMs5611UpdateAlt(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611_alt; baro_ms5611.data_available = FALSE; } } + +#endif From 1ddc30549cab6348d02cb3abea025238da3e2f47 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 14:53:49 +0200 Subject: [PATCH 124/309] [boards] use ms5611 peripheral in lisa_m baro --- conf/firmwares/rotorcraft.makefile | 8 + sw/airborne/boards/lisa_m/baro_ms5611_i2c.c | 236 ++++++------------ sw/airborne/boards/lisa_m/baro_ms5611_spi.c | 256 ++++++-------------- 3 files changed, 147 insertions(+), 353 deletions(-) diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index 58b2b6187e..3616061a7c 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -172,9 +172,13 @@ LISA_M_BARO ?= BARO_BOARD_BMP085 ifeq ($(LISA_M_BARO), BARO_MS5611_SPI) include $(CFG_SHARED)/spi_master.makefile ap.CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3 + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_spi.c ap.srcs += $(SRC_BOARD)/baro_ms5611_spi.c else ifeq ($(LISA_M_BARO), BARO_MS5611_I2C) ap.CFLAGS += -DUSE_I2C2 + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_i2c.c ap.srcs += $(SRC_BOARD)/baro_ms5611_i2c.c else ifeq ($(LISA_M_BARO), BARO_BOARD_BMP085) ap.srcs += $(SRC_BOARD)/baro_board.c @@ -189,9 +193,13 @@ LIA_BARO ?= BARO_MS5611_SPI ifeq ($(LIA_BARO), BARO_MS5611_SPI) include $(CFG_SHARED)/spi_master.makefile ap.CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3 + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_spi.c ap.srcs += boards/lisa_m/baro_ms5611_spi.c else ifeq ($(LIA_BARO), BARO_MS5611_I2C) ap.CFLAGS += -DUSE_I2C2 + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_i2c.c ap.srcs += boards/lisa_m/baro_ms5611_i2c.c endif ap.CFLAGS += -D$(LIA_BARO) diff --git a/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c b/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c index 57c0ea103d..989096848a 100644 --- a/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c +++ b/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c @@ -1,16 +1,39 @@ -/** - * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for I2C +/* + * Copyright (C) 2011-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. * - * Edit by: Michal Podhradsky, michal.podhradsky@aggiemail.usu.edu - * Utah State University, http://aggieair.usu.edu/ */ + +/** + * @file boards/lisa_m/baro_ms5611_i2c.c + * + * Driver for MS5611 baro on LisaM/Aspirin2.1 via I2C. + * + */ + #include "subsystems/sensors/baro.h" -#include "peripherals/ms5611_regs.h" +#include "peripherals/ms5611_i2c.h" + +#include "mcu_periph/sys_time.h" #include "led.h" #include "std.h" -#include "mcu_periph/sys_time.h" -#include "mcu_periph/i2c.h" #ifndef MS5611_I2C_DEV #define MS5611_I2C_DEV i2c2 #endif @@ -23,192 +46,73 @@ */ #define MS5611_SLAVE_ADDR 0xEE + #ifdef DEBUG + #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE #endif #include "mcu_periph/uart.h" #include "messages.h" #include "subsystems/datalink/downlink.h" + +float fbaroms, ftempms; #endif struct Baro baro; -struct i2c_transaction ms5611_trans; -uint8_t ms5611_status; -int32_t prom_cnt; -uint16_t ms5611_c[PROM_NB]; -uint32_t ms5611_d1, ms5611_d2; -float fbaroms, ftempms; +struct Ms5611_I2c baro_ms5611; -static int8_t baro_ms5611_crc(uint16_t* prom) { - int32_t i, j; - uint32_t res = 0; - uint8_t crc = prom[7] & 0xF; - prom[7] &= 0xFF00; - for (i = 0; i < 16; i++) { - if (i & 1) res ^= ((prom[i>>1]) & 0x00FF); - else res ^= (prom[i>>1]>>8); - for (j = 8; j > 0; j--) { - if (res & 0x8000) res ^= 0x1800; - res <<= 1; - } - } - prom[7] |= crc; - if (crc == ((res >> 12) & 0xF)) return 0; - else return -1; -} void baro_init(void) { - ms5611_status = MS5611_UNINIT; baro.status = BS_UNINITIALIZED; - prom_cnt = 0; + baro.absolute = 0; + baro.differential = 0; + + ms5611_i2c_init(&baro_ms5611, &MS5611_I2C_DEV, MS5611_SLAVE_ADDR); } void baro_periodic(void) { if (sys_time.nb_sec > 1) { - if (ms5611_status == MS5611_IDLE) { - /* start D1 conversion */ - ms5611_status = MS5611_CONV_D1; - ms5611_trans.buf[0] = MS5611_START_CONV_D1; - i2c_transmit(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1); - #ifdef DEBUG - RunOnceEvery(60, { DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &ms5611_c[0], &ms5611_c[1], &ms5611_c[2], &ms5611_c[3], - &ms5611_c[4], &ms5611_c[5], &ms5611_c[6], &ms5611_c[7]);}); - #endif - } - else if (ms5611_status == MS5611_CONV_D1) { - /* assume D1 conversion is done */ - ms5611_status = MS5611_CONV_D1_OK; - } - else if (ms5611_status == MS5611_CONV_D1_OK) { - /* read D1 adc */ - ms5611_status = MS5611_ADC_D1; - ms5611_trans.buf[0] = MS5611_ADC_READ; - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 3); - } - else if (ms5611_status == MS5611_CONV_D2) { - /* assume D2 conversion is done */ - ms5611_status = MS5611_CONV_D2_OK; - } - else if (ms5611_status == MS5611_CONV_D2_OK) { - /* read D2 adc */ - ms5611_status = MS5611_ADC_D2; - ms5611_trans.buf[0] = MS5611_ADC_READ; - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 3); - } - else if (ms5611_status == MS5611_UNINIT) { - /* reset sensor */ - ms5611_status = MS5611_RESET; - ms5611_trans.buf[0] = MS5611_SOFT_RESET; - i2c_transmit(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1); - } - else if (ms5611_status == MS5611_RESET_OK) { - /* start getting prom data */ - ms5611_status = MS5611_PROM; - ms5611_trans.buf[0] = MS5611_PROM_READ | (prom_cnt << 1); - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 2); + + /* call the convenience periodic that initializes the sensor and starts reading*/ + ms5611_i2c_periodic(&baro_ms5611); + + if (baro_ms5611.initialized) { + baro.status = BS_RUNNING; +#if DEBUG + RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7])); +#endif } } } void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)){ - if (ms5611_trans.status == I2CTransSuccess) { - #ifdef ROTORCRAFT_BARO_LED - RunOnceEvery(10,LED_TOGGLE(ROTORCRAFT_BARO_LED)); - #endif - switch (ms5611_status) { - - case MS5611_RESET: - ms5611_status = MS5611_RESET_OK; - ms5611_trans.status = I2CTransDone; - break; - - case MS5611_PROM: - /* read prom data */ - ms5611_c[prom_cnt++] = (ms5611_trans.buf[0] << 8) | ms5611_trans.buf[1]; - if (prom_cnt < PROM_NB) {//8 bytes at PROM - /* get next prom data */ - ms5611_trans.buf[0] = MS5611_PROM_READ | (prom_cnt << 1); - i2c_transceive(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1, 2); - } - else { - /* done reading prom */ - ms5611_trans.status = I2CTransDone; - /* check prom crc */ - if (baro_ms5611_crc(ms5611_c) == 0) { - ms5611_status = MS5611_IDLE; - baro.status = BS_RUNNING; - } - else { - /* checksum error, try again */ - baro_init(); - } - } - break; - - case MS5611_ADC_D1: - /* read D1 (pressure) */ - ms5611_d1 = (ms5611_trans.buf[0] << 16) | - (ms5611_trans.buf[1] << 8) | - ms5611_trans.buf[2]; - /* start D2 conversion */ - ms5611_status = MS5611_CONV_D2; - ms5611_trans.buf[0] = MS5611_START_CONV_D2; - i2c_transmit(&MS5611_I2C_DEV, &ms5611_trans, MS5611_SLAVE_ADDR, 1); - break; - - case MS5611_ADC_D2: { - int64_t dt, baroms, tempms, off, sens, t2, off2, sens2; - /* read D2 (temperature) */ - ms5611_d2 = (ms5611_trans.buf[0] << 16) | - (ms5611_trans.buf[1] << 8) | - ms5611_trans.buf[2]; - ms5611_status = MS5611_IDLE; - ms5611_trans.status = I2CTransDone; - - /* difference between actual and ref temperature */ - dt = ms5611_d2 - (int64_t)ms5611_c[5] * (1<<8); - /* actual temperature */ - tempms = 2000 + ((int64_t)dt * ms5611_c[6]) / (1<<23); - /* offset at actual temperature */ - off = ((int64_t)ms5611_c[2] * (1<<16)) + ((int64_t)ms5611_c[4] * dt) / (1<<7); - /* sensitivity at actual temperature */ - sens = ((int64_t)ms5611_c[1] * (1<<15)) + ((int64_t)ms5611_c[3] * dt) / (1<<8); - /* second order temperature compensation */ - if (tempms < 2000) { - t2 = (dt*dt) / (1<<31); - off2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<1); - sens2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<2); - if (tempms < -1500) { - off2 = off2 + 7 * (int64_t)(tempms+1500)*(tempms+1500); - sens2 = sens2 + 11 * ((int64_t)(tempms+1500)*(tempms+1500)) / (1<<1); - } - tempms = tempms - t2; - off = off - off2; - sens = sens - sens2; - } - /* temperature compensated pressure */ - baroms = (((int64_t)ms5611_d1 * sens) / (1<<21) - off) / (1<<15); - - /* Update baro structure */ - baro.absolute = (int32_t)baroms; + if (sys_time.nb_sec > 1) { + ms5611_i2c_event(&baro_ms5611); + if (baro_ms5611.data_available) { b_abs_handler(); - b_diff_handler(); + baro_ms5611.data_available = FALSE; - #ifdef DEBUG - ftempms = tempms / 100.; - fbaroms = baroms / 100.; +#ifdef ROTORCRAFT_BARO_LED + RunOnceEvery(10,LED_TOGGLE(ROTORCRAFT_BARO_LED)); +#endif + +#if DEBUG + ftempms = baro_ms5611.data.temperature / 100.; + fbaroms = baro_ms5611.data.pressure / 100.; DOWNLINK_SEND_BARO_MS5611(DefaultChannel, DefaultDevice, - &ms5611_d1, &ms5611_d2, &fbaroms, &ftempms, &baro.status); - #endif - break; - } - - default: - ms5611_trans.status = I2CTransDone; - break; + &baro_ms5611.data.d1, &baro_ms5611.data.d2, + &fbaroms, &ftempms); +#endif } } } diff --git a/sw/airborne/boards/lisa_m/baro_ms5611_spi.c b/sw/airborne/boards/lisa_m/baro_ms5611_spi.c index 4e58c10605..84091d5a04 100644 --- a/sw/airborne/boards/lisa_m/baro_ms5611_spi.c +++ b/sw/airborne/boards/lisa_m/baro_ms5611_spi.c @@ -1,16 +1,39 @@ -/** - * Measurement Specialties (Intersema) MS5611-01BA pressure/temperature sensor interface for I2C +/* + * Copyright (C) 2011-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. * - * Edit by: Michal Podhradsky, michal.podhradsky@aggiemail.usu.edu - * Utah State University, http://aggieair.usu.edu/ */ + +/** + * @file boards/lisa_m/baro_ms5611_spi.c + * + * Driver for MS5611 baro on LisaM/Aspirin2.2 via SPI. + * + */ + #include "subsystems/sensors/baro.h" -#include "peripherals/ms5611_regs.h" +#include "peripherals/ms5611_spi.h" + +#include "mcu_periph/sys_time.h" #include "led.h" #include "std.h" -#include "mcu_periph/sys_time.h" -#include "mcu_periph/spi.h" #ifndef MS5611_SPI_DEV #define MS5611_SPI_DEV spi2 #endif @@ -23,213 +46,72 @@ #endif -#define MS5611_BUFFER_LENGTH 4 - #ifdef DEBUG + #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE #endif #include "mcu_periph/uart.h" #include "messages.h" #include "subsystems/datalink/downlink.h" + +float fbaroms, ftempms; #endif struct Baro baro; -struct spi_transaction ms5611_trans; -uint8_t ms5611_status; -int32_t prom_cnt; -uint16_t ms5611_c[PROM_NB]; -uint32_t ms5611_d1, ms5611_d2; -float fbaroms, ftempms; -volatile uint8_t input_buf_ms5611[MS5611_BUFFER_LENGTH]; -volatile uint8_t output_buf_ms5611[MS5611_BUFFER_LENGTH]; -static void trans_cb_ms5611( struct spi_transaction *trans ); +struct Ms5611_Spi baro_ms5611; -static int8_t baro_ms5611_crc(uint16_t* prom) { - int32_t i, j; - uint32_t res = 0; - uint8_t crc = prom[7] & 0xF; - prom[7] &= 0xFF00; - for (i = 0; i < 16; i++) { - if (i & 1) res ^= ((prom[i>>1]) & 0x00FF); - else res ^= (prom[i>>1]>>8); - for (j = 8; j > 0; j--) { - if (res & 0x8000) res ^= 0x1800; - res <<= 1; - } - } - prom[7] |= crc; - if (crc == ((res >> 12) & 0xF)) return 0; - else return -1; -} - -static void trans_cb_ms5611( struct spi_transaction *trans ) { -#ifdef ROTORCRAFT_BARO_LED - RunOnceEvery(10,LED_TOGGLE(ROTORCRAFT_BARO_LED)); -#endif -} void baro_init(void) { - ms5611_trans.select = SPISelectUnselect; - ms5611_trans.cpol = SPICpolIdleHigh; - ms5611_trans.cpha = SPICphaEdge2; - ms5611_trans.dss = SPIDss8bit; - ms5611_trans.bitorder = SPIMSBFirst; - ms5611_trans.cdiv = SPIDiv64; - ms5611_trans.slave_idx = MS5611_SLAVE_DEV; - ms5611_trans.output_length = MS5611_BUFFER_LENGTH; - ms5611_trans.input_length = MS5611_BUFFER_LENGTH; - ms5611_trans.after_cb = trans_cb_ms5611; - ms5611_trans.input_buf = &input_buf_ms5611[0]; - ms5611_trans.output_buf = &input_buf_ms5611[0]; - - ms5611_status = MS5611_UNINIT; baro.status = BS_UNINITIALIZED; - prom_cnt = 0; + baro.absolute = 0; + baro.differential = 0; + + ms5611_spi_init(&baro_ms5611, &MS5611_SPI_DEV, MS5611_SLAVE_DEV); } void baro_periodic(void) { if (sys_time.nb_sec > 1) { - if (ms5611_status == MS5611_IDLE) { - /* start D1 conversion */ - ms5611_status = MS5611_CONV_D1; - ms5611_trans.output_buf[0] = MS5611_START_CONV_D1; - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); - #ifdef DEBUG - RunOnceEvery(300, { DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &ms5611_c[0], &ms5611_c[1], &ms5611_c[2], &ms5611_c[3], - &ms5611_c[4], &ms5611_c[5], &ms5611_c[6], &ms5611_c[7]);}); - #endif - } - else if (ms5611_status == MS5611_CONV_D1) { - /* assume D1 conversion is done */ - ms5611_status = MS5611_CONV_D1_OK; - } - else if (ms5611_status == MS5611_CONV_D1_OK) { - /* read D1 adc */ - ms5611_status = MS5611_ADC_D1; - ms5611_trans.output_buf[0] = MS5611_ADC_READ; - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); - } - else if (ms5611_status == MS5611_CONV_D2) { - /* assume D2 conversion is done */ - ms5611_status = MS5611_CONV_D2_OK; - } - else if (ms5611_status == MS5611_CONV_D2_OK) { - /* read D2 adc */ - ms5611_status = MS5611_ADC_D2; - ms5611_trans.output_buf[0] = MS5611_ADC_READ; - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); - } - else if (ms5611_status == MS5611_UNINIT) { - /* reset sensor */ - ms5611_status = MS5611_RESET; - ms5611_trans.output_buf[0] = MS5611_SOFT_RESET; - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); - } - else if (ms5611_status == MS5611_RESET_OK) { - /* start getting prom data */ - ms5611_status = MS5611_PROM; - ms5611_trans.output_buf[0] = MS5611_PROM_READ | (prom_cnt << 1); - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); + + /* call the convenience periodic that initializes the sensor and starts reading*/ + ms5611_spi_periodic(&baro_ms5611); + + if (baro_ms5611.initialized) { + baro.status = BS_RUNNING; +#if DEBUG + RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7])); +#endif } } } void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)){ - if (ms5611_trans.status == SPITransSuccess) { - switch (ms5611_status) { - - case MS5611_RESET: - ms5611_status = MS5611_RESET_OK; - ms5611_trans.status = SPITransDone; - break; - - case MS5611_PROM: - /* read prom data */ - ms5611_c[prom_cnt++] = (ms5611_trans.input_buf[1] << 8) | ms5611_trans.input_buf[2]; - if (prom_cnt < PROM_NB) {//8 bytes at PROM - /* get next prom data */ - ms5611_trans.output_buf[0] = MS5611_PROM_READ | (prom_cnt << 1); - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); - } - else { - /* done reading prom */ - ms5611_trans.status = SPITransDone; - /* check prom crc */ - if (baro_ms5611_crc(ms5611_c) == 0) { - ms5611_status = MS5611_IDLE; - baro.status = BS_RUNNING; - } - else { - /* checksum error, try again */ - baro_init(); - } - } - break; - - case MS5611_ADC_D1: - /* read D1 (pressure) */ - ms5611_d1 = (ms5611_trans.input_buf[1] << 16) | - (ms5611_trans.input_buf[2] << 8) | - ms5611_trans.input_buf[3]; - /* start D2 conversion */ - ms5611_status = MS5611_CONV_D2; - ms5611_trans.output_buf[0] = MS5611_START_CONV_D2; - spi_submit(&(MS5611_SPI_DEV), &ms5611_trans); - break; - - case MS5611_ADC_D2: { - int64_t dt, baroms, tempms, off, sens, t2, off2, sens2; - /* read D2 (temperature) */ - ms5611_d2 = (ms5611_trans.input_buf[1] << 16) | - (ms5611_trans.input_buf[2] << 8) | - ms5611_trans.input_buf[3]; - ms5611_status = MS5611_IDLE; - ms5611_trans.status = SPITransDone; - - /* difference between actual and ref temperature */ - dt = ms5611_d2 - (int64_t)ms5611_c[5] * (1<<8); - /* actual temperature */ - tempms = 2000 + ((int64_t)dt * ms5611_c[6]) / (1<<23); - /* offset at actual temperature */ - off = ((int64_t)ms5611_c[2] * (1<<16)) + ((int64_t)ms5611_c[4] * dt) / (1<<7); - /* sensitivity at actual temperature */ - sens = ((int64_t)ms5611_c[1] * (1<<15)) + ((int64_t)ms5611_c[3] * dt) / (1<<8); - /* second order temperature compensation */ - if (tempms < 2000) { - t2 = (dt*dt) / (1<<31); - off2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<1); - sens2 = 5 * ((int64_t)(tempms-2000)*(tempms-2000)) / (1<<2); - if (tempms < -1500) { - off2 = off2 + 7 * (int64_t)(tempms+1500)*(tempms+1500); - sens2 = sens2 + 11 * ((int64_t)(tempms+1500)*(tempms+1500)) / (1<<1); - } - tempms = tempms - t2; - off = off - off2; - sens = sens - sens2; - } - /* temperature compensated pressure */ - baroms = (((int64_t)ms5611_d1 * sens) / (1<<21) - off) / (1<<15); - - /* Update baro structure */ - baro.absolute = (int32_t)baroms; + if (sys_time.nb_sec > 1) { + ms5611_spi_event(&baro_ms5611); + if (baro_ms5611.data_available) { b_abs_handler(); - b_diff_handler(); + baro_ms5611.data_available = FALSE; - #ifdef DEBUG - ftempms = tempms / 100.; - fbaroms = baroms / 100.; +#ifdef ROTORCRAFT_BARO_LED + RunOnceEvery(10,LED_TOGGLE(ROTORCRAFT_BARO_LED)); +#endif + +#if DEBUG + ftempms = baro_ms5611.data.temperature / 100.; + fbaroms = baro_ms5611.data.pressure / 100.; DOWNLINK_SEND_BARO_MS5611(DefaultChannel, DefaultDevice, - &ms5611_d1, &ms5611_d2, &fbaroms, &ftempms, &baro.status); - #endif - break; - } - - default: - ms5611_trans.status = SPITransDone; - break; + &baro_ms5611.data.d1, &baro_ms5611.data.d2, + &fbaroms, &ftempms); +#endif } } } From db101eeae751f46f439abe4275ef887773f677ef Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 15:26:17 +0200 Subject: [PATCH 125/309] [boards] move generic baro_ms5611_x driver to subsystem/sensors - use this for krooz as well - don't call the differential pressure handler, only absolute available there - lisa_m: if using bmp, store temp in baro_board struct instead of abusing differential pressure --- conf/firmwares/rotorcraft.makefile | 31 ++++++++++--------- sw/airborne/boards/krooz/baro_board.c | 30 ------------------ sw/airborne/boards/krooz/baro_board.h | 24 +++----------- sw/airborne/boards/lisa_m/baro_board.c | 6 ++-- sw/airborne/boards/lisa_m/baro_board.h | 5 +-- .../sensors}/baro_ms5611_i2c.c | 4 +-- .../sensors}/baro_ms5611_spi.c | 2 +- 7 files changed, 29 insertions(+), 73 deletions(-) delete mode 100644 sw/airborne/boards/krooz/baro_board.c rename sw/airborne/{boards/lisa_m => subsystems/sensors}/baro_ms5611_i2c.c (96%) rename sw/airborne/{boards/lisa_m => subsystems/sensors}/baro_ms5611_spi.c (97%) diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index 3616061a7c..ab551d0482 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -172,17 +172,17 @@ LISA_M_BARO ?= BARO_BOARD_BMP085 ifeq ($(LISA_M_BARO), BARO_MS5611_SPI) include $(CFG_SHARED)/spi_master.makefile ap.CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3 - ap.srcs += peripherals/ms5611.c - ap.srcs += peripherals/ms5611_spi.c - ap.srcs += $(SRC_BOARD)/baro_ms5611_spi.c + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_spi.c + ap.srcs += subsystems/sensors/baro_ms5611_spi.c else ifeq ($(LISA_M_BARO), BARO_MS5611_I2C) ap.CFLAGS += -DUSE_I2C2 - ap.srcs += peripherals/ms5611.c - ap.srcs += peripherals/ms5611_i2c.c - ap.srcs += $(SRC_BOARD)/baro_ms5611_i2c.c + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_i2c.c + ap.srcs += subsystems/sensors/baro_ms5611_i2c.c else ifeq ($(LISA_M_BARO), BARO_BOARD_BMP085) ap.srcs += $(SRC_BOARD)/baro_board.c - ap.CFLAGS += -DUSE_I2C2 + ap.CFLAGS += -DUSE_I2C2 endif ap.CFLAGS += -D$(LISA_M_BARO) @@ -193,14 +193,14 @@ LIA_BARO ?= BARO_MS5611_SPI ifeq ($(LIA_BARO), BARO_MS5611_SPI) include $(CFG_SHARED)/spi_master.makefile ap.CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3 - ap.srcs += peripherals/ms5611.c - ap.srcs += peripherals/ms5611_spi.c - ap.srcs += boards/lisa_m/baro_ms5611_spi.c + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_spi.c + ap.srcs += subsystems/sensors/baro_ms5611_spi.c else ifeq ($(LIA_BARO), BARO_MS5611_I2C) ap.CFLAGS += -DUSE_I2C2 - ap.srcs += peripherals/ms5611.c - ap.srcs += peripherals/ms5611_i2c.c - ap.srcs += boards/lisa_m/baro_ms5611_i2c.c + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_i2c.c + ap.srcs += subsystems/sensors/baro_ms5611_i2c.c endif ap.CFLAGS += -D$(LIA_BARO) @@ -214,7 +214,10 @@ ap.srcs += $(SRC_BOARD)/baro_board.c # krooz baro else ifeq ($(BOARD), krooz) -ap.srcs += $(SRC_BOARD)/baro_board.c +ap.CFLAGS += -DMS5611_I2C_DEV=i2c0 +ap.srcs += peripherals/ms5611.c +ap.srcs += peripherals/ms5611_i2c.c +ap.srcs += subsystems/sensors/baro_ms5611_i2c.c # apogee baro else ifeq ($(BOARD), apogee) diff --git a/sw/airborne/boards/krooz/baro_board.c b/sw/airborne/boards/krooz/baro_board.c deleted file mode 100644 index bc042c6cd0..0000000000 --- a/sw/airborne/boards/krooz/baro_board.c +++ /dev/null @@ -1,30 +0,0 @@ - -#include "subsystems/sensors/baro.h" -#include "baro_board.h" - -struct Baro baro; - -void baro_init(void) { - baro_ms5611_init(); -} - -void baro_periodic(void) { - static uint8_t cnt; - switch(cnt) { - case 0: - baro_ms5611_periodic(); - cnt++; - break; - case 1: - baro_ms5611_d1(); - cnt++; - break; - case 2: - baro_ms5611_d2(); - cnt = 0; - break; - default: - cnt = 0; - break; - } -} diff --git a/sw/airborne/boards/krooz/baro_board.h b/sw/airborne/boards/krooz/baro_board.h index b73f33d90d..5f47ad650e 100644 --- a/sw/airborne/boards/krooz/baro_board.h +++ b/sw/airborne/boards/krooz/baro_board.h @@ -1,30 +1,14 @@ /* - * board specific fonctions for the KroozSD board + * board specific interface for the KroozSD board * + * It uses the subsystems/sensors/baro_ms5611_i2c.c driver */ #ifndef BOARDS_KROOZ_BARO_H #define BOARDS_KROOZ_BARO_H -#include "std.h" -#include "mcu_periph/i2c.h" -#include "modules/sensors/baro_ms5611_i2c.h" -#include "math/pprz_algebra_int.h" - -//#include "led.h" - -static inline void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)) -{ - baro_ms5611_event(); - if(baro_ms5611_valid) { - baro.status = BS_RUNNING; - baro.absolute = (int32_t)baroms; - b_abs_handler(); - baro_ms5611_valid = FALSE; - } -} - -#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler,_b_diff_handler) +extern void baro_event(void (*b_abs_handler)(void)); +#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler) #endif /* BOARDS_KROOZ_SD_BARO_H */ diff --git a/sw/airborne/boards/lisa_m/baro_board.c b/sw/airborne/boards/lisa_m/baro_board.c index b51743c30a..77afc80485 100644 --- a/sw/airborne/boards/lisa_m/baro_board.c +++ b/sw/airborne/boards/lisa_m/baro_board.c @@ -167,7 +167,7 @@ static int32_t baro_apply_calibration(int32_t raw) return p + ((x1 + x2 + 3791) >> 4); } -void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)) +void baro_event(void (*b_abs_handler)(void)) { if (baro_board.status == LBS_READING && baro_trans.status != I2CTransPending && baro_trans.status != I2CTransRunning) { @@ -183,13 +183,11 @@ void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)) baro_trans.status != I2CTransPending && baro_trans.status != I2CTransRunning) { baro_board.status = LBS_REQUEST; if (baro_trans.status == I2CTransSuccess) { - // abuse differential to store temp in 0.1C for now int32_t tmp = (baro_trans.buf[0] << 8) | baro_trans.buf[1]; int32_t x1 = ((tmp - calibration.ac6) * calibration.ac5) >> 15; int32_t x2 = (calibration.mc << 11) / (x1 + calibration.md); calibration.b5 = x1 + x2; - baro.differential = (calibration.b5 + 8) >> 4; - b_diff_handler(); + baro_board.temp = (calibration.b5 + 8) >> 4; } } } diff --git a/sw/airborne/boards/lisa_m/baro_board.h b/sw/airborne/boards/lisa_m/baro_board.h index 42014ddeee..dd62dfb5ba 100644 --- a/sw/airborne/boards/lisa_m/baro_board.h +++ b/sw/airborne/boards/lisa_m/baro_board.h @@ -31,6 +31,7 @@ enum LisaBaroStatus { struct BaroBoard { enum LisaBaroStatus status; + int32_t temp; ///< temperature in 0.1C }; struct bmp085_baro_calibration { @@ -60,8 +61,8 @@ extern void baro_board_send_config(void); #endif // !BARO_MS5611_xx -extern void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)); +extern void baro_event(void (*b_abs_handler)(void)); -#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler,_b_diff_handler) +#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler) #endif /* BOARDS_LISA_M_BARO_H */ diff --git a/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c similarity index 96% rename from sw/airborne/boards/lisa_m/baro_ms5611_i2c.c rename to sw/airborne/subsystems/sensors/baro_ms5611_i2c.c index 989096848a..a301213aab 100644 --- a/sw/airborne/boards/lisa_m/baro_ms5611_i2c.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c @@ -23,7 +23,7 @@ /** * @file boards/lisa_m/baro_ms5611_i2c.c * - * Driver for MS5611 baro on LisaM/Aspirin2.1 via I2C. + * Driver for MS5611 baro via I2C. * */ @@ -94,7 +94,7 @@ void baro_periodic(void) { } } -void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)){ +void baro_event(void (*b_abs_handler)(void)){ if (sys_time.nb_sec > 1) { ms5611_i2c_event(&baro_ms5611); diff --git a/sw/airborne/boards/lisa_m/baro_ms5611_spi.c b/sw/airborne/subsystems/sensors/baro_ms5611_spi.c similarity index 97% rename from sw/airborne/boards/lisa_m/baro_ms5611_spi.c rename to sw/airborne/subsystems/sensors/baro_ms5611_spi.c index 84091d5a04..127f07c31c 100644 --- a/sw/airborne/boards/lisa_m/baro_ms5611_spi.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_spi.c @@ -93,7 +93,7 @@ void baro_periodic(void) { } } -void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)){ +void baro_event(void (*b_abs_handler)(void)){ if (sys_time.nb_sec > 1) { ms5611_spi_event(&baro_ms5611); From abdc6884325d673d4f4b1774ac5c11f739099d9f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 16:10:05 +0200 Subject: [PATCH 126/309] [boards] fix baro on krooz, don't add it in imu subsystem --- conf/firmwares/rotorcraft.makefile | 2 +- conf/firmwares/subsystems/shared/imu_krooz_sd.makefile | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index ab551d0482..5a90dae947 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -214,7 +214,7 @@ ap.srcs += $(SRC_BOARD)/baro_board.c # krooz baro else ifeq ($(BOARD), krooz) -ap.CFLAGS += -DMS5611_I2C_DEV=i2c0 +ap.CFLAGS += -DMS5611_I2C_DEV=i2c2 -DMS5611_SLAVE_ADDR=0xEC ap.srcs += peripherals/ms5611.c ap.srcs += peripherals/ms5611_i2c.c ap.srcs += subsystems/sensors/baro_ms5611_i2c.c diff --git a/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile b/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile index c2a7e83fe0..878dadfac1 100644 --- a/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile +++ b/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile @@ -14,11 +14,9 @@ IMU_KROOZ_I2C_DEV=i2c2 IMU_KROOZ_CFLAGS += -DUSE_I2C -DUSE_I2C2 -DI2C2_CLOCK_SPEED=400000 IMU_KROOZ_CFLAGS += -DIMU_KROOZ_I2C_DEV=$(IMU_KROOZ_I2C_DEV) -IMU_KROOZ_CFLAGS += -DMS5611_I2C_DEV=$(IMU_KROOZ_I2C_DEV) -DMS5611_SLAVE_ADDR=0xEC IMU_KROOZ_SRCS += peripherals/mpu60x0.c IMU_KROOZ_SRCS += peripherals/mpu60x0_i2c.c IMU_KROOZ_SRCS += peripherals/hmc58xx.c -IMU_KROOZ_SRCS += modules/sensors/baro_ms5611_i2c.c AHRS_PROPAGATE_FREQUENCY ?= 512 AHRS_CORRECT_FREQUENCY ?= 512 From 4a20e7ff498b065d717e7146298f07d942313331 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 16:43:14 +0200 Subject: [PATCH 127/309] [baro] ms5611_i2c: ifndef around MS5611_SLAVE_ADDR --- sw/airborne/subsystems/sensors/baro_ms5611_i2c.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c index a301213aab..a7aa03370d 100644 --- a/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c @@ -44,8 +44,9 @@ * * Note: Aspirin 2.1 has CSB bound to GND. */ +#ifndef MS5611_SLAVE_ADDR #define MS5611_SLAVE_ADDR 0xEE - +#endif #ifdef DEBUG From 112638e919c0eaae239a303f87a07076d73c0cb9 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 17:13:56 +0200 Subject: [PATCH 128/309] [peripherals] ms5611: read prom while not yet initialized --- sw/airborne/peripherals/ms5611_i2c.c | 46 ++++++++++++++-------------- sw/airborne/peripherals/ms5611_spi.c | 46 ++++++++++++++-------------- 2 files changed, 46 insertions(+), 46 deletions(-) diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c index 4b248ffe12..17f603d421 100644 --- a/sw/airborne/peripherals/ms5611_i2c.c +++ b/sw/airborne/peripherals/ms5611_i2c.c @@ -115,35 +115,13 @@ void ms5611_i2c_periodic_check(struct Ms5611_I2c *ms) void ms5611_i2c_event(struct Ms5611_I2c *ms) { if (ms->initialized) { if (ms->i2c_trans.status == I2CTransFailed) { + ms->status = MS5611_STATUS_IDLE; ms->i2c_trans.status = I2CTransDone; } else if (ms->i2c_trans.status == I2CTransSuccess) { // Successfull reading switch (ms->status) { - case MS5611_STATUS_PROM: - /* read prom data */ - ms->data.c[ms->prom_cnt++] = (ms->i2c_trans.buf[0] << 8) | - ms->i2c_trans.buf[1]; - if (ms->prom_cnt < PROM_NB) { - /* get next prom data */ - ms->i2c_trans.buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); - i2c_transceive(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1, 2); - } - else { - /* done reading prom, check prom crc */ - if (ms5611_prom_crc_ok(ms->data.c)) { - ms->initialized = TRUE; - ms->status = MS5611_STATUS_IDLE; - } - else { - /* checksum error, try again */ - ms->prom_cnt = 0; - ms->status = MS5611_STATUS_UNINIT; - } - } - break; - case MS5611_STATUS_ADC_D1: /* read D1 (pressure) */ ms->data.d1 = (ms->i2c_trans.buf[0] << 16) | @@ -179,6 +157,28 @@ void ms5611_i2c_event(struct Ms5611_I2c *ms) { ms->prom_cnt = 0; ms->status = MS5611_STATUS_UNINIT; case I2CTransSuccess: + if (ms->status == MS5611_STATUS_PROM) { + /* read prom data */ + ms->data.c[ms->prom_cnt++] = (ms->i2c_trans.buf[0] << 8) | + ms->i2c_trans.buf[1]; + if (ms->prom_cnt < PROM_NB) { + /* get next prom data */ + ms->i2c_trans.buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); + i2c_transceive(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1, 2); + } + else { + /* done reading prom, check prom crc */ + if (ms5611_prom_crc_ok(ms->data.c)) { + ms->initialized = TRUE; + ms->status = MS5611_STATUS_IDLE; + } + else { + /* checksum error, try again */ + ms->prom_cnt = 0; + ms->status = MS5611_STATUS_UNINIT; + } + } + } case I2CTransDone: ms->i2c_trans.status = I2CTransDone; break; diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c index bcf7d129d4..bcb157ffd6 100644 --- a/sw/airborne/peripherals/ms5611_spi.c +++ b/sw/airborne/peripherals/ms5611_spi.c @@ -129,35 +129,13 @@ void ms5611_spi_periodic_check(struct Ms5611_Spi *ms) void ms5611_spi_event(struct Ms5611_Spi *ms) { if (ms->initialized) { if (ms->spi_trans.status == SPITransFailed) { + ms->status = MS5611_STATUS_IDLE; ms->spi_trans.status = SPITransDone; } else if (ms->spi_trans.status == SPITransSuccess) { // Successfull reading switch (ms->status) { - case MS5611_STATUS_PROM: - /* read prom data */ - ms->data.c[ms->prom_cnt++] = (ms->rx_buf[1] << 8) | - ms->rx_buf[2]; - if (ms->prom_cnt < PROM_NB) { - /* get next prom data */ - ms->tx_buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); - spi_submit(ms->spi_p, &(ms->spi_trans)); - } - else { - /* done reading prom, check prom crc */ - if (ms5611_prom_crc_ok(ms->data.c)) { - ms->initialized = TRUE; - ms->status = MS5611_STATUS_IDLE; - } - else { - /* checksum error, try again */ - ms->prom_cnt = 0; - ms->status = MS5611_STATUS_UNINIT; - } - } - break; - case MS5611_STATUS_ADC_D1: /* read D1 (pressure) */ ms->data.d1 = (ms->rx_buf[1] << 16) | @@ -193,6 +171,28 @@ void ms5611_spi_event(struct Ms5611_Spi *ms) { ms->prom_cnt = 0; ms->status = MS5611_STATUS_UNINIT; case SPITransSuccess: + if (ms->status == MS5611_STATUS_PROM) { + /* read prom data */ + ms->data.c[ms->prom_cnt++] = (ms->rx_buf[1] << 8) | + ms->rx_buf[2]; + if (ms->prom_cnt < PROM_NB) { + /* get next prom data */ + ms->tx_buf[0] = MS5611_PROM_READ | (ms->prom_cnt << 1); + spi_submit(ms->spi_p, &(ms->spi_trans)); + } + else { + /* done reading prom, check prom crc */ + if (ms5611_prom_crc_ok(ms->data.c)) { + ms->initialized = TRUE; + ms->status = MS5611_STATUS_IDLE; + } + else { + /* checksum error, try again */ + ms->prom_cnt = 0; + ms->status = MS5611_STATUS_UNINIT; + } + } + } case SPITransDone: ms->spi_trans.status = SPITransDone; break; From 308adb750286b1bfade0c0d86d67aebfa9fc2733 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 17:20:53 +0200 Subject: [PATCH 129/309] [baro] ms5611: actually write result to baro.absolute --- sw/airborne/peripherals/ms5611_i2c.c | 10 +++++++--- sw/airborne/peripherals/ms5611_spi.c | 10 +++++++--- sw/airborne/subsystems/sensors/baro_ms5611_i2c.c | 1 + sw/airborne/subsystems/sensors/baro_ms5611_spi.c | 1 + 4 files changed, 16 insertions(+), 6 deletions(-) diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c index 17f603d421..ae7da64d63 100644 --- a/sw/airborne/peripherals/ms5611_i2c.c +++ b/sw/airborne/peripherals/ms5611_i2c.c @@ -49,6 +49,8 @@ void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t ad void ms5611_i2c_start_configure(struct Ms5611_I2c *ms) { if (ms->status == MS5611_STATUS_UNINIT) { + ms->initialized = FALSE; + ms->prom_cnt = 0; ms->i2c_trans.buf[0] = MS5611_SOFT_RESET; i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); ms->status = MS5611_STATUS_RESET; @@ -152,10 +154,13 @@ void ms5611_i2c_event(struct Ms5611_I2c *ms) { } else if (ms->status != MS5611_STATUS_UNINIT) { // Configuring but not yet initialized switch (ms->i2c_trans.status) { + case I2CTransFailed: /* try again */ - ms->prom_cnt = 0; ms->status = MS5611_STATUS_UNINIT; + ms->i2c_trans.status = I2CTransDone; + break; + case I2CTransSuccess: if (ms->status == MS5611_STATUS_PROM) { /* read prom data */ @@ -174,14 +179,13 @@ void ms5611_i2c_event(struct Ms5611_I2c *ms) { } else { /* checksum error, try again */ - ms->prom_cnt = 0; ms->status = MS5611_STATUS_UNINIT; } } } - case I2CTransDone: ms->i2c_trans.status = I2CTransDone; break; + default: break; } diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c index bcb157ffd6..a183163969 100644 --- a/sw/airborne/peripherals/ms5611_spi.c +++ b/sw/airborne/peripherals/ms5611_spi.c @@ -63,6 +63,8 @@ void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t sl void ms5611_spi_start_configure(struct Ms5611_Spi *ms) { if (ms->status == MS5611_STATUS_UNINIT) { + ms->initalized = FALSE; + ms->prom_cnt = 0; ms->tx_buf[0] = MS5611_SOFT_RESET; spi_submit(ms->spi_p, &(ms->spi_trans)); ms->status = MS5611_STATUS_RESET; @@ -166,10 +168,13 @@ void ms5611_spi_event(struct Ms5611_Spi *ms) { } else if (ms->status != MS5611_STATUS_UNINIT) { // Configuring but not yet initialized switch (ms->spi_trans.status) { + case SPITransFailed: /* try again */ - ms->prom_cnt = 0; ms->status = MS5611_STATUS_UNINIT; + ms->spi_trans.status = SPITransDone; + break; + case SPITransSuccess: if (ms->status == MS5611_STATUS_PROM) { /* read prom data */ @@ -188,14 +193,13 @@ void ms5611_spi_event(struct Ms5611_Spi *ms) { } else { /* checksum error, try again */ - ms->prom_cnt = 0; ms->status = MS5611_STATUS_UNINIT; } } } - case SPITransDone: ms->spi_trans.status = SPITransDone; break; + default: break; } diff --git a/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c index a7aa03370d..a996cee2dc 100644 --- a/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c @@ -100,6 +100,7 @@ void baro_event(void (*b_abs_handler)(void)){ ms5611_i2c_event(&baro_ms5611); if (baro_ms5611.data_available) { + baro.absolute = baro_ms5611.data.pressure; b_abs_handler(); baro_ms5611.data_available = FALSE; diff --git a/sw/airborne/subsystems/sensors/baro_ms5611_spi.c b/sw/airborne/subsystems/sensors/baro_ms5611_spi.c index 127f07c31c..a86ab818f7 100644 --- a/sw/airborne/subsystems/sensors/baro_ms5611_spi.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_spi.c @@ -98,6 +98,7 @@ void baro_event(void (*b_abs_handler)(void)){ ms5611_spi_event(&baro_ms5611); if (baro_ms5611.data_available) { + baro.absolute = baro_ms5611.data.pressure; b_abs_handler(); baro_ms5611.data_available = FALSE; From 1c64767b8286d089681af05b8924998e0bc8a9c1 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 17:46:20 +0200 Subject: [PATCH 130/309] [peripherals] fix typo in ms5611 --- sw/airborne/peripherals/ms5611_i2c.c | 2 +- sw/airborne/peripherals/ms5611_spi.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c index ae7da64d63..c65cb19ddd 100644 --- a/sw/airborne/peripherals/ms5611_i2c.c +++ b/sw/airborne/peripherals/ms5611_i2c.c @@ -37,7 +37,7 @@ void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t ad /* slave address */ ms->i2c_trans.slave_addr = addr; - /* set inital status: Success or Done */ + /* set initial status: Success or Done */ ms->i2c_trans.status = I2CTransDone; ms->data_available = FALSE; diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c index a183163969..5b7e01ab78 100644 --- a/sw/airborne/peripherals/ms5611_spi.c +++ b/sw/airborne/peripherals/ms5611_spi.c @@ -51,7 +51,7 @@ void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t sl ms->spi_trans.input_buf = ms->rx_buf; ms->spi_trans.output_buf = ms->tx_buf; - /* set inital status: Success or Done */ + /* set initial status: Success or Done */ ms->spi_trans.status = SPITransDone; ms->data_available = FALSE; @@ -63,7 +63,7 @@ void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t sl void ms5611_spi_start_configure(struct Ms5611_Spi *ms) { if (ms->status == MS5611_STATUS_UNINIT) { - ms->initalized = FALSE; + ms->initialized = FALSE; ms->prom_cnt = 0; ms->tx_buf[0] = MS5611_SOFT_RESET; spi_submit(ms->spi_p, &(ms->spi_trans)); From 3bf713a831241e24c6f6f0780422ce66a6baea9a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 23 Aug 2013 23:27:24 +0200 Subject: [PATCH 131/309] [modules] add min/max periodic time to sys_mon --- conf/messages.xml | 2 ++ sw/airborne/modules/core/sys_mon.c | 38 ++++++++++++++++++++---------- sw/airborne/modules/core/sys_mon.h | 2 ++ 3 files changed, 30 insertions(+), 12 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index 8a610824c1..456a1cd8ab 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -255,6 +255,8 @@ + + diff --git a/sw/airborne/modules/core/sys_mon.c b/sw/airborne/modules/core/sys_mon.c index c4d3239ccd..5f76e17395 100644 --- a/sw/airborne/modules/core/sys_mon.c +++ b/sw/airborne/modules/core/sys_mon.c @@ -27,24 +27,26 @@ #include "mcu_periph/usb_serial.h" #endif -/* Global system monitor data (averaged over 1 sec) */ +/** Global system monitor data (averaged over 1 sec) */ struct SysMon sys_mon; /* Local vars */ -uint16_t n_periodic; -uint16_t n_event; -uint32_t periodic_timer; -uint32_t periodic_cycle; -uint32_t event_timer; -uint32_t sum_time_periodic; ///< in usec -uint32_t sum_cycle_periodic; ///< in usec -uint32_t sum_time_event; ///< in usec -uint32_t min_time_event; ///< in usec -uint32_t sum_n_event; +static uint16_t n_periodic; +static uint16_t n_event; +static uint32_t periodic_timer; +static uint32_t periodic_cycle; +static uint32_t event_timer; +static uint32_t sum_time_periodic; ///< in usec +static uint32_t sum_cycle_periodic; ///< in usec +static uint32_t sum_time_event; ///< in usec +static uint32_t min_time_event; ///< in usec +static uint32_t sum_n_event; void init_sysmon(void) { sys_mon.cpu_load = 0; sys_mon.periodic_time = 0; + sys_mon.periodic_time_min = 0xFFFF; + sys_mon.periodic_time_max = 0; sys_mon.periodic_cycle = 0; sys_mon.periodic_cycle_min = 0xFFFF; sys_mon.periodic_cycle_max = 0; @@ -75,13 +77,19 @@ void periodic_report_sysmon(void) { sys_mon.cpu_load = 100 * sys_mon.periodic_cycle / sys_mon.periodic_time; sys_mon.event_number = sum_n_event / n_periodic; - DOWNLINK_SEND_SYS_MON(DefaultChannel, DefaultDevice, &sys_mon.periodic_time, &sys_mon.periodic_cycle, &sys_mon.periodic_cycle_min, &sys_mon.periodic_cycle_max, &sys_mon.event_number, &sys_mon.cpu_load); + DOWNLINK_SEND_SYS_MON(DefaultChannel, DefaultDevice, &sys_mon.periodic_time, + &sys_mon.periodic_time_min, &sys_mon.periodic_time_max, + &sys_mon.periodic_cycle, &sys_mon.periodic_cycle_min, + &sys_mon.periodic_cycle_max, &sys_mon.event_number, + &sys_mon.cpu_load); } n_periodic = 0; sum_time_periodic = 0; sum_cycle_periodic = 0; sum_n_event = 0; + sys_mon.periodic_time_min = 0xFFFF; + sys_mon.periodic_time_max = 0; sys_mon.periodic_cycle_min = 0xFFFF; sys_mon.periodic_cycle_max = 0; } @@ -96,6 +104,12 @@ void periodic_sysmon(void) { periodic_cycle = periodic_usec - n_event * min_time_event; sum_cycle_periodic += periodic_cycle; + /* remember min and max periodic times */ + if (periodic_usec < sys_mon.periodic_time_min) + sys_mon.periodic_time_min = periodic_usec; + if (periodic_usec > sys_mon.periodic_time_max) + sys_mon.periodic_time_max = periodic_usec; + /* remember min and max periodic cycle times */ if (periodic_cycle < sys_mon.periodic_cycle_min) sys_mon.periodic_cycle_min = periodic_cycle; diff --git a/sw/airborne/modules/core/sys_mon.h b/sw/airborne/modules/core/sys_mon.h index 0496f9b970..aec9286d7b 100644 --- a/sw/airborne/modules/core/sys_mon.h +++ b/sw/airborne/modules/core/sys_mon.h @@ -34,6 +34,8 @@ struct SysMon { uint8_t cpu_load; uint16_t periodic_time; ///< in usec + uint16_t periodic_time_min; ///< in usec + uint16_t periodic_time_max; ///< in usec uint16_t periodic_cycle; ///< in usec uint16_t periodic_cycle_min; ///< in usec uint16_t periodic_cycle_max; ///< in usec From a8ad3d9ec4fb97578e2ae18cedf8339c1f251eb1 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 26 Aug 2013 20:58:11 +0200 Subject: [PATCH 132/309] [peripherals] add bmp085 peripheral and use it on the lisa_m baro_board --- conf/firmwares/rotorcraft.makefile | 1 + sw/airborne/boards/lisa_m/baro_board.c | 212 ++++++------------------- sw/airborne/boards/lisa_m/baro_board.h | 46 +----- sw/airborne/peripherals/bmp085.c | 191 ++++++++++++++++++++++ sw/airborne/peripherals/bmp085.h | 81 ++++++++++ sw/airborne/peripherals/bmp085_regs.h | 59 +++++++ 6 files changed, 384 insertions(+), 206 deletions(-) create mode 100644 sw/airborne/peripherals/bmp085.c create mode 100644 sw/airborne/peripherals/bmp085.h create mode 100644 sw/airborne/peripherals/bmp085_regs.h diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index 5a90dae947..b5cd13d64e 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -181,6 +181,7 @@ LISA_M_BARO ?= BARO_BOARD_BMP085 ap.srcs += peripherals/ms5611_i2c.c ap.srcs += subsystems/sensors/baro_ms5611_i2c.c else ifeq ($(LISA_M_BARO), BARO_BOARD_BMP085) + ap.srcs += peripherals/bmp085.c ap.srcs += $(SRC_BOARD)/baro_board.c ap.CFLAGS += -DUSE_I2C2 endif diff --git a/sw/airborne/boards/lisa_m/baro_board.c b/sw/airborne/boards/lisa_m/baro_board.c index 77afc80485..9c09b97d90 100644 --- a/sw/airborne/boards/lisa_m/baro_board.c +++ b/sw/airborne/boards/lisa_m/baro_board.c @@ -1,193 +1,81 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** @file boards/lisa_m/baro_board.c + * Baro board interface for Bosch BMP085 on LisaM I2C2 with EOC check. + */ #include "subsystems/sensors/baro.h" -#include +#include "peripherals/bmp085_regs.h" +#include + +#include "led.h" struct Baro baro; -struct BaroBoard baro_board; -struct i2c_transaction baro_trans; -struct bmp085_baro_calibration calibration; +struct Bmp085 baro_bmp085; -#define BMP085_SAMPLE_PERIOD_MS (3 + (2 << BMP085_OSS) * 3) -#define BMP085_SAMPLE_PERIOD (BMP075_SAMPLE_PERIOD_MS >> 1) - -// FIXME: BARO DRDY connected to PB0 for lisa/m - -static inline void bmp085_write_reg(uint8_t addr, uint8_t value) +static bool_t baro_eoc(void) { - baro_trans.buf[0] = addr; - baro_trans.buf[1] = value; - - i2c_transmit(&i2c2, &baro_trans, BMP085_ADDR, 2); - - // FIXME, no while loops without timeout!! - while (baro_trans.status == I2CTransPending || baro_trans.status == I2CTransRunning); -} - -static inline void bmp085_read_reg16(uint8_t addr) -{ - baro_trans.buf[0] = addr; - i2c_transceive(&i2c2, &baro_trans, BMP085_ADDR, 1, 2); -} - -static inline int16_t bmp085_read_reg16_blocking(uint8_t addr, uint32_t timeout) -{ - uint32_t time = 0; - - bmp085_read_reg16(addr); - - while (baro_trans.status == I2CTransPending || baro_trans.status == I2CTransRunning) { - if ((time == timeout) && (timeout != 0)) { - return 0; /* Timeout of the i2c read */ - } else { - time++; - } - } - - return ((baro_trans.buf[0] << 8) | baro_trans.buf[1]); -} - -static inline void bmp085_read_reg24(uint8_t addr) -{ - baro_trans.buf[0] = addr; - i2c_transceive(&i2c2, &baro_trans, BMP085_ADDR, 1, 3); -} - -static void bmp085_baro_read_calibration(void) -{ - calibration.ac1 = bmp085_read_reg16_blocking(0xAA, 10000); // AC1 - calibration.ac2 = bmp085_read_reg16_blocking(0xAC, 10000); // AC2 - calibration.ac3 = bmp085_read_reg16_blocking(0xAE, 10000); // AC3 - calibration.ac4 = bmp085_read_reg16_blocking(0xB0, 10000); // AC4 - calibration.ac5 = bmp085_read_reg16_blocking(0xB2, 10000); // AC5 - calibration.ac6 = bmp085_read_reg16_blocking(0xB4, 10000); // AC6 - calibration.b1 = bmp085_read_reg16_blocking(0xB6, 10000); // B1 - calibration.b2 = bmp085_read_reg16_blocking(0xB8, 10000); // B2 - calibration.mb = bmp085_read_reg16_blocking(0xBA, 10000); // MB - calibration.mc = bmp085_read_reg16_blocking(0xBC, 10000); // MC - calibration.md = bmp085_read_reg16_blocking(0xBE, 10000); // MD + return gpio_get(GPIOB, GPIO0); } void baro_init(void) { baro.status = BS_UNINITIALIZED; baro.absolute = 0; baro.differential = 0; - baro_board.status = LBS_UNINITIALIZED; - bmp085_baro_read_calibration(); - /* STM32 specific (maybe this is a LISA/M specific driver anyway?) */ + bmp085_init(&baro_bmp085, &i2c2, BMP085_SLAVE_ADDR); + + /* setup eoc check function */ + baro_bmp085.eoc = &baro_eoc; + gpio_clear(GPIOB, GPIO0); gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO0); } -static inline int baro_eoc(void) -{ - return gpio_get(GPIOB, GPIO0); -} - -static inline void bmp085_request_pressure(void) -{ - bmp085_write_reg(0xF4, 0x34 + (BMP085_OSS << 6)); -} - -static inline void bmp085_request_temp(void) -{ - bmp085_write_reg(0xF4, 0x2E); -} - -static inline void bmp085_read_pressure(void) -{ - bmp085_read_reg24(0xF6); -} - -static inline void bmp085_read_temp(void) -{ - bmp085_read_reg16(0xF6); -} void baro_periodic(void) { - // check that nothing is in progress - if (baro_trans.status == I2CTransPending) return; - if (baro_trans.status == I2CTransRunning) return; - if (!i2c_idle(&i2c2)) return; - switch (baro_board.status) { - case LBS_UNINITIALIZED: - baro_board_send_reset(); - baro_board.status = LBS_REQUEST; + if (baro_bmp085.initialized) { baro.status = BS_RUNNING; - break; - case LBS_REQUEST: - bmp085_request_pressure(); - baro_board.status = LBS_READ; - break; - case LBS_READ: - if (baro_eoc()) { - bmp085_read_pressure(); - baro_board.status = LBS_READING; - } - break; - case LBS_REQUEST_TEMP: - bmp085_request_temp(); - baro_board.status = LBS_READ_TEMP; - break; - case LBS_READ_TEMP: - if (baro_eoc()) { - bmp085_read_temp(); - baro_board.status = LBS_READING_TEMP; - } - break; - default: - break; + bmp085_periodic(&baro_bmp085); } - + else + bmp085_read_eeprom_calib(&baro_bmp085); } -void baro_board_send_reset(void) { - // This is a NOP at the moment -} -// Apply temp calibration and sensor calibration to raw measurement to get Pa (from BMP085 datasheet) -static int32_t baro_apply_calibration(int32_t raw) -{ - int32_t b6 = calibration.b5 - 4000; - int x1 = (calibration.b2 * (b6 * b6 >> 12)) >> 11; - int x2 = calibration.ac2 * b6 >> 11; - int32_t x3 = x1 + x2; - int32_t b3 = (((calibration.ac1 * 4 + x3) << BMP085_OSS) + 2)/4; - x1 = calibration.ac3 * b6 >> 13; - x2 = (calibration.b1 * (b6 * b6 >> 12)) >> 16; - x3 = ((x1 + x2) + 2) >> 2; - uint32_t b4 = (calibration.ac4 * (uint32_t) (x3 + 32768)) >> 15; - uint32_t b7 = (raw - b3) * (50000 >> BMP085_OSS); - int32_t p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2; - x1 = (p >> 8) * (p >> 8); - x1 = (x1 * 3038) >> 16; - x2 = (-7357 * p) >> 16; - return p + ((x1 + x2 + 3791) >> 4); -} void baro_event(void (*b_abs_handler)(void)) { - if (baro_board.status == LBS_READING && - baro_trans.status != I2CTransPending && baro_trans.status != I2CTransRunning) { - baro_board.status = LBS_REQUEST_TEMP; - if (baro_trans.status == I2CTransSuccess) { - int32_t tmp = (baro_trans.buf[0]<<16) | (baro_trans.buf[1] << 8) | baro_trans.buf[2]; - tmp = tmp >> (8 - BMP085_OSS); - baro.absolute = baro_apply_calibration(tmp); - b_abs_handler(); - } - } - if (baro_board.status == LBS_READING_TEMP && - baro_trans.status != I2CTransPending && baro_trans.status != I2CTransRunning) { - baro_board.status = LBS_REQUEST; - if (baro_trans.status == I2CTransSuccess) { - int32_t tmp = (baro_trans.buf[0] << 8) | baro_trans.buf[1]; - int32_t x1 = ((tmp - calibration.ac6) * calibration.ac5) >> 15; - int32_t x2 = (calibration.mc << 11) / (x1 + calibration.md); - calibration.b5 = x1 + x2; - baro_board.temp = (calibration.b5 + 8) >> 4; - } + bmp085_event(&baro_bmp085); + + if (baro_bmp085.data_available) { + baro.absolute = baro_bmp085.pressure; + b_abs_handler(); + baro_bmp085.data_available = FALSE; + +#ifdef ROTORCRAFT_BARO_LED + RunOnceEvery(10,LED_TOGGLE(ROTORCRAFT_BARO_LED)); +#endif } } diff --git a/sw/airborne/boards/lisa_m/baro_board.h b/sw/airborne/boards/lisa_m/baro_board.h index dd62dfb5ba..b84a11a7da 100644 --- a/sw/airborne/boards/lisa_m/baro_board.h +++ b/sw/airborne/boards/lisa_m/baro_board.h @@ -12,52 +12,10 @@ // for right now we abuse this file for the ms5611 baro on aspirin as well #if !BARO_MS5611_I2C && !BARO_MS5611 -#include "mcu_periph/i2c.h" +#include "peripherals/bmp085.h" -// absolute addr -#define BMP085_ADDR 0xEE -// Over sample setting (0-3) -#define BMP085_OSS 3 +extern struct Bmp085 baro_bmp085; -enum LisaBaroStatus { - LBS_UNINITIALIZED, - LBS_REQUEST, - LBS_READING, - LBS_READ, - LBS_REQUEST_TEMP, - LBS_READING_TEMP, - LBS_READ_TEMP, -}; - -struct BaroBoard { - enum LisaBaroStatus status; - int32_t temp; ///< temperature in 0.1C -}; - -struct bmp085_baro_calibration { - // These values come from EEPROM on sensor - int16_t ac1; - int16_t ac2; - int16_t ac3; - uint16_t ac4; - uint16_t ac5; - uint16_t ac6; - int16_t b1; - int16_t b2; - int16_t mb; - int16_t mc; - int16_t md; - - // These values are calculated - int32_t b5; -}; - -extern struct BaroBoard baro_board; -extern struct i2c_transaction baro_trans; -extern struct bmp085_baro_calibration calibration; - -extern void baro_board_send_reset(void); -extern void baro_board_send_config(void); #endif // !BARO_MS5611_xx diff --git a/sw/airborne/peripherals/bmp085.c b/sw/airborne/peripherals/bmp085.c new file mode 100644 index 0000000000..60630d02cb --- /dev/null +++ b/sw/airborne/peripherals/bmp085.c @@ -0,0 +1,191 @@ +/* + * Copyright (C) 2010 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** @file peripherals/bmp085.c + * Bosch BMP085 driver interface. + */ + +#include "peripherals/bmp085.h" +#include "peripherals/bmp085_regs.h" + + +static int32_t bmp085_compensated_temperature(struct Bmp085Calib* calib, int32_t raw) +{ + int32_t x1 = (raw - calib->ac6) * calib->ac5 / (1<<15); + int32_t x2 = (calib->mc << 11) / (x1 + calib->md); + calib->b5 = x1 + x2; + return (calib->b5 + 8) >> 4; +} + + + +/** Apply temp calibration and sensor calibration to raw measurement to get Pa + * (from BMP085 datasheet) + */ +static int32_t bmp085_compensated_pressure(struct Bmp085Calib* calib, int32_t raw) +{ + int32_t b6 = calib->b5 - 4000; + int32_t x1 = (calib->b2 * (b6 * b6 >> 12)) >> 11; + int32_t x2 = calib->ac2 * b6 >> 11; + int32_t x3 = x1 + x2; + int32_t b3 = (((calib->ac1 * 4 + x3) << BMP085_OSS) + 2)/4; + x1 = calib->ac3 * b6 >> 13; + x2 = (calib->b1 * (b6 * b6 >> 12)) >> 16; + x3 = ((x1 + x2) + 2) >> 2; + uint32_t b4 = (calib->ac4 * (uint32_t) (x3 + 32768)) >> 15; + uint32_t b7 = (raw - b3) * (50000 >> BMP085_OSS); + int32_t p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2; + x1 = (p >> 8) * (p >> 8); + x1 = (x1 * 3038) >> 16; + x2 = (-7357 * p) >> 16; + return p + ((x1 + x2 + 3791) >> 4); +} + +/** + * Dummy function to always return TRUE on EndOfConversion check. + * Ensure proper timing trough frequency of bmp085_periodic instead! + */ +static bool_t bmp085_eoc_true(void) +{ + return TRUE; +} + + +void bmp085_read_eeprom_calib(struct Bmp085* bmp) +{ + if (bmp->status == BMP085_STATUS_UNINIT) { + bmp->initialized = FALSE; + bmp->i2c_trans.buf[0] = BMP085_EEPROM_AC1; + i2c_transceive(bmp->i2c_p, &(bmp->i2c_trans), bmp->i2c_trans.slave_addr, 1, 22); + } +} + + +void bmp085_init(struct Bmp085* bmp, struct i2c_periph *i2c_p, uint8_t addr) +{ + /* set i2c_peripheral */ + bmp->i2c_p = i2c_p; + + /* slave address */ + bmp->i2c_trans.slave_addr = addr; + /* set initial status: Success or Done */ + bmp->i2c_trans.status = I2CTransDone; + + bmp->data_available = FALSE; + bmp->initialized = FALSE; + bmp->status = BMP085_STATUS_UNINIT; + + /* by default assign EOC function that always returns TRUE + * ensure proper timing through frequeny of bmp_periodic! + */ + bmp->eoc = &bmp085_eoc_true; +} + +void bmp085_periodic(struct Bmp085* bmp) +{ + switch (bmp->status) { + case BMP085_STATUS_IDLE: + /* start temp measurement */ + bmp->i2c_trans.buf[0] = BMP085_CTRL_REG; + bmp->i2c_trans.buf[1] = BMP085_START_TEMP; + i2c_transmit(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 2); + bmp->status = BMP085_STATUS_START_TEMP; + break; + + case BMP085_STATUS_START_TEMP: + /* read temp measurement */ + if (bmp->eoc()) { + bmp->i2c_trans.buf[0] = BMP085_DAT_MSB; + i2c_transceive(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 1, 2); + bmp->status = BMP085_STATUS_READ_TEMP; + } + break; + + case BMP085_STATUS_START_PRESS: + /* read press measurement */ + if (bmp->eoc()) { + bmp->i2c_trans.buf[0] = BMP085_DAT_MSB; + i2c_transceive(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 1, 3); + bmp->status = BMP085_STATUS_READ_PRESS; + } + break; + + default: + break; + } +} + +void bmp085_event(struct Bmp085* bmp) +{ + if (bmp->i2c_trans.status == I2CTransSuccess) { + switch (bmp->status) { + case BMP085_STATUS_UNINIT: + bmp->calib.ac1 = (bmp->i2c_trans.buf[0] << 8) | bmp->i2c_trans.buf[1]; + bmp->calib.ac2 = (bmp->i2c_trans.buf[2] << 8) | bmp->i2c_trans.buf[3]; + bmp->calib.ac3 = (bmp->i2c_trans.buf[4] << 8) | bmp->i2c_trans.buf[5]; + bmp->calib.ac4 = (bmp->i2c_trans.buf[6] << 8) | bmp->i2c_trans.buf[7]; + bmp->calib.ac5 = (bmp->i2c_trans.buf[8] << 8) | bmp->i2c_trans.buf[9]; + bmp->calib.ac6 = (bmp->i2c_trans.buf[10] << 8) | bmp->i2c_trans.buf[11]; + bmp->calib.b1 = (bmp->i2c_trans.buf[12] << 8) | bmp->i2c_trans.buf[13]; + bmp->calib.b2 = (bmp->i2c_trans.buf[14] << 8) | bmp->i2c_trans.buf[15]; + bmp->calib.mb = (bmp->i2c_trans.buf[16] << 8) | bmp->i2c_trans.buf[17]; + bmp->calib.mc = (bmp->i2c_trans.buf[18] << 8) | bmp->i2c_trans.buf[19]; + bmp->calib.md = (bmp->i2c_trans.buf[20] << 8) | bmp->i2c_trans.buf[21]; + bmp->status = BMP085_STATUS_IDLE; + bmp->initialized = TRUE; + break; + + case BMP085_STATUS_READ_TEMP: + /* get uncompensated temperature */ + bmp->ut = (bmp->i2c_trans.buf[0] << 8) | bmp->i2c_trans.buf[1]; + bmp->temperature = bmp085_compensated_temperature(&(bmp->calib), bmp->ut); + /* start high res pressure measurement */ + bmp->i2c_trans.buf[0] = BMP085_CTRL_REG; + bmp->i2c_trans.buf[1] = BMP085_START_P3; + i2c_transmit(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 2); + bmp->status = BMP085_STATUS_START_PRESS; + break; + + case BMP085_STATUS_READ_PRESS: + /* get uncompensated pressure */ + bmp->up = (bmp->i2c_trans.buf[0]<<16) | + (bmp->i2c_trans.buf[1] << 8) | + bmp->i2c_trans.buf[2]; + bmp->up = bmp->up >> (8 - BMP085_OSS); + bmp->pressure = bmp085_compensated_pressure(&(bmp->calib), bmp->up); + bmp->data_available = TRUE; + bmp->status = BMP085_STATUS_IDLE; + break; + + default: + break; + } + } + else if (bmp->i2c_trans.status == I2CTransFailed) { + /* try again */ + if (bmp->initialized) + bmp->status = BMP085_STATUS_IDLE; + else + bmp->status = BMP085_STATUS_UNINIT; + bmp->i2c_trans.status = I2CTransDone; + } +} diff --git a/sw/airborne/peripherals/bmp085.h b/sw/airborne/peripherals/bmp085.h new file mode 100644 index 0000000000..a335f1e3b5 --- /dev/null +++ b/sw/airborne/peripherals/bmp085.h @@ -0,0 +1,81 @@ +/* + * Copyright (C) 2010 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** @file peripherals/bmp085.h + * Bosch BMP085 driver interface. + */ + +#ifndef BMP085_H +#define BMP085_H + +#include "mcu_periph/i2c.h" +#include "std.h" + +enum Bmp085Status { + BMP085_STATUS_UNINIT, + BMP085_STATUS_IDLE, + BMP085_STATUS_START_TEMP, + BMP085_STATUS_READ_TEMP, + BMP085_STATUS_START_PRESS, + BMP085_STATUS_READ_PRESS +}; + +struct Bmp085Calib { + // These values come from EEPROM on sensor + int16_t ac1; + int16_t ac2; + int16_t ac3; + uint16_t ac4; + uint16_t ac5; + uint16_t ac6; + int16_t b1; + int16_t b2; + int16_t mb; + int16_t mc; + int16_t md; + + // These values are calculated + int32_t b5; +}; + +typedef bool_t (*Bmp085EOC)(void); + +struct Bmp085 { + struct i2c_periph *i2c_p; + struct i2c_transaction i2c_trans; + Bmp085EOC eoc; ///< function to check End Of Conversion + enum Bmp085Status status; ///< state machine status + bool_t initialized; ///< config done flag + volatile bool_t data_available; ///< data ready flag + struct Bmp085Calib calib; + int32_t ut; ///< uncompensated temperature + int32_t up; ///< uncompensated pressure + int32_t temperature; ///< temperature in 0.1 deg Celcius + int32_t pressure; ///< pressure in Pascal +}; + +extern void bmp085_read_eeprom_calib(struct Bmp085* bmp); +extern void bmp085_init(struct Bmp085* bmp, struct i2c_periph *i2c_p, uint8_t addr); +extern void bmp085_periodic(struct Bmp085* bmp); +extern void bmp085_event(struct Bmp085* bmp); + +#endif diff --git a/sw/airborne/peripherals/bmp085_regs.h b/sw/airborne/peripherals/bmp085_regs.h new file mode 100644 index 0000000000..fb94b6a67d --- /dev/null +++ b/sw/airborne/peripherals/bmp085_regs.h @@ -0,0 +1,59 @@ +/* + * Copyright (C) 2010 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** @file peripherals/bmp085_regs.h + * Bosch BMP085 register definitions. + */ + +#ifndef BMP085_REGS_H +#define BMP085_REGS_H + +#define BMP085_EEPROM_AC1 0xAA +#define BMP085_EEPROM_AC2 0xAC +#define BMP085_EEPROM_AC3 0xAE +#define BMP085_EEPROM_AC4 0xB0 +#define BMP085_EEPROM_AC5 0xB2 +#define BMP085_EEPROM_AC6 0xB4 +#define BMP085_EEPROM_B1 0xB6 +#define BMP085_EEPROM_B2 0xB8 +#define BMP085_EEPROM_MB 0xBA +#define BMP085_EEPROM_MC 0xBC +#define BMP085_EEPROM_MD 0xBE + +#define BMP085_CTRL_REG 0xF4 + +#define BMP085_START_TEMP 0x2E +#define BMP085_START_P0 0x34 +#define BMP085_START_P1 0x74 +#define BMP085_START_P2 0xB4 +#define BMP085_START_P3 0xF4 + +#define BMP085_DAT_MSB 0xF6 +#define BMP085_DAT_LSB 0xF7 +#define BMP085_DAT_XLSB 0xF8 + +/// Over sample setting (0-3) +#define BMP085_OSS 3 + +#define BMP085_SLAVE_ADDR 0xEE + +#endif From f2d2af9f681df918ef09e99b2032634a0b88b697 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 26 Aug 2013 21:57:53 +0200 Subject: [PATCH 133/309] [modules] use bmp085 peripheral for baro_bmp module also increase freq of periodic to 15Hz, should result in new measurements at 5Hz --- conf/modules/baro_bmp.xml | 5 +- sw/airborne/modules/sensors/baro_bmp.c | 203 ++++--------------------- sw/airborne/modules/sensors/baro_bmp.h | 77 +++++----- sw/airborne/peripherals/bmp085.c | 5 + 4 files changed, 74 insertions(+), 216 deletions(-) diff --git a/conf/modules/baro_bmp.xml b/conf/modules/baro_bmp.xml index 0fa9cc1edf..1bf6bde874 100644 --- a/conf/modules/baro_bmp.xml +++ b/conf/modules/baro_bmp.xml @@ -10,10 +10,11 @@ - + - + + diff --git a/sw/airborne/modules/sensors/baro_bmp.c b/sw/airborne/modules/sensors/baro_bmp.c index bdfce3a3af..5011b7d075 100644 --- a/sw/airborne/modules/sensors/baro_bmp.c +++ b/sw/airborne/modules/sensors/baro_bmp.c @@ -1,5 +1,6 @@ /* * Copyright (C) 2010 Martin Mueller + * Copyright (C) 2013 Felix Ruess * * This file is part of paparazzi. * @@ -20,14 +21,16 @@ * */ -/** \file baro_bmp.c - * \brief Bosch BMP085 I2C sensor interface +/** + * @file modules/sensors/baro_bmp.c + * Bosch BMP085 I2C sensor interface. * - * This reads the values for pressure and temperature from the Bosch BMP085 sensor through I2C. + * This reads the values for pressure and temperature from the Bosch BMP085 sensor through I2C. */ #include "baro_bmp.h" +#include "peripherals/bmp085_regs.h" #include "mcu_periph/sys_time.h" #include "mcu_periph/i2c.h" @@ -35,12 +38,6 @@ #include "mcu_periph/uart.h" #include "messages.h" #include "subsystems/datalink/downlink.h" -#include "state.h" -#include "subsystems/nav.h" - -#ifdef SITL -#include "subsystems/gps.h" -#endif #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE @@ -54,196 +51,56 @@ #define BMP_I2C_DEV i2c0 #endif -#define BMP085_SLAVE_ADDR 0xEE -#define BARO_BMP_OFFSET_MAX 30000 -#define BARO_BMP_OFFSET_MIN 10 -#define BARO_BMP_OFFSET_NBSAMPLES_INIT 2 -#define BARO_BMP_OFFSET_NBSAMPLES_AVRG 4 #define BARO_BMP_R 0.5 #define BARO_BMP_SIGMA2 0.1 -struct i2c_transaction bmp_trans; + +struct Bmp085 baro_bmp; bool_t baro_bmp_enabled; float baro_bmp_r; float baro_bmp_sigma2; +int32_t baro_bmp_alt; -// Global variables -uint8_t baro_bmp_status; -bool_t baro_bmp_valid; -uint32_t baro_bmp_pressure; -uint16_t baro_bmp_temperature; -int32_t baro_bmp_altitude, baro_bmp,baro_bmp_temp,baro_bmp_offset; -double tmp_float; +void baro_bmp_init(void) { -int16_t bmp_ac1, bmp_ac2, bmp_ac3; -uint16_t bmp_ac4, bmp_ac5, bmp_ac6; -int16_t bmp_b1, bmp_b2; -int16_t bmp_mb, bmp_mc, bmp_md; -int32_t bmp_up, bmp_ut; + bmp085_init(&baro_bmp, &BMP_I2C_DEV, BMP085_SLAVE_ADDR); -// Local variables -bool_t baro_bmp_offset_init; -int32_t baro_bmp_offset_tmp; -uint16_t baro_bmp_cnt; - -void baro_bmp_init( void ) { - baro_bmp_status = BARO_BMP_UNINIT; - baro_bmp_valid = FALSE; baro_bmp_r = BARO_BMP_R; baro_bmp_sigma2 = BARO_BMP_SIGMA2; baro_bmp_enabled = TRUE; - baro_bmp_offset_init = FALSE; - baro_bmp_cnt = BARO_BMP_OFFSET_NBSAMPLES_INIT + BARO_BMP_OFFSET_NBSAMPLES_AVRG; - /* read calibration values */ - bmp_trans.buf[0] = BMP085_EEPROM_AC1; - i2c_transceive(&BMP_I2C_DEV, &bmp_trans, BMP085_SLAVE_ADDR, 1, 22); -} - -void baro_bmp_periodic( void ) { -#ifndef SITL - if (baro_bmp_status == BARO_BMP_IDLE) { - /* start temp measurement (once) */ - bmp_trans.buf[0] = BMP085_CTRL_REG; - bmp_trans.buf[1] = BMP085_START_TEMP; - i2c_transmit(&BMP_I2C_DEV, &bmp_trans, BMP085_SLAVE_ADDR, 2); - baro_bmp_status = BARO_BMP_START_TEMP; - } - else if (baro_bmp_status == BARO_BMP_START_TEMP) { - /* read temp measurement */ - bmp_trans.buf[0] = BMP085_DAT_MSB; - i2c_transceive(&BMP_I2C_DEV, &bmp_trans, BMP085_SLAVE_ADDR, 1, 2); - baro_bmp_status = BARO_BMP_READ_TEMP; - } - else if (baro_bmp_status == BARO_BMP_START_PRESS) { - /* read press measurement */ - bmp_trans.buf[0] = BMP085_DAT_MSB; - i2c_transceive(&BMP_I2C_DEV, &bmp_trans, BMP085_SLAVE_ADDR, 1, 3); - baro_bmp_status = BARO_BMP_READ_PRESS; - } -#else // SITL - baro_bmp_altitude = gps.hmsl / 1000.0; - baro_bmp_pressure = baro_bmp_altitude; //FIXME do a proper scaling here - baro_bmp_valid = TRUE; -#endif } -void baro_bmp_event( void ) { +void baro_bmp_periodic(void) { - if (bmp_trans.status == I2CTransSuccess) { + if (baro_bmp.initialized) + bmp085_periodic(&baro_bmp); + else + bmp085_read_eeprom_calib(&baro_bmp); - if (baro_bmp_status == BARO_BMP_UNINIT) { - /* get calibration data */ - bmp_ac1 = (bmp_trans.buf[0] << 8) | bmp_trans.buf[1]; - bmp_ac2 = (bmp_trans.buf[2] << 8) | bmp_trans.buf[3]; - bmp_ac3 = (bmp_trans.buf[4] << 8) | bmp_trans.buf[5]; - bmp_ac4 = (bmp_trans.buf[6] << 8) | bmp_trans.buf[7]; - bmp_ac5 = (bmp_trans.buf[8] << 8) | bmp_trans.buf[9]; - bmp_ac6 = (bmp_trans.buf[10] << 8) | bmp_trans.buf[11]; - bmp_b1 = (bmp_trans.buf[12] << 8) | bmp_trans.buf[13]; - bmp_b2 = (bmp_trans.buf[14] << 8) | bmp_trans.buf[15]; - bmp_mb = (bmp_trans.buf[16] << 8) | bmp_trans.buf[17]; - bmp_mc = (bmp_trans.buf[18] << 8) | bmp_trans.buf[19]; - bmp_md = (bmp_trans.buf[20] << 8) | bmp_trans.buf[21]; - baro_bmp_status = BARO_BMP_IDLE; - } - else if (baro_bmp_status == BARO_BMP_READ_TEMP) { - /* get uncompensated temperature */ - bmp_ut = (bmp_trans.buf[0] << 8) | bmp_trans.buf[1]; - /* start high res pressure measurement */ - bmp_trans.buf[0] = BMP085_CTRL_REG; - bmp_trans.buf[1] = BMP085_START_P3; - i2c_transmit(&BMP_I2C_DEV, &bmp_trans, BMP085_SLAVE_ADDR, 2); - baro_bmp_status = BARO_BMP_START_PRESS; - } - else if (baro_bmp_status == BARO_BMP_READ_PRESS) { - int32_t bmp_p, bmp_t; - int32_t bmp_x1, bmp_x2, bmp_x3; - int32_t bmp_b3, bmp_b5, bmp_b6; - uint32_t bmp_b4, bmp_b7; +} - /* get uncompensated pressure, oss=3 */ - bmp_up = (bmp_trans.buf[0] << 11) | - (bmp_trans.buf[1] << 3) | - (bmp_trans.buf[2] >> 5); - /* start temp measurement */ - bmp_trans.buf[0] = BMP085_CTRL_REG; - bmp_trans.buf[1] = BMP085_START_TEMP; - i2c_transmit(&BMP_I2C_DEV, &bmp_trans, BMP085_SLAVE_ADDR, 2); - baro_bmp_status = BARO_BMP_START_TEMP; +void baro_bmp_event(void) { - /* compensate temperature */ - bmp_x1 = (bmp_ut - bmp_ac6) * bmp_ac5 / (1<<15); - bmp_x2 = bmp_mc * (1<<11) / (bmp_x1 + bmp_md); - bmp_b5 = bmp_x1 + bmp_x2; - bmp_t = (bmp_b5 + 8) / (1<<4); + bmp085_event(&baro_bmp); - /* compensate pressure */ - bmp_b6 = bmp_b5 - 4000; - bmp_x1 = (bmp_b2 * (bmp_b6 * bmp_b6 / (1<<12))) / (1<<11); - bmp_x2 = bmp_ac2 *bmp_b6 / (1<<11); - bmp_x3 = bmp_x1 + bmp_x2; - bmp_b3 = (((bmp_ac1 * 4 + bmp_x3) << 3) + 2) / 4; - bmp_x1 = bmp_ac3 * bmp_b6 / (1<<13); - bmp_x2 = (bmp_b1 * (bmp_b6 * bmp_b6 / (1<<12))) / (1<<16); - bmp_x3 = ((bmp_x1 + bmp_x2) +2) / (1<<2); - bmp_b4 = bmp_ac4 * (uint32_t)(bmp_x3 + 32768) / (1<<15); - bmp_b7 = ((uint32_t)bmp_up - bmp_b3) * (50000>>3); - if (bmp_b7 < 0x80000000) - bmp_p = (bmp_b7 * 2) / bmp_b4; - else - bmp_p = (bmp_b7 / bmp_b4) * 2; - bmp_x1 = (bmp_p / (1<<8)) * (bmp_p / (1<<8)); - bmp_x1 = (bmp_x1 * 3038) / (1<<16); - bmp_x2 = (-7357 * bmp_p) / (1<<16); - bmp_p = bmp_p + (bmp_x1 + bmp_x2 + 3791) / (1<<4); + if (baro_bmp.data_available) { - baro_bmp_temperature = bmp_t; - baro_bmp_pressure = bmp_p; - - tmp_float = bmp_p/101325.0; //pressao nivel mar - tmp_float = pow(tmp_float,0.190295); //eleva pressao ao expoente - baro_bmp = 44330*(1.0-tmp_float); - - if (!baro_bmp_offset_init) { - baro_bmp_offset = baro_bmp; - baro_bmp_offset_init = TRUE; -#if 0 - --baro_bmp_cnt; - // Check if averaging completed - if (baro_bmp_cnt == 0) { - // Calculate average - baro_bmp_offset = (baro_bmp_offset_tmp / BARO_BMP_OFFSET_NBSAMPLES_AVRG); - // Limit offset - if (baro_bmp_offset < BARO_BMP_OFFSET_MIN) - baro_bmp_offset = BARO_BMP_OFFSET_MIN; - if (baro_bmp_offset > BARO_BMP_OFFSET_MAX) - baro_bmp_offset = BARO_BMP_OFFSET_MAX; - baro_bmp_offset_init = TRUE; - } - // Check if averaging needs to continue - else if (baro_bmp_cnt <= BARO_BMP_OFFSET_NBSAMPLES_AVRG) - baro_bmp_offset_tmp += baro_bmp; -#endif - } //baro offset init - - baro_bmp_temp = (baro_bmp - baro_bmp_offset); - - if (baro_bmp_offset_init) { - baro_bmp_altitude = ground_alt + baro_bmp_temp; - // New value available - baro_bmp_valid = TRUE; + float tmp = baro_bmp.pressure / 101325.0; // pressure at sea level + tmp = pow(tmp, 0.190295); + baro_bmp_alt = 44330 * (1.0 - tmp); #ifdef SENSOR_SYNC_SEND - DOWNLINK_SEND_BMP_STATUS(DefaultChannel, DefaultDevice, &bmp_up, &bmp_ut, &bmp_p, &bmp_t); + DOWNLINK_SEND_BMP_STATUS(DefaultChannel, DefaultDevice, &baro_bmp.up, + &baro_bmp.ut, &baro_bmp.pressure, + &baro_bmp.temperature); #else - RunOnceEvery(10, DOWNLINK_SEND_BMP_STATUS(DefaultChannel, DefaultDevice, &baro_bmp_temp, &bmp_ut, &bmp_p, &bmp_t)); + RunOnceEvery(10, DOWNLINK_SEND_BMP_STATUS(DefaultChannel, DefaultDevice, + &baro_bmp.up, &baro_bmp.ut, + &baro_bmp.pressure, + &baro_bmp.temperature)); #endif - } else { - baro_bmp_altitude = 0.0; - } - } } } diff --git a/sw/airborne/modules/sensors/baro_bmp.h b/sw/airborne/modules/sensors/baro_bmp.h index 53adeb184d..46dd30991f 100644 --- a/sw/airborne/modules/sensors/baro_bmp.h +++ b/sw/airborne/modules/sensors/baro_bmp.h @@ -1,56 +1,51 @@ +/* + * Copyright (C) 2010 Martin Mueller + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file modules/sensors/baro_bmp.h + * Bosch BMP085 I2C sensor interface. + * + * This reads the values for pressure and temperature from the Bosch BMP085 sensor through I2C. + */ + #ifndef BARO_BMP_H #define BARO_BMP_H -#include "std.h" +#include "peripherals/bmp085.h" -#define BMP085_EEPROM_AC1 0xAA -#define BMP085_EEPROM_AC2 0xAC -#define BMP085_EEPROM_AC3 0xAE -#define BMP085_EEPROM_AC4 0xB0 -#define BMP085_EEPROM_AC5 0xB2 -#define BMP085_EEPROM_AC6 0xB4 -#define BMP085_EEPROM_B1 0xB6 -#define BMP085_EEPROM_B2 0xB8 -#define BMP085_EEPROM_MB 0xBA -#define BMP085_EEPROM_MC 0xBC -#define BMP085_EEPROM_MD 0xBE +extern struct Bmp085 baro_bmp; -#define BMP085_CTRL_REG 0xF4 - -#define BMP085_START_TEMP 0x2E -#define BMP085_START_P0 0x34 -#define BMP085_START_P1 0x74 -#define BMP085_START_P2 0xB4 -#define BMP085_START_P3 0xF4 - -#define BMP085_DAT_MSB 0xF6 -#define BMP085_DAT_LSB 0xF7 -#define BMP085_DAT_XLSB 0xF8 - -#define BARO_BMP_UNINIT 0 -#define BARO_BMP_IDLE 1 -#define BARO_BMP_START_TEMP 2 -#define BARO_BMP_READ_TEMP 3 -#define BARO_BMP_START_PRESS 4 -#define BARO_BMP_READ_PRESS 5 - -#define BARO_BMP_DT 0.05 +/// new measurement every 3rd execution of baro_bmp_periodic +#define BARO_BMP_DT (BARO_BMP_PERIODIC_PERIOD / 3) extern bool_t baro_bmp_enabled; extern float baro_bmp_r; extern float baro_bmp_sigma2; - -extern uint8_t baro_bmp_status; -extern bool_t baro_bmp_valid; -extern uint32_t baro_bmp_pressure; -extern uint16_t baro_bmp_temperature; -extern int32_t baro_bmp_altitude; -extern int32_t baro_bmp; -extern int32_t baro_bmp_offset; +extern int32_t baro_bmp_alt; void baro_bmp_init(void); void baro_bmp_periodic(void); void baro_bmp_event(void); -#define BaroBmpUpdate(_b) { if (baro_bmp_valid) { _b = baro_bmp_pressure; baro_bmp_valid = FALSE; } } +#define BaroBmpUpdate(_b) { if (baro_bmp.data_available) { _b = baro_bmp.pressure; baro_bmp.data_available = FALSE; } } #endif diff --git a/sw/airborne/peripherals/bmp085.c b/sw/airborne/peripherals/bmp085.c index 60630d02cb..2c123ef592 100644 --- a/sw/airborne/peripherals/bmp085.c +++ b/sw/airborne/peripherals/bmp085.c @@ -100,6 +100,11 @@ void bmp085_init(struct Bmp085* bmp, struct i2c_periph *i2c_p, uint8_t addr) bmp->eoc = &bmp085_eoc_true; } +/** + * Start new measurement if idle or read temp/pressure. + * Should run at < 40Hz unless eoc check function is provided. + * At ultra high resolution (oss = 3) conversion time is max 25.5ms. + */ void bmp085_periodic(struct Bmp085* bmp) { switch (bmp->status) { From b895ded49c1508405110d8315892b6753880568a Mon Sep 17 00:00:00 2001 From: fvantienen Date: Mon, 26 Aug 2013 14:24:42 +0200 Subject: [PATCH 134/309] [ardrone2] Magneto axis correction and calibration --- conf/airframes/ardrone2_raw.xml | 35 +++++++-------- sw/airborne/boards/ardrone/electrical_raw.c | 44 +++++++++++++++++++ sw/airborne/boards/ardrone/navdata.h | 2 +- sw/airborne/subsystems/imu/imu_ardrone2_raw.h | 6 +-- 4 files changed, 65 insertions(+), 22 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 09f5b3f97d..f72c47161c 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -22,18 +22,16 @@ - + - @@ -71,16 +69,16 @@
- - - + + + - - + + @@ -90,19 +88,19 @@ - - + + - - - - - - + + + + + + - + - + @@ -232,6 +230,7 @@
+ diff --git a/sw/airborne/boards/ardrone/electrical_raw.c b/sw/airborne/boards/ardrone/electrical_raw.c index 6dd9e93cd0..f47f0157bd 100644 --- a/sw/airborne/boards/ardrone/electrical_raw.c +++ b/sw/airborne/boards/ardrone/electrical_raw.c @@ -36,9 +36,35 @@ #include #include #include "i2c-dev.h" +#include "subsystems/commands.h" +#include "generated/airframe.h" struct Electrical electrical; +#if defined ADC_CHANNEL_VSUPPLY || defined ADC_CHANNEL_CURRENT || defined MILLIAMP_AT_FULL_THROTTLE +static struct { +#ifdef ADC_CHANNEL_VSUPPLY + struct adc_buf vsupply_adc_buf; +#endif +#ifdef ADC_CHANNEL_CURRENT + struct adc_buf current_adc_buf; +#endif +#ifdef MILLIAMP_AT_FULL_THROTTLE + float nonlin_factor; +#endif +} electrical_priv; +#endif + +#if defined COMMAND_THROTTLE +#define COMMAND_CURRENT_ESTIMATION COMMAND_THROTTLE +#elif defined COMMAND_THRUST +#define COMMAND_CURRENT_ESTIMATION COMMAND_THRUST +#endif + +#ifndef CURRENT_ESTIMATION_NONLINEARITY +#define CURRENT_ESTIMATION_NONLINEARITY 1.2 +#endif + int fd; void electrical_init(void) { @@ -51,6 +77,7 @@ void electrical_init(void) { } electrical_setup(); + electrical_priv.nonlin_factor = CURRENT_ESTIMATION_NONLINEARITY; } void electrical_setup(void) { @@ -94,4 +121,21 @@ void electrical_periodic(void) { //9.0V=662, 9.5V=698, 10.0V=737,10.5V=774, 11.0V=811, 11.5V=848, 12.0V=886, 12.5V=923 //leading to our 0.13595166 magic number for decivolts conversion electrical.vsupply = raw_voltage*0.13595166; + + /* + * Superellipse: abs(x/a)^n + abs(y/b)^n = 1 + * with a = 1 + * b = mA at full throttle + * n = 1.2 This defines nonlinearity (1 = linear) + * x = throttle + * y = current + * + * define CURRENT_ESTIMATION_NONLINEARITY in your airframe file to change the default nonlinearity factor of 1.2 + */ + float b = (float)MILLIAMP_AT_FULL_THROTTLE; + float x = ((float)commands[COMMAND_CURRENT_ESTIMATION]) / ((float)MAX_PPRZ); + /* electrical.current y = ( b^n - (b* x/a)^n )^1/n + * a=1, n = electrical_priv.nonlin_factor + */ + electrical.current = b - pow((pow(b,electrical_priv.nonlin_factor)-pow((b*x),electrical_priv.nonlin_factor)), (1./electrical_priv.nonlin_factor)); } diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index ec40241dcc..922bb2e46b 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -81,8 +81,8 @@ typedef struct int32_t pressure; uint16_t temperature_pressure; - int16_t mx; int16_t my; + int16_t mx; int16_t mz; uint16_t chksum; diff --git a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h index 9688459bca..99a9f39d52 100644 --- a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h +++ b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h @@ -39,9 +39,9 @@ static inline void imu_ardrone2_event ( void (* _gyro_handler)(void), void (* _a //checks if the navboard has a new dataset ready if (navdata_imu_available == TRUE) { navdata_imu_available = FALSE; - RATES_ASSIGN(imu.gyro_unscaled, navdata->vx, navdata->vy, navdata->vz); - VECT3_ASSIGN(imu.accel_unscaled, navdata->ax, navdata->ay, navdata->az); - VECT3_ASSIGN(imu.mag_unscaled, navdata->mx, navdata->my, navdata->mz); + RATES_ASSIGN(imu.gyro_unscaled, navdata->vx, -navdata->vy, -navdata->vz); + VECT3_ASSIGN(imu.accel_unscaled, navdata->ax, 4096-navdata->ay, 4096-navdata->az); + VECT3_ASSIGN(imu.mag_unscaled, -navdata->mx, -navdata->my, -navdata->mz); _gyro_handler(); _accel_handler(); From eacf610e88f3aeaeb21ca22a470e57d2c10b181d Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 27 Aug 2013 14:33:44 +0200 Subject: [PATCH 135/309] [Build] Compile info about selected Arming --- sw/airborne/firmwares/rotorcraft/autopilot.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index b67685765f..41c21a3343 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -68,10 +68,13 @@ static inline int ahrs_is_aligned(void) { #if USE_KILL_SWITCH_FOR_MOTOR_ARMING #include "autopilot_arming_switch.h" +PRINT_CONFIG_MSG("Using kill switch for motor arming") #elif USE_THROTTLE_FOR_MOTOR_ARMING #include "autopilot_arming_throttle.h" +PRINT_CONFIG_MSG("Using throttle for motor arming") #else #include "autopilot_arming_yaw.h" +PRINT_CONFIG_MSG("Using 2 sec yaw for motor arming") #endif #ifndef MODE_STARTUP From fbdb40d0293ba42cfc46b10a41ca7ba7c11b304b Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 27 Aug 2013 15:26:47 +0200 Subject: [PATCH 136/309] [airframes] CDW --- conf/airframes/CDW/asctec_cdw.xml | 224 +++++++++++++++++++++++++++ conf/airframes/CDW/tricopter_cdw.xml | 214 +++++++++++++++++++++++++ 2 files changed, 438 insertions(+) create mode 100644 conf/airframes/CDW/asctec_cdw.xml create mode 100644 conf/airframes/CDW/tricopter_cdw.xml diff --git a/conf/airframes/CDW/asctec_cdw.xml b/conf/airframes/CDW/asctec_cdw.xml new file mode 100644 index 0000000000..300eb6eb11 --- /dev/null +++ b/conf/airframes/CDW/asctec_cdw.xml @@ -0,0 +1,224 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + +
+ + + + + + + + + + + +
+ + + + + + + + + + + + + + + +
+ +
+ +
+ + + +
+ + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ + + + + +
+ + +
+ +
+ + + +
+ +
+ +
+ +
+ +
+ +
+ + + +
+ +
diff --git a/conf/airframes/CDW/tricopter_cdw.xml b/conf/airframes/CDW/tricopter_cdw.xml new file mode 100644 index 0000000000..00d9368d88 --- /dev/null +++ b/conf/airframes/CDW/tricopter_cdw.xml @@ -0,0 +1,214 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ + + + + + + + + + +
+ + + +
+ + + + + + + + + + + + + + + + + + +
+ + + + + + + + + +
+ + + + + + + + + + + +
+ + + + + + + + + +
+ +
+ +
+ + + +
+ + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + +
+ +
+ + + +
+ + + +
+ +
+ +
+ +
+ +
+ + + +
+ +
+ + + +
+ +
From 261df1f18589bec48d9a4617d90e88eb7e76929e Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 15:37:52 +0200 Subject: [PATCH 137/309] [boards] baro_board fixes for lia --- sw/airborne/boards/lia/baro_board.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/boards/lia/baro_board.h b/sw/airborne/boards/lia/baro_board.h index d65c11d266..59782132c8 100644 --- a/sw/airborne/boards/lia/baro_board.h +++ b/sw/airborne/boards/lia/baro_board.h @@ -9,8 +9,8 @@ #include "std.h" -extern void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)); +extern void baro_event(void (*b_abs_handler)(void)); -#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler,_b_diff_handler) +#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler) #endif /* BOARDS_LIA_BARO_H */ From e10c953b277644b73e6e3e77c77bcfa4bcf57964 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Tue, 27 Aug 2013 16:47:48 +0200 Subject: [PATCH 138/309] [apogee] fix type in board file --- sw/airborne/boards/apogee_1.0.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/boards/apogee_1.0.h b/sw/airborne/boards/apogee_1.0.h index a9ca6af6c5..343c514eca 100644 --- a/sw/airborne/boards/apogee_1.0.h +++ b/sw/airborne/boards/apogee_1.0.h @@ -308,7 +308,7 @@ #endif #if USE_PWM3 -#define PWM_SERVO_3_IDX 3 +#define PWM_SERVO_3 3 #define PWM_SERVO_3_TIMER TIM3 #define PWM_SERVO_3_RCC_IOP RCC_AHB1ENR_IOPBEN #define PWM_SERVO_3_GPIO GPIOB From 42edf3a1aed315ac14881aad082fa8ebe1fc06eb Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 16:17:36 +0200 Subject: [PATCH 139/309] [mcu_periph][i2c] add queue_full_cnt - also set transaction status to I2CTransFailed on stm32 (like already the case on lpc21) - add I2C_ERRORS message to fixedwing --- conf/messages.xml | 1 + sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c | 4 +- sw/airborne/arch/stm32/mcu_periph/i2c_arch.c | 8 +- sw/airborne/firmwares/fixedwing/ap_downlink.h | 146 ++++++++++++++++++ sw/airborne/firmwares/rotorcraft/telemetry.h | 38 +++++ sw/airborne/mcu_periph/i2c.h | 2 + 6 files changed, 196 insertions(+), 3 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index 456a1cd8ab..683bac8e3c 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -2076,6 +2076,7 @@ + diff --git a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c index 5838dcea14..0f405325d3 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c @@ -336,8 +336,10 @@ bool_t i2c_submit(struct i2c_periph* p, struct i2c_transaction* t) { idx = p->trans_insert_idx + 1; if (idx >= I2C_TRANSACTION_QUEUE_LEN) idx = 0; if (idx == p->trans_extract_idx) { + /* queue full */ + periph->errors->queue_full_cnt++; t->status = I2CTransFailed; - return FALSE; /* queue full */ + return FALSE; } t->status = I2CTransPending; diff --git a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c index 046f0c9441..38e737db23 100644 --- a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c @@ -1316,8 +1316,12 @@ bool_t i2c_submit(struct i2c_periph* periph, struct i2c_transaction* t) { uint8_t temp; temp = periph->trans_insert_idx + 1; if (temp >= I2C_TRANSACTION_QUEUE_LEN) temp = 0; - if (temp == periph->trans_extract_idx) - return FALSE; // queue full + if (temp == periph->trans_extract_idx) { + // queue full + periph->errors->queue_full_cnt++; + t->status = I2CTransFailed; + return FALSE; + } t->status = I2CTransPending; diff --git a/sw/airborne/firmwares/fixedwing/ap_downlink.h b/sw/airborne/firmwares/fixedwing/ap_downlink.h index 76bdf38f2b..dc7ede333a 100644 --- a/sw/airborne/firmwares/fixedwing/ap_downlink.h +++ b/sw/airborne/firmwares/fixedwing/ap_downlink.h @@ -47,6 +47,9 @@ #include "messages.h" #include "generated/periodic_telemetry.h" +// I2C Error counters +#include "mcu_periph/i2c.h" + #if defined DOWNLINK #define Downlink(x) x #else @@ -333,4 +336,147 @@ #define PERIODIC_SEND_GX3_INFO(_trans, _dev) {} #endif +#ifdef USE_I2C0 +#define PERIODIC_SEND_I2C0_ERRORS(_trans, _dev) { \ + uint16_t i2c0_queue_full_cnt = i2c0.errors->queue_full_cnt; \ + uint16_t i2c0_ack_fail_cnt = i2c0.errors->ack_fail_cnt; \ + uint16_t i2c0_miss_start_stop_cnt = i2c0.errors->miss_start_stop_cnt; \ + uint16_t i2c0_arb_lost_cnt = i2c0.errors->arb_lost_cnt; \ + uint16_t i2c0_over_under_cnt = i2c0.errors->over_under_cnt; \ + uint16_t i2c0_pec_recep_cnt = i2c0.errors->pec_recep_cnt; \ + uint16_t i2c0_timeout_tlow_cnt = i2c0.errors->timeout_tlow_cnt; \ + uint16_t i2c0_smbus_alert_cnt = i2c0.errors->smbus_alert_cnt; \ + uint16_t i2c0_unexpected_event_cnt = i2c0.errors->unexpected_event_cnt; \ + uint32_t i2c0_last_unexpected_event = i2c0.errors->last_unexpected_event; \ + const uint8_t _bus0 = 0; \ + DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c0_queue_full_cnt, \ + &i2c0_ack_fail_cnt, \ + &i2c0_miss_start_stop_cnt, \ + &i2c0_arb_lost_cnt, \ + &i2c0_over_under_cnt, \ + &i2c0_pec_recep_cnt, \ + &i2c0_timeout_tlow_cnt, \ + &i2c0_smbus_alert_cnt, \ + &i2c0_unexpected_event_cnt, \ + &i2c0_last_unexpected_event, \ + &_bus0); \ + } +#else +#define PERIODIC_SEND_I2C0_ERRORS(_trans, _dev) {} +#endif + +#ifdef USE_I2C1 +#define PERIODIC_SEND_I2C1_ERRORS(_trans, _dev) { \ + uint16_t i2c1_queue_full_cnt = i2c1.errors->queue_full_cnt; \ + uint16_t i2c1_ack_fail_cnt = i2c1.errors->ack_fail_cnt; \ + uint16_t i2c1_miss_start_stop_cnt = i2c1.errors->miss_start_stop_cnt; \ + uint16_t i2c1_arb_lost_cnt = i2c1.errors->arb_lost_cnt; \ + uint16_t i2c1_over_under_cnt = i2c1.errors->over_under_cnt; \ + uint16_t i2c1_pec_recep_cnt = i2c1.errors->pec_recep_cnt; \ + uint16_t i2c1_timeout_tlow_cnt = i2c1.errors->timeout_tlow_cnt; \ + uint16_t i2c1_smbus_alert_cnt = i2c1.errors->smbus_alert_cnt; \ + uint16_t i2c1_unexpected_event_cnt = i2c1.errors->unexpected_event_cnt; \ + uint32_t i2c1_last_unexpected_event = i2c1.errors->last_unexpected_event; \ + const uint8_t _bus1 = 1; \ + DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c1_queue_full_cnt, \ + &i2c1_ack_fail_cnt, \ + &i2c1_miss_start_stop_cnt, \ + &i2c1_arb_lost_cnt, \ + &i2c1_over_under_cnt, \ + &i2c1_pec_recep_cnt, \ + &i2c1_timeout_tlow_cnt, \ + &i2c1_smbus_alert_cnt, \ + &i2c1_unexpected_event_cnt, \ + &i2c1_last_unexpected_event, \ + &_bus1); \ + } +#else +#define PERIODIC_SEND_I2C1_ERRORS(_trans, _dev) {} +#endif + +#ifdef USE_I2C2 +#define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) { \ + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; \ + uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; \ + uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; \ + uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; \ + uint16_t i2c2_over_under_cnt = i2c2.errors->over_under_cnt; \ + uint16_t i2c2_pec_recep_cnt = i2c2.errors->pec_recep_cnt; \ + uint16_t i2c2_timeout_tlow_cnt = i2c2.errors->timeout_tlow_cnt; \ + uint16_t i2c2_smbus_alert_cnt = i2c2.errors->smbus_alert_cnt; \ + uint16_t i2c2_unexpected_event_cnt = i2c2.errors->unexpected_event_cnt; \ + uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; \ + const uint8_t _bus2 = 2; \ + DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c2_queue_full_cnt, \ + &i2c2_ack_fail_cnt, \ + &i2c2_miss_start_stop_cnt, \ + &i2c2_arb_lost_cnt, \ + &i2c2_over_under_cnt, \ + &i2c2_pec_recep_cnt, \ + &i2c2_timeout_tlow_cnt, \ + &i2c2_smbus_alert_cnt, \ + &i2c2_unexpected_event_cnt, \ + &i2c2_last_unexpected_event, \ + &_bus2); \ + } +#else +#define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) {} +#endif + +#ifdef USE_I2C3 +#define PERIODIC_SEND_I2C3_ERRORS(_trans, _dev) { \ + uint16_t i2c3_queue_full_cnt = i2c3.errors->queue_full_cnt; \ + uint16_t i2c3_ack_fail_cnt = i2c3.errors->ack_fail_cnt; \ + uint16_t i2c3_miss_start_stop_cnt = i2c3.errors->miss_start_stop_cnt; \ + uint16_t i2c3_arb_lost_cnt = i2c3.errors->arb_lost_cnt; \ + uint16_t i2c3_over_under_cnt = i2c3.errors->over_under_cnt; \ + uint16_t i2c3_pec_recep_cnt = i2c3.errors->pec_recep_cnt; \ + uint16_t i2c3_timeout_tlow_cnt = i2c3.errors->timeout_tlow_cnt; \ + uint16_t i2c3_smbus_alert_cnt = i2c3.errors->smbus_alert_cnt; \ + uint16_t i2c3_unexpected_event_cnt = i2c3.errors->unexpected_event_cnt; \ + uint32_t i2c3_last_unexpected_event = i2c3.errors->last_unexpected_event; \ + const uint8_t _bus3 = 3; \ + DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c3_queue_full_cnt, \ + &i2c3_ack_fail_cnt, \ + &i2c3_miss_start_stop_cnt, \ + &i2c3_arb_lost_cnt, \ + &i2c3_over_under_cnt, \ + &i2c3_pec_recep_cnt, \ + &i2c3_timeout_tlow_cnt, \ + &i2c3_smbus_alert_cnt, \ + &i2c3_unexpected_event_cnt, \ + &i2c3_last_unexpected_event, \ + &_bus3); \ + } +#else +#define PERIODIC_SEND_I2C3_ERRORS(_trans, _dev) {} +#endif + +#ifndef SITL +#define PERIODIC_SEND_I2C_ERRORS(_trans, _dev) { \ + static uint8_t _i2c_nb_cnt = 0; \ + switch (_i2c_nb_cnt) { \ + case 0: \ + PERIODIC_SEND_I2C0_ERRORS(_trans, _dev); break; \ + case 1: \ + PERIODIC_SEND_I2C1_ERRORS(_trans, _dev); break; \ + case 2: \ + PERIODIC_SEND_I2C2_ERRORS(_trans, _dev); break; \ + case 3: \ + PERIODIC_SEND_I2C3_ERRORS(_trans, _dev); break; \ + default: \ + break; \ + } \ + _i2c_nb_cnt++; \ + if (_i2c_nb_cnt == 3) \ + _i2c_nb_cnt = 0; \ + } +#else +#define PERIODIC_SEND_I2C_ERRORS(_trans, _dev) {} +#endif + #endif /* AP_DOWNLINK_H */ diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 4522d049b4..a1b3472812 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -774,6 +774,7 @@ #ifdef USE_I2C0 #define PERIODIC_SEND_I2C0_ERRORS(_trans, _dev) { \ + uint16_t i2c0_queue_full_cnt = i2c0.errors->queue_full_cnt; \ uint16_t i2c0_ack_fail_cnt = i2c0.errors->ack_fail_cnt; \ uint16_t i2c0_miss_start_stop_cnt = i2c0.errors->miss_start_stop_cnt; \ uint16_t i2c0_arb_lost_cnt = i2c0.errors->arb_lost_cnt; \ @@ -785,6 +786,7 @@ uint32_t i2c0_last_unexpected_event = i2c0.errors->last_unexpected_event; \ const uint8_t _bus0 = 0; \ DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c0_queue_full_cnt, \ &i2c0_ack_fail_cnt, \ &i2c0_miss_start_stop_cnt, \ &i2c0_arb_lost_cnt, \ @@ -802,6 +804,7 @@ #ifdef USE_I2C1 #define PERIODIC_SEND_I2C1_ERRORS(_trans, _dev) { \ + uint16_t i2c1_queue_full_cnt = i2c1.errors->queue_full_cnt; \ uint16_t i2c1_ack_fail_cnt = i2c1.errors->ack_fail_cnt; \ uint16_t i2c1_miss_start_stop_cnt = i2c1.errors->miss_start_stop_cnt; \ uint16_t i2c1_arb_lost_cnt = i2c1.errors->arb_lost_cnt; \ @@ -813,6 +816,7 @@ uint32_t i2c1_last_unexpected_event = i2c1.errors->last_unexpected_event; \ const uint8_t _bus1 = 1; \ DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c1_queue_full_cnt, \ &i2c1_ack_fail_cnt, \ &i2c1_miss_start_stop_cnt, \ &i2c1_arb_lost_cnt, \ @@ -830,6 +834,7 @@ #ifdef USE_I2C2 #define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) { \ + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; \ uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; \ uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; \ uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; \ @@ -841,6 +846,7 @@ uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; \ const uint8_t _bus2 = 2; \ DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c2_queue_full_cnt, \ &i2c2_ack_fail_cnt, \ &i2c2_miss_start_stop_cnt, \ &i2c2_arb_lost_cnt, \ @@ -856,6 +862,36 @@ #define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) {} #endif +#ifdef USE_I2C3 +#define PERIODIC_SEND_I2C3_ERRORS(_trans, _dev) { \ + uint16_t i2c3_queue_full_cnt = i2c3.errors->queue_full_cnt; \ + uint16_t i2c3_ack_fail_cnt = i2c3.errors->ack_fail_cnt; \ + uint16_t i2c3_miss_start_stop_cnt = i2c3.errors->miss_start_stop_cnt; \ + uint16_t i2c3_arb_lost_cnt = i2c3.errors->arb_lost_cnt; \ + uint16_t i2c3_over_under_cnt = i2c3.errors->over_under_cnt; \ + uint16_t i2c3_pec_recep_cnt = i2c3.errors->pec_recep_cnt; \ + uint16_t i2c3_timeout_tlow_cnt = i2c3.errors->timeout_tlow_cnt; \ + uint16_t i2c3_smbus_alert_cnt = i2c3.errors->smbus_alert_cnt; \ + uint16_t i2c3_unexpected_event_cnt = i2c3.errors->unexpected_event_cnt; \ + uint32_t i2c3_last_unexpected_event = i2c3.errors->last_unexpected_event; \ + const uint8_t _bus3 = 3; \ + DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \ + &i2c3_queue_full_cnt, \ + &i2c3_ack_fail_cnt, \ + &i2c3_miss_start_stop_cnt, \ + &i2c3_arb_lost_cnt, \ + &i2c3_over_under_cnt, \ + &i2c3_pec_recep_cnt, \ + &i2c3_timeout_tlow_cnt, \ + &i2c3_smbus_alert_cnt, \ + &i2c3_unexpected_event_cnt, \ + &i2c3_last_unexpected_event, \ + &_bus3); \ + } +#else +#define PERIODIC_SEND_I2C3_ERRORS(_trans, _dev) {} +#endif + #ifndef SITL #define PERIODIC_SEND_I2C_ERRORS(_trans, _dev) { \ static uint8_t _i2c_nb_cnt = 0; \ @@ -866,6 +902,8 @@ PERIODIC_SEND_I2C1_ERRORS(_trans, _dev); break; \ case 2: \ PERIODIC_SEND_I2C2_ERRORS(_trans, _dev); break; \ + case 3: \ + PERIODIC_SEND_I2C3_ERRORS(_trans, _dev); break; \ default: \ break; \ } \ diff --git a/sw/airborne/mcu_periph/i2c.h b/sw/airborne/mcu_periph/i2c.h index ac8872bd9c..5d0220ebda 100644 --- a/sw/airborne/mcu_periph/i2c.h +++ b/sw/airborne/mcu_periph/i2c.h @@ -102,6 +102,7 @@ struct i2c_periph { struct i2c_errors { + volatile uint16_t queue_full_cnt; volatile uint16_t ack_fail_cnt; volatile uint16_t miss_start_stop_cnt; volatile uint16_t arb_lost_cnt; @@ -126,6 +127,7 @@ struct i2c_errors { } #define ZEROS_ERR_COUNTER(_i2c_err) { \ + _i2c_err.queue_full_cnt = 0; \ _i2c_err.ack_fail_cnt = 0; \ _i2c_err.miss_start_stop_cnt = 0; \ _i2c_err.arb_lost_cnt = 0; \ From 17fa58d265dbc37d1f2564444cb33772d482bfab Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 27 Aug 2013 16:59:09 +0200 Subject: [PATCH 140/309] [ardrone] Default IMU calibration in header file --- conf/airframes/ardrone2_raw.xml | 28 +------ sw/airborne/subsystems/imu/imu_ardrone2_raw.h | 77 +++++++++++++++++++ 2 files changed, 79 insertions(+), 26 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index f72c47161c..1a4f10df16 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -72,35 +72,11 @@ - - - - - - - - - - - - - - - - - - - - - - - + + - - - diff --git a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h index 99a9f39d52..18b1b1bbad 100644 --- a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h +++ b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h @@ -31,6 +31,83 @@ #include "generated/airframe.h" #include "navdata.h" +#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN +#define IMU_MAG_X_SIGN 1 +#define IMU_MAG_Y_SIGN 1 +#define IMU_MAG_Z_SIGN 1 +#endif +#if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN +#define IMU_GYRO_P_SIGN 1 +#define IMU_GYRO_Q_SIGN 1 +#define IMU_GYRO_R_SIGN 1 +#endif +#if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN +#define IMU_ACCEL_X_SIGN 1 +#define IMU_ACCEL_Y_SIGN 1 +#define IMU_ACCEL_Z_SIGN 1 +#endif + +/** default gyro sensitivy and neutral from the datasheet + * MPU with 2000 deg/s + */ +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS 4.359 +#define IMU_GYRO_P_SENS_NUM 4359 +#define IMU_GYRO_P_SENS_DEN 1000 +#define IMU_GYRO_Q_SENS 4.359 +#define IMU_GYRO_Q_SENS_NUM 4359 +#define IMU_GYRO_Q_SENS_DEN 1000 +#define IMU_GYRO_R_SENS 4.359 +#define IMU_GYRO_R_SENS_NUM 4359 +#define IMU_GYRO_R_SENS_DEN 1000 +#endif +#if !defined IMU_GYRO_P_NEUTRAL & !defined IMU_GYRO_Q_NEUTRAL & !defined IMU_GYRO_R_NEUTRAL +#define IMU_GYRO_P_NEUTRAL 0 +#define IMU_GYRO_Q_NEUTRAL 0 +#define IMU_GYRO_R_NEUTRAL 0 +#endif + +/** default accel sensitivy from the datasheet + * 512 LSB/g + */ +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS 19.5 +#define IMU_ACCEL_X_SENS_NUM 195 +#define IMU_ACCEL_X_SENS_DEN 10 +#define IMU_ACCEL_Y_SENS 19.5 +#define IMU_ACCEL_Y_SENS_NUM 195 +#define IMU_ACCEL_Y_SENS_DEN 10 +#define IMU_ACCEL_Z_SENS 19.5 +#define IMU_ACCEL_Z_SENS_NUM 195 +#define IMU_ACCEL_Z_SENS_DEN 10 +#endif + +#if !defined IMU_ACCEL_X_NEUTRAL & !defined IMU_ACCEL_Y_NEUTRAL & !defined IMU_ACCEL_Z_NEUTRAL +#define IMU_ACCEL_X_NEUTRAL 2048 +#define IMU_ACCEL_Y_NEUTRAL 2048 +#define IMU_ACCEL_Z_NEUTRAL 2048 +#endif + +#if !defined IMU_MAG_X_SENS & !defined IMU_MAG_Y_SENS & !defined IMU_MAG_Z_SENS +#define IMU_MAG_X_SENS 16.0 +#define IMU_MAG_X_SENS_NUM 16 +#define IMU_MAG_X_SENS_DEN 1 +#define IMU_MAG_Y_SENS 16.0 +#define IMU_MAG_Y_SENS_NUM 16 +#define IMU_MAG_Y_SENS_DEN 1 +#define IMU_MAG_Z_SENS 16.0 +#define IMU_MAG_Z_SENS_NUM 16 +#define IMU_MAG_Z_SENS_DEN 1 +#endif + +#if !defined IMU_MAG_X_NEUTRAL & !defined IMU_MAG_Y_NEUTRAL & !defined IMU_MAG_Z_NEUTRAL +#define IMU_MAG_X_NEUTRAL 0 +#define IMU_MAG_Y_NEUTRAL 0 +#define IMU_MAG_Z_NEUTRAL 0 +#endif + + + void navdata_event(void); static inline void imu_ardrone2_event ( void (* _gyro_handler)(void), void (* _accel_handler)(void), void (* _mag_handler)(void)) From 20897342749319edd8c137f80fa3e1afc803c8ca Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 19:38:32 +0200 Subject: [PATCH 141/309] [lpc21] fix typo in i2c --- sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c index 0f405325d3..c5379f91ea 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c @@ -337,7 +337,7 @@ bool_t i2c_submit(struct i2c_periph* p, struct i2c_transaction* t) { if (idx >= I2C_TRANSACTION_QUEUE_LEN) idx = 0; if (idx == p->trans_extract_idx) { /* queue full */ - periph->errors->queue_full_cnt++; + p->errors->queue_full_cnt++; t->status = I2CTransFailed; return FALSE; } From b2504c7bcd9ebab2f376457edbf8d6ff9dd6fb8c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 21:52:41 +0200 Subject: [PATCH 142/309] [tests] fix SEND_I2C_ERRORS for some test progs --- sw/airborne/lisa/test/lisa_test_hmc5843.c | 2 ++ sw/airborne/lisa/test/lisa_test_itg3200.c | 2 ++ sw/airborne/lisa/test/test_board.c | 4 ++++ sw/airborne/lisa/test/test_mc_asctec_v1_simple.c | 2 ++ sw/airborne/lisa/test_baro_i2c.c | 2 ++ sw/airborne/test/subsystems/test_ahrs.c | 2 ++ sw/airborne/test/subsystems/test_imu.c | 2 ++ 7 files changed, 16 insertions(+) diff --git a/sw/airborne/lisa/test/lisa_test_hmc5843.c b/sw/airborne/lisa/test/lisa_test_hmc5843.c index 5f64d89539..bb76fe423f 100644 --- a/sw/airborne/lisa/test/lisa_test_hmc5843.c +++ b/sw/airborne/lisa/test/lisa_test_hmc5843.c @@ -85,6 +85,7 @@ static inline void main_periodic_task( void ) { }); RunOnceEvery(256, { + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; @@ -96,6 +97,7 @@ static inline void main_periodic_task( void ) { uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; const uint8_t _bus2 = 2; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c2_queue_full_cnt, &i2c2_ack_fail_cnt, &i2c2_miss_start_stop_cnt, &i2c2_arb_lost_cnt, diff --git a/sw/airborne/lisa/test/lisa_test_itg3200.c b/sw/airborne/lisa/test/lisa_test_itg3200.c index 81ba2f3f4d..ae7b8583f2 100644 --- a/sw/airborne/lisa/test/lisa_test_itg3200.c +++ b/sw/airborne/lisa/test/lisa_test_itg3200.c @@ -81,6 +81,7 @@ static inline void main_periodic_task( void ) { LED_PERIODIC(); }); RunOnceEvery(256, { + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; @@ -92,6 +93,7 @@ static inline void main_periodic_task( void ) { uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; const uint8_t _bus2 = 2; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c2_queue_full_cnt, &i2c2_ack_fail_cnt, &i2c2_miss_start_stop_cnt, &i2c2_arb_lost_cnt, diff --git a/sw/airborne/lisa/test/test_board.c b/sw/airborne/lisa/test/test_board.c index a105d61306..432d145d74 100644 --- a/sw/airborne/lisa/test/test_board.c +++ b/sw/airborne/lisa/test/test_board.c @@ -155,6 +155,7 @@ static void test_baro_start(void) {all_led_green();} static void test_baro_periodic(void) { RunOnceEvery(2, {baro_periodic();}); RunOnceEvery(100,{ + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; @@ -166,6 +167,7 @@ static void test_baro_periodic(void) { uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; const uint8_t _bus2 = 2; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c2_queue_full_cnt, &i2c2_ack_fail_cnt, &i2c2_miss_start_stop_cnt, &i2c2_arb_lost_cnt, @@ -200,6 +202,7 @@ static void test_bldc_periodic(void) { i2c1_transmit(0x58, 1, NULL); RunOnceEvery(100,{ + uint16_t i2c1_queue_full_cnt = i2c1.errors->queue_full_cnt; uint16_t i2c1_ack_fail_cnt = i2c1.errors->ack_fail_cnt; uint16_t i2c1_miss_start_stop_cnt = i2c1.errors->miss_start_stop_cnt; uint16_t i2c1_arb_lost_cnt = i2c1.errors->arb_lost_cnt; @@ -211,6 +214,7 @@ static void test_bldc_periodic(void) { uint32_t i2c1_last_unexpected_event = i2c1.errors->last_unexpected_event; const uint8_t _bus1 = 1; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c1_queue_full_cnt, &i2c1_ack_fail_cnt, &i2c1_miss_start_stop_cnt, &i2c1_arb_lost_cnt, diff --git a/sw/airborne/lisa/test/test_mc_asctec_v1_simple.c b/sw/airborne/lisa/test/test_mc_asctec_v1_simple.c index 0579315927..519656f62e 100644 --- a/sw/airborne/lisa/test/test_mc_asctec_v1_simple.c +++ b/sw/airborne/lisa/test/test_mc_asctec_v1_simple.c @@ -62,6 +62,7 @@ static inline void main_periodic_task( void ) { RunOnceEvery(256, {DOWNLINK_SEND_ALIVE(DefaultChannel, DefaultDevice, 16, MD5SUM);}); RunOnceEvery(256, { + uint16_t i2c1_queue_full_cnt = i2c1.errors->queue_full_cnt; uint16_t i2c1_ack_fail_cnt = i2c1.errors->ack_fail_cnt; uint16_t i2c1_miss_start_stop_cnt = i2c1.errors->miss_start_stop_cnt; uint16_t i2c1_arb_lost_cnt = i2c1.errors->arb_lost_cnt; @@ -73,6 +74,7 @@ static inline void main_periodic_task( void ) { uint32_t i2c1_last_unexpected_event = i2c1.errors->last_unexpected_event; const uint8_t _bus1 = 1; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c1_queue_full_cnt, &i2c1_ack_fail_cnt, &i2c1_miss_start_stop_cnt, &i2c1_arb_lost_cnt, diff --git a/sw/airborne/lisa/test_baro_i2c.c b/sw/airborne/lisa/test_baro_i2c.c index 1a63ad6274..250bf89c33 100644 --- a/sw/airborne/lisa/test_baro_i2c.c +++ b/sw/airborne/lisa/test_baro_i2c.c @@ -78,6 +78,7 @@ static inline void main_periodic_task( void ) { RunOnceEvery(256, {DOWNLINK_SEND_ALIVE(DefaultChannel, DefaultDevice, 16, MD5SUM);}); RunOnceEvery(256, { + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; @@ -89,6 +90,7 @@ static inline void main_periodic_task( void ) { uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; const uint8_t _bus2 = 2; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c2_queue_full_cnt, &i2c2_ack_fail_cnt, &i2c2_miss_start_stop_cnt, &i2c2_arb_lost_cnt, diff --git a/sw/airborne/test/subsystems/test_ahrs.c b/sw/airborne/test/subsystems/test_ahrs.c index 3871888bf6..701fc0bda5 100644 --- a/sw/airborne/test/subsystems/test_ahrs.c +++ b/sw/airborne/test/subsystems/test_ahrs.c @@ -159,6 +159,7 @@ static inline void main_report(void) { }, { #ifdef USE_I2C2 + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; @@ -170,6 +171,7 @@ static inline void main_report(void) { uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; const uint8_t _bus2 = 2; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c2_queue_full_cnt, &i2c2_ack_fail_cnt, &i2c2_miss_start_stop_cnt, &i2c2_arb_lost_cnt, diff --git a/sw/airborne/test/subsystems/test_imu.c b/sw/airborne/test/subsystems/test_imu.c index 332cbba003..e3bb239df2 100644 --- a/sw/airborne/test/subsystems/test_imu.c +++ b/sw/airborne/test/subsystems/test_imu.c @@ -80,6 +80,7 @@ static inline void main_periodic_task( void ) { }); #ifdef USE_I2C2 RunOnceEvery(111, { + uint16_t i2c2_queue_full_cnt = i2c2.errors->queue_full_cnt; uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; @@ -91,6 +92,7 @@ static inline void main_periodic_task( void ) { uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; const uint8_t _bus2 = 2; DOWNLINK_SEND_I2C_ERRORS(DefaultChannel, DefaultDevice, + &i2c2_queue_full_cnt, &i2c2_ack_fail_cnt, &i2c2_miss_start_stop_cnt, &i2c2_arb_lost_cnt, From c3cb277d51e9f08b68014573ed4709f5200964cf Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 22:01:07 +0200 Subject: [PATCH 143/309] [peripherals] data invalid if d1/d1 is zero, back to idle --- sw/airborne/peripherals/ms5611_i2c.c | 28 ++++++++++++++++++++-------- sw/airborne/peripherals/ms5611_spi.c | 28 ++++++++++++++++++++-------- 2 files changed, 40 insertions(+), 16 deletions(-) diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c index c65cb19ddd..1ec14b4611 100644 --- a/sw/airborne/peripherals/ms5611_i2c.c +++ b/sw/airborne/peripherals/ms5611_i2c.c @@ -129,10 +129,16 @@ void ms5611_i2c_event(struct Ms5611_I2c *ms) { ms->data.d1 = (ms->i2c_trans.buf[0] << 16) | (ms->i2c_trans.buf[1] << 8) | ms->i2c_trans.buf[2]; - /* start D2 conversion */ - ms->i2c_trans.buf[0] = MS5611_START_CONV_D2; - i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); - ms->status = MS5611_STATUS_CONV_D2; + if (ms->data.d1 == 0) { + /* if value is zero, it was read to soon and is invalid, back to idle */ + ms->status = MS5611_STATUS_IDLE; + } + else { + /* start D2 conversion */ + ms->i2c_trans.buf[0] = MS5611_START_CONV_D2; + i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); + ms->status = MS5611_STATUS_CONV_D2; + } break; case MS5611_STATUS_ADC_D2: @@ -140,10 +146,16 @@ void ms5611_i2c_event(struct Ms5611_I2c *ms) { ms->data.d2 = (ms->i2c_trans.buf[0] << 16) | (ms->i2c_trans.buf[1] << 8) | ms->i2c_trans.buf[2]; - /* calculate temp and pressure from measurements */ - ms5611_calc(&(ms->data)); - ms->status = MS5611_STATUS_IDLE; - ms->data_available = TRUE; + if (ms->data.d2 == 0) { + /* if value is zero, it was read to soon and is invalid, back to idle */ + ms->status = MS5611_STATUS_IDLE; + } + else { + /* calculate temp and pressure from measurements */ + ms5611_calc(&(ms->data)); + ms->status = MS5611_STATUS_IDLE; + ms->data_available = TRUE; + } break; default: diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c index 5b7e01ab78..d8e9293185 100644 --- a/sw/airborne/peripherals/ms5611_spi.c +++ b/sw/airborne/peripherals/ms5611_spi.c @@ -143,10 +143,16 @@ void ms5611_spi_event(struct Ms5611_Spi *ms) { ms->data.d1 = (ms->rx_buf[1] << 16) | (ms->rx_buf[2] << 8) | ms->rx_buf[3]; - /* start D2 conversion */ - ms->tx_buf[0] = MS5611_START_CONV_D2; - spi_submit(ms->spi_p, &(ms->spi_trans)); - ms->status = MS5611_STATUS_CONV_D2; + if (ms->data.d1 == 0) { + /* if value is zero, it was read to soon and is invalid, back to idle */ + ms->status = MS5611_STATUS_IDLE; + } + else { + /* start D2 conversion */ + ms->tx_buf[0] = MS5611_START_CONV_D2; + spi_submit(ms->spi_p, &(ms->spi_trans)); + ms->status = MS5611_STATUS_CONV_D2; + } break; case MS5611_STATUS_ADC_D2: @@ -154,10 +160,16 @@ void ms5611_spi_event(struct Ms5611_Spi *ms) { ms->data.d2 = (ms->rx_buf[1] << 16) | (ms->rx_buf[2] << 8) | ms->rx_buf[3]; - /* calculate temp and pressure from measurements */ - ms5611_calc(&(ms->data)); - ms->status = MS5611_STATUS_IDLE; - ms->data_available = TRUE; + if (ms->data.d2 == 0) { + /* if value is zero, it was read to soon and is invalid, back to idle */ + ms->status = MS5611_STATUS_IDLE; + } + else { + /* calculate temp and pressure from measurements */ + ms5611_calc(&(ms->data)); + ms->status = MS5611_STATUS_IDLE; + ms->data_available = TRUE; + } break; default: From 446c7f1f2efc3c97fd7817de10fefddc27abda90 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 27 Aug 2013 23:09:40 +0200 Subject: [PATCH 144/309] [nps] define some default MAG_x_SENS values --- sw/airborne/subsystems/imu/imu_nps.h | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/sw/airborne/subsystems/imu/imu_nps.h b/sw/airborne/subsystems/imu/imu_nps.h index 2b7facdc0f..6c1f647da9 100644 --- a/sw/airborne/subsystems/imu/imu_nps.h +++ b/sw/airborne/subsystems/imu/imu_nps.h @@ -56,6 +56,19 @@ #endif +#if !defined IMU_MAG_X_SENS & !defined IMU_MAG_Y_SENS & !defined IMU_MAG_Z_SENS +#define IMU_MAG_X_SENS 3.5 +#define IMU_MAG_X_SENS_NUM 7 +#define IMU_MAG_X_SENS_DEN 2 +#define IMU_MAG_Y_SENS 3.5 +#define IMU_MAG_Y_SENS_NUM 7 +#define IMU_MAG_Y_SENS_DEN 2 +#define IMU_MAG_Z_SENS 3.5 +#define IMU_MAG_Z_SENS_NUM 7 +#define IMU_MAG_Z_SENS_DEN 2 +#endif + + struct ImuNps { uint8_t mag_available; uint8_t accel_available; From d9eb74ce070666b14e0fa04fe5469900950bd259 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Wed, 28 Aug 2013 13:21:41 +0200 Subject: [PATCH 145/309] [sim] fix simulation using baro_amsys --- sw/airborne/modules/sensors/baro_amsys.c | 1 + sw/airborne/modules/sensors/baro_board_module.h | 6 ++++++ 2 files changed, 7 insertions(+) diff --git a/sw/airborne/modules/sensors/baro_amsys.c b/sw/airborne/modules/sensors/baro_amsys.c index 9a6e1c0e7c..faa014ff94 100644 --- a/sw/airborne/modules/sensors/baro_amsys.c +++ b/sw/airborne/modules/sensors/baro_amsys.c @@ -31,6 +31,7 @@ #ifdef SITL #include "subsystems/gps.h" +#include "subsystems/navigation/common_nav.h" #endif //Messages diff --git a/sw/airborne/modules/sensors/baro_board_module.h b/sw/airborne/modules/sensors/baro_board_module.h index 57ae9dd4af..bc5f48d23b 100644 --- a/sw/airborne/modules/sensors/baro_board_module.h +++ b/sw/airborne/modules/sensors/baro_board_module.h @@ -54,7 +54,13 @@ /** BaroEvent macro. * Need to be maped to one the external baro running has a module + * + * Undef if necessary (already defined in a baro_board.h file) */ +#ifdef BaroEvent +#undef BaroEvent +#endif + #define BaroEvent(_b_abs_handler, _b_diff_handler) { \ BARO_ABS_EVENT(baro.absolute, _b_abs_handler); \ BARO_DIFF_EVENT(baro.differential, _b_diff_handler); \ From 7344099703a0c423168bb7468dd61c60b76f88e9 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 14:06:16 +0200 Subject: [PATCH 146/309] [rotorcraft] INS_PROPAGATE_FREQUENCY for vff - defaults to 1/PERIODIC_FREQUENCY - should be the frequency of new accel measurements --- conf/firmwares/subsystems/rotorcraft/ins.makefile | 2 +- .../subsystems/rotorcraft/ins_extended.makefile | 2 +- sw/airborne/subsystems/ins/vf_extended_float.c | 9 +++++++++ sw/airborne/subsystems/ins/vf_float.c | 8 ++++++++ 4 files changed, 19 insertions(+), 2 deletions(-) diff --git a/conf/firmwares/subsystems/rotorcraft/ins.makefile b/conf/firmwares/subsystems/rotorcraft/ins.makefile index c23c0333ca..fd4878813c 100644 --- a/conf/firmwares/subsystems/rotorcraft/ins.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ins.makefile @@ -8,5 +8,5 @@ $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/ins_int.c # vertical filter float version $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/vf_float.c -$(TARGET).CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./$(PERIODIC_FREQUENCY).)' +$(TARGET).CFLAGS += -DUSE_VFF diff --git a/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile b/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile index e4ecf1b674..6ce7f94af9 100644 --- a/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ins_extended.makefile @@ -8,5 +8,5 @@ $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/ins_int_extended.c # vertical filter float version $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/vf_extended_float.c -$(TARGET).CFLAGS += -DUSE_VFF_EXTENDED -DDT_VFILTER='(1./$(PERIODIC_FREQUENCY).)' +$(TARGET).CFLAGS += -DUSE_VFF_EXTENDED diff --git a/sw/airborne/subsystems/ins/vf_extended_float.c b/sw/airborne/subsystems/ins/vf_extended_float.c index 48d96f0b09..6e34cecfd7 100644 --- a/sw/airborne/subsystems/ins/vf_extended_float.c +++ b/sw/airborne/subsystems/ins/vf_extended_float.c @@ -30,6 +30,7 @@ */ #include "subsystems/ins/vf_extended_float.h" +#include "generated/airframe.h" #define DEBUG_VFF_EXTENDED 1 @@ -39,6 +40,14 @@ #include "subsystems/datalink/downlink.h" #endif +#ifndef INS_PROPAGATE_FREQUENCY +#define INS_PROPAGATE_FREQUENCY PERIODIC_FREQUENCY +#endif +PRINT_CONFIG_VAR(INS_PROPAGATE_FREQUENCY) + +#define DT_VFILTER (1./(INS_PROPAGATE_FREQUENCY)) + + /* X = [ z zdot accel_bias baro_offset ] diff --git a/sw/airborne/subsystems/ins/vf_float.c b/sw/airborne/subsystems/ins/vf_float.c index 54bf0c612b..7a2d023ac4 100644 --- a/sw/airborne/subsystems/ins/vf_float.c +++ b/sw/airborne/subsystems/ins/vf_float.c @@ -27,6 +27,14 @@ */ #include "subsystems/ins/vf_float.h" +#include "generated/airframe.h" + +#ifndef INS_PROPAGATE_FREQUENCY +#define INS_PROPAGATE_FREQUENCY PERIODIC_FREQUENCY +#endif +PRINT_CONFIG_VAR(INS_PROPAGATE_FREQUENCY) + +#define DT_VFILTER (1./(INS_PROPAGATE_FREQUENCY)) /* From c959335b2c03c9a0f4007b44177c3ec787f76bc7 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 15:09:51 +0200 Subject: [PATCH 147/309] [modules] ms5611 read function to request new measurement - run periodic_check at higher freq - the DT between two measurements should now be automatically correctly set according to the freq of the baro_ms5611_read function --- conf/modules/baro_ms5611_i2c.xml | 3 +- conf/modules/baro_ms5611_spi.xml | 3 +- sw/airborne/modules/sensors/baro_ms5611_i2c.c | 33 ++++++++++--------- sw/airborne/modules/sensors/baro_ms5611_i2c.h | 7 ++-- sw/airborne/modules/sensors/baro_ms5611_spi.c | 33 ++++++++++--------- sw/airborne/modules/sensors/baro_ms5611_spi.h | 7 ++-- sw/airborne/peripherals/ms5611_i2c.h | 12 +++++-- sw/airborne/peripherals/ms5611_spi.h | 12 +++++-- 8 files changed, 68 insertions(+), 42 deletions(-) diff --git a/conf/modules/baro_ms5611_i2c.xml b/conf/modules/baro_ms5611_i2c.xml index c7ea554422..027cd4061c 100644 --- a/conf/modules/baro_ms5611_i2c.xml +++ b/conf/modules/baro_ms5611_i2c.xml @@ -13,7 +13,8 @@ - + + diff --git a/conf/modules/baro_ms5611_spi.xml b/conf/modules/baro_ms5611_spi.xml index 335ac840fd..2ec153e554 100644 --- a/conf/modules/baro_ms5611_spi.xml +++ b/conf/modules/baro_ms5611_spi.xml @@ -14,7 +14,8 @@ - + + diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.c b/sw/airborne/modules/sensors/baro_ms5611_i2c.c index c87794f160..d3b3a3d88c 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.c @@ -68,26 +68,29 @@ void baro_ms5611_init(void) { baro_ms5611_sigma2 = BARO_MS5611_SIGMA2; } -void baro_ms5611_periodic( void ) { - if (sys_time.nb_sec > 1) { +void baro_ms5611_periodic_check( void ) { - /* call the convenience periodic that initializes the sensor and starts reading*/ - ms5611_i2c_periodic(&baro_ms5611); + ms5611_i2c_periodic_check(&baro_ms5611); - if (baro_ms5611.initialized) { - RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &baro_ms5611.data.c[0], - &baro_ms5611.data.c[1], - &baro_ms5611.data.c[2], - &baro_ms5611.data.c[3], - &baro_ms5611.data.c[4], - &baro_ms5611.data.c[5], - &baro_ms5611.data.c[6], - &baro_ms5611.data.c[7])); - } + if (baro_ms5611.initialized) { + RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7])); } } +/// trigger new measurement or initialize if needed +void baro_ms5611_read(void) { + if (sys_time.nb_sec > 1) { + ms5611_i2c_read(&baro_ms5611); + } +} void baro_ms5611_event( void ) { diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h index 0e16161a21..ce4747aca9 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.h +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.h @@ -4,8 +4,8 @@ #include "std.h" #include "peripherals/ms5611_i2c.h" - -#define BARO_MS5611_DT 0.05 +/// new measurement with every baro_ms5611_read() call +#define BARO_MS5611_DT BARO_MS5611_READ_PERIOD #define BARO_MS5611_R 20 #define BARO_MS5611_SIGMA2 1 extern float baro_ms5611_r; @@ -18,7 +18,8 @@ extern bool_t baro_ms5611_enabled; extern struct Ms5611_I2c baro_ms5611; extern void baro_ms5611_init(void); -extern void baro_ms5611_periodic(void); +extern void baro_ms5611_read(void); +extern void baro_ms5611_periodic_check(void); extern void baro_ms5611_event(void); #define BaroMs5611UpdatePressure(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; baro_ms5611.data_available = FALSE; } } diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.c b/sw/airborne/modules/sensors/baro_ms5611_spi.c index 0b0316b151..c91d713153 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.c +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.c @@ -68,26 +68,29 @@ void baro_ms5611_init(void) { baro_ms5611_sigma2 = BARO_MS5611_SIGMA2; } -void baro_ms5611_periodic( void ) { - if (sys_time.nb_sec > 1) { +void baro_ms5611_periodic_check( void ) { - /* call the convenience periodic that initializes the sensor and starts reading*/ - ms5611_spi_periodic(&baro_ms5611); + ms5611_spi_periodic_check(&baro_ms5611); - if (baro_ms5611.initialized) { - RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &baro_ms5611.data.c[0], - &baro_ms5611.data.c[1], - &baro_ms5611.data.c[2], - &baro_ms5611.data.c[3], - &baro_ms5611.data.c[4], - &baro_ms5611.data.c[5], - &baro_ms5611.data.c[6], - &baro_ms5611.data.c[7])); - } + if (baro_ms5611.initialized) { + RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7])); } } +/// trigger new measurement or initialize if needed +void baro_ms5611_read(void) { + if (sys_time.nb_sec > 1) { + ms5611_spi_read(&baro_ms5611); + } +} void baro_ms5611_event( void ) { diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.h b/sw/airborne/modules/sensors/baro_ms5611_spi.h index e752e7a250..7bab9d92e8 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.h +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.h @@ -32,8 +32,8 @@ #include "std.h" #include "peripherals/ms5611_spi.h" - -#define BARO_MS5611_DT 0.05 +/// new measurement with every baro_ms5611_read() call +#define BARO_MS5611_DT BARO_MS5611_READ_PERIOD #define BARO_MS5611_R 20 #define BARO_MS5611_SIGMA2 1 extern float baro_ms5611_r; @@ -46,7 +46,8 @@ extern bool_t baro_ms5611_enabled; extern struct Ms5611_Spi baro_ms5611; extern void baro_ms5611_init(void); -extern void baro_ms5611_periodic(void); +extern void baro_ms5611_read(void); +extern void baro_ms5611_periodic_check(void); extern void baro_ms5611_event(void); #define BaroMs5611UpdatePressure(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; baro_ms5611.data_available = FALSE; } } diff --git a/sw/airborne/peripherals/ms5611_i2c.h b/sw/airborne/peripherals/ms5611_i2c.h index 614e3c605b..149312ff36 100644 --- a/sw/airborne/peripherals/ms5611_i2c.h +++ b/sw/airborne/peripherals/ms5611_i2c.h @@ -50,12 +50,20 @@ extern void ms5611_i2c_start_conversion(struct Ms5611_I2c* ms); extern void ms5611_i2c_periodic_check(struct Ms5611_I2c* ms); extern void ms5611_i2c_event(struct Ms5611_I2c* ms); -/// convenience function: trigger read or start configuration if not already initialized -static inline void ms5611_i2c_periodic(struct Ms5611_I2c* ms) { +/** convenience function to trigger new measurement. + * (or start configuration if not already initialized) + * Still need to regularly run ms5611_i2c_periodic_check to complete the measurement. + */ +static inline void ms5611_i2c_read(struct Ms5611_I2c* ms) { if (ms->initialized) ms5611_i2c_start_conversion(ms); else ms5611_i2c_start_configure(ms); +} + +/// convenience function +static inline void ms5611_i2c_periodic(struct Ms5611_I2c* ms) { + ms5611_i2c_read(ms); ms5611_i2c_periodic_check(ms); } diff --git a/sw/airborne/peripherals/ms5611_spi.h b/sw/airborne/peripherals/ms5611_spi.h index 8e0b42c1b2..59f8f6e8e8 100644 --- a/sw/airborne/peripherals/ms5611_spi.h +++ b/sw/airborne/peripherals/ms5611_spi.h @@ -52,12 +52,20 @@ extern void ms5611_spi_start_conversion(struct Ms5611_Spi* ms); extern void ms5611_spi_periodic_check(struct Ms5611_Spi* ms); extern void ms5611_spi_event(struct Ms5611_Spi* ms); -/// convenience function: trigger read or start configuration if not already initialized -static inline void ms5611_spi_periodic(struct Ms5611_Spi* ms) { +/** convenience function to trigger new measurement. + * (or start configuration if not already initialized) + * Still need to regularly run ms5611_spi_periodic_check to complete the measurement. + */ +static inline void ms5611_spi_read(struct Ms5611_Spi* ms) { if (ms->initialized) ms5611_spi_start_conversion(ms); else ms5611_spi_start_configure(ms); +} + +/// convenience function +static inline void ms5611_spi_periodic(struct Ms5611_Spi* ms) { + ms5611_spi_read(ms); ms5611_spi_periodic_check(ms); } From b8ec860edc4f7b46bcbb2816f681fe1332f7fbb2 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 28 Aug 2013 14:28:27 +0200 Subject: [PATCH 148/309] [ardrone] 200Hz Baro messages are actually 100Hz temp and then pressure. One should not use the wrong temp with the wrong pressure either. A change tracker is used. --- sw/airborne/boards/ardrone/navdata.c | 57 +++++++++++++++++++++++++++- 1 file changed, 56 insertions(+), 1 deletion(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 831a492367..683426faba 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -172,6 +172,60 @@ void navdata_read() } } +void baro_update_logic(void); +void baro_update_logic(void) +{ + static int32_t lastpressval = 0; + static uint16_t lasttempval = 0; + static uint8_t temp_or_press_was_updated_last = 0; // 0 = press, so we now wait for temp, 1 = temp so we now wait for press + + static int sync_errors; + + if (temp_or_press_was_updated_last == 0) // Last update was press so we are now waiting for temp + { + // temp was updated + temp_or_press_was_updated_last = 1; + + // This means that press must remain constant + if (lastpressval != 0) + { + // If pressure was updated: this is a sync error + if (lastpressval != navdata->pressure) + { + // wait for temp again + temp_or_press_was_updated_last = 0; + sync_errors++; + navdata_baro_available = 1; + } + } + } + else + { + // press was updated + temp_or_press_was_updated_last = 0; + + // This means that temp must remain constant + if (lasttempval != 0) + { + // If temp was updated: this is a sync error + if (lasttempval != navdata->temperature_pressure) + { + // wait for press again + temp_or_press_was_updated_last = 1; + sync_errors++; + } + } + + navdata_baro_available = 1; + } + + lastpressval = navdata->pressure; + lasttempval = navdata->temperature_pressure; + + // debug + // navdata->temperature_pressure = sync_errors; +} + void navdata_update() { navdata_read(); @@ -198,8 +252,9 @@ void navdata_update() p[0] = p[1]; p[1] = tmp; + baro_update_logic(); + navdata_imu_available = 1; - navdata_baro_available = 1; port->packetsRead++; // printf("CCRC=%d, GCRC=%d, error=%d\n", crc, navdata->chksum, abs(crc-navdata->chksum)); From 5ebb391b03012181dae5b7b348c67333c151419b Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 28 Aug 2013 15:31:59 +0200 Subject: [PATCH 149/309] [ardrone] INS 200Hz progation, extended ins with baro alt0 estimation based on GPS --- conf/airframes/ardrone2_raw.xml | 3 ++- sw/airborne/boards/ardrone/baro_board.c | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 1a4f10df16..66512c4045 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -8,6 +8,7 @@ + @@ -25,7 +26,7 @@ - + diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index 4ab4845087..ce0a1591a6 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -58,7 +58,7 @@ static inline int32_t baro_apply_calibration(int32_t raw) x2 = (-7357L * p) >> 16; int32_t press = p + ((x1 + x2 + 3791L) >> 4); // Zero at sealevel - return press - 101325; + return press; } static inline int32_t baro_apply_calibration_temp(int32_t tmp_raw) From f7d26c37a0390b7f9924ce92ecd8795799d9b76e Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 15:51:57 +0200 Subject: [PATCH 150/309] [boards] imu_krooz: only set flag in isr, read data in event This should prevent new i2c transactions beeing inserted from the ISR and hence preventing other transactions from beeing properly added to the queue. i2c_submit can currently not be called from ISRs, since the transaction queue is checked before interrupts are disabled. --- .../arch/stm32/subsystems/imu/imu_krooz_sd_arch.c | 4 ++-- sw/airborne/boards/krooz/imu_krooz.c | 13 +++++++++++++ sw/airborne/boards/krooz/imu_krooz.h | 2 ++ 3 files changed, 17 insertions(+), 2 deletions(-) diff --git a/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c b/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c index 64ef448548..a13032bf7c 100644 --- a/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c +++ b/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c @@ -28,10 +28,10 @@ void exti9_5_isr(void) { /* clear EXTI */ if(EXTI_PR & EXTI6) { exti_reset_request(EXTI6); - hmc58xx_read(&imu_krooz.hmc); + imu_krooz.hmc_eoc = TRUE; } if(EXTI_PR & EXTI5) { exti_reset_request(EXTI5); - mpu60x0_i2c_read(&imu_krooz.mpu); + imu_krooz.mpu_eoc = TRUE; } } diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index fe14fbb448..e120cbbea3 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -103,6 +103,9 @@ void imu_impl_init( void ) imu_krooz.acc_valid = FALSE; imu_krooz.mag_valid = FALSE; + imu_krooz.hmc_eoc = FALSE; + imu_krooz.mpu_eoc = FALSE; + imu_krooz_sd_arch_init(); } @@ -155,6 +158,11 @@ void imu_krooz_downlink_raw( void ) void imu_krooz_event( void ) { + if (imu_krooz.mpu_eoc) { + mpu60x0_i2c_read(&imu_krooz.mpu); + imu_krooz.mpu_eoc = FALSE; + } + // If the MPU6050 I2C transaction has succeeded: convert the data mpu60x0_i2c_event(&imu_krooz.mpu); if (imu_krooz.mpu.data_available) { @@ -164,6 +172,11 @@ void imu_krooz_event( void ) imu_krooz.mpu.data_available = FALSE; } + if (imu_krooz.hmc_eoc) { + hmc58xx_read(&imu_krooz.hmc); + imu_krooz.hmc_eoc = FALSE; + } + // If the HMC5883 I2C transaction has succeeded: convert the data hmc58xx_event(&imu_krooz.hmc); if (imu_krooz.hmc.data_available) { diff --git a/sw/airborne/boards/krooz/imu_krooz.h b/sw/airborne/boards/krooz/imu_krooz.h index 543306d225..565e48a838 100644 --- a/sw/airborne/boards/krooz/imu_krooz.h +++ b/sw/airborne/boards/krooz/imu_krooz.h @@ -111,6 +111,8 @@ struct ImuKrooz { volatile bool_t gyr_valid; volatile bool_t acc_valid; volatile bool_t mag_valid; + volatile bool_t mpu_eoc; + volatile bool_t hmc_eoc; struct Mpu60x0_I2c mpu; struct Hmc58xx hmc; struct Int32Rates rates_sum; From 029264bdc2d7e22f44479e9fef6177d0e54091b9 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 28 Aug 2013 18:05:36 +0200 Subject: [PATCH 151/309] [Ardrone] Full Auto2 Flight in RAW Mode --- conf/airframes/ardrone2_raw.xml | 256 ++++++++++++++++---------------- 1 file changed, 131 insertions(+), 125 deletions(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 66512c4045..0b6eb33d18 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -4,214 +4,220 @@ - + - - - - - - + + + + + + - - + + - + - - - - - - + + + + + + - - + + - - - - + + + + - - - - + + + +
- - - - - + + + + + - - - - + + + +
- - - - - + + + + +
- - - + + + + + + + + + + + + + - - - - + - + - +
- - - + + +
- +
- - - - - - - + + + + + + + - - - + + + - - - + + + - - - + + +
- - - - - - + + + + + + - - - - + + + + - - - - + + + + - - - - + + + + - - - + + + - - - + + + - - - + + + - - - + + +
- - - - - - - - + + + + + + + + - + - +
- - - - + + + +
- - - + + +
- - - + + +
- - - - - + + + + +
From fb4990234de147fd956b8372dc9f603f790640c4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 17:53:53 +0200 Subject: [PATCH 152/309] [ins] include std.h for PRINT_CONFIG_VAR --- sw/airborne/subsystems/ins/vf_extended_float.c | 1 + sw/airborne/subsystems/ins/vf_float.c | 1 + 2 files changed, 2 insertions(+) diff --git a/sw/airborne/subsystems/ins/vf_extended_float.c b/sw/airborne/subsystems/ins/vf_extended_float.c index 6e34cecfd7..307c253f05 100644 --- a/sw/airborne/subsystems/ins/vf_extended_float.c +++ b/sw/airborne/subsystems/ins/vf_extended_float.c @@ -31,6 +31,7 @@ #include "subsystems/ins/vf_extended_float.h" #include "generated/airframe.h" +#include "std.h" #define DEBUG_VFF_EXTENDED 1 diff --git a/sw/airborne/subsystems/ins/vf_float.c b/sw/airborne/subsystems/ins/vf_float.c index 7a2d023ac4..9c8cf7300f 100644 --- a/sw/airborne/subsystems/ins/vf_float.c +++ b/sw/airborne/subsystems/ins/vf_float.c @@ -28,6 +28,7 @@ #include "subsystems/ins/vf_float.h" #include "generated/airframe.h" +#include "std.h" #ifndef INS_PROPAGATE_FREQUENCY #define INS_PROPAGATE_FREQUENCY PERIODIC_FREQUENCY From 8c7724cc3351db6e94f81efa6cd477352573a4ab Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 17:57:51 +0200 Subject: [PATCH 153/309] [conf][tests] fix test_baro sources --- conf/firmwares/lisa_test_progs.makefile | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/conf/firmwares/lisa_test_progs.makefile b/conf/firmwares/lisa_test_progs.makefile index bb8f1a53b8..5a18345359 100644 --- a/conf/firmwares/lisa_test_progs.makefile +++ b/conf/firmwares/lisa_test_progs.makefile @@ -203,16 +203,21 @@ LISA_M_BARO ?= BARO_BOARD_BMP085 ifeq ($(LISA_M_BARO), BARO_MS5611_SPI) include $(CFG_SHARED)/spi_master.makefile test_baro.CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3 - test_baro.srcs += $(SRC_BOARD)/baro_ms5611_spi.c + test_baro.srcs += peripherals/ms5611.c + test_baro.srcs += peripherals/ms5611_spi.c + test_baro.srcs += subsystems/sensors/baro_ms5611_spi.c test_baro.srcs += $(SRC_LISA)/test_baro_spi.c else ifeq ($(LISA_M_BARO), BARO_MS5611_I2C) test_baro.CFLAGS += -DUSE_I2C2 test_baro.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c - test_baro.srcs += $(SRC_BOARD)/baro_ms5611_i2c.c + test_baro.srcs += peripherals/ms5611.c + test_baro.srcs += peripherals/ms5611_i2c.c + test_baro.srcs += subsystems/sensors/baro_ms5611_i2c.c test_baro.srcs += $(SRC_LISA)/test_baro_i2c.c else ifeq ($(LISA_M_BARO), BARO_BOARD_BMP085) test_baro.CFLAGS += -DUSE_I2C2 test_baro.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c + test_baro.srcs += peripherals/bmp085.c test_baro.srcs += $(SRC_BOARD)/baro_board.c test_baro.srcs += $(SRC_LISA)/test_baro_i2c.c endif From 63dbb46d2ea72bc6cd92d805b785caca7408ba85 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 19:33:18 +0200 Subject: [PATCH 154/309] add make-release-tarball script --- make-release-tarball.sh | 255 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 255 insertions(+) create mode 100755 make-release-tarball.sh diff --git a/make-release-tarball.sh b/make-release-tarball.sh new file mode 100755 index 0000000000..5d50033178 --- /dev/null +++ b/make-release-tarball.sh @@ -0,0 +1,255 @@ +#!/bin/bash - +# +# File: git-archive-all.sh +# +# Description: A utility script that builds an archive file(s) of all +# git repositories and submodules in the current path. +# Useful for creating a single tarfile of a git super- +# project that contains other submodules. +# +# Examples: Use git-archive-all.sh to create archive distributions +# from git repositories. To use, simply do: +# +# cd $GIT_DIR; git-archive-all.sh +# +# where $GIT_DIR is the root of your git superproject. +# +# License: GPL3 +# +############################################################################### +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program; if not, write to the Free Software +# Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +# +############################################################################### + +# DEBUGGING +set -e +set -C # noclobber + +# TRAP SIGNALS +trap 'cleanup' QUIT EXIT + +# For security reasons, explicitly set the internal field separator +# to newline, space, tab +OLD_IFS=$IFS +IFS=' + ' + +function cleanup () { + rm -f $TMPFILE + rm -f $TOARCHIVE + IFS="$OLD_IFS" +} + +function usage () { + echo "Usage is as follows:" + echo + echo "$PROGRAM <--version>" + echo " Prints the program version number on a line by itself and exits." + echo + echo "$PROGRAM <--usage|--help|-?>" + echo " Prints this usage output and exits." + echo + echo "$PROGRAM [--format ] [--prefix ] [--verbose|-v] [--separate|-s] [output_file]" + echo " Creates an archive for the entire git superproject, and its submodules" + echo " using the passed parameters, described below." + echo + echo " If '--format' is specified, the archive is created with the named" + echo " git archiver backend. Obviously, this must be a backend that git archive" + echo " understands. The format defaults to 'tar' if not specified." + echo + echo " If '--prefix' is specified, the archive's superproject and all submodules" + echo " are created with the prefix named. The default is to not use one." + echo + echo " If '--separate' or '-s' is specified, individual archives will be created" + echo " for each of the superproject itself and its submodules. The default is to" + echo " concatenate individual archives into one larger archive." + echo + echo " If 'output_file' is specified, the resulting archive is created as the" + echo " file named. This parameter is essentially a path that must be writeable." + echo " When combined with '--separate' ('-s') this path must refer to a directory." + echo " Without this parameter or when combined with '--separate' the resulting" + echo " archive(s) are named with a dot-separated path of the archived directory and" + echo " a file extension equal to their format (e.g., 'superdir.submodule1dir.tar')." + echo + echo " If '--verbose' or '-v' is specified, progress will be printed." +} + +function version () { + echo "$PROGRAM version $VERSION" +} + +# Internal variables and initializations. +readonly PROGRAM=`basename "$0"` +readonly VERSION=0.2 + +OLD_PWD="`pwd`" +TMPDIR=${TMPDIR:-/tmp} +TMPFILE=`mktemp "$TMPDIR/$PROGRAM.XXXXXX"` # Create a place to store our work's progress +TOARCHIVE=`mktemp "$TMPDIR/$PROGRAM.toarchive.XXXXXX"` +OUT_FILE=$OLD_PWD # assume "this directory" without a name change by default +SEPARATE=0 +VERBOSE=0 + +FORMAT=tar +PREFIX= +TREEISH=HEAD + +# RETURN VALUES/EXIT STATUS CODES +readonly E_BAD_OPTION=254 +readonly E_UNKNOWN=255 + +# Process command-line arguments. +while test $# -gt 0; do + case $1 in + --format ) + shift + FORMAT="$1" + shift + ;; + + --prefix ) + shift + PREFIX="$1" + shift + ;; + + --separate | -s ) + shift + SEPARATE=1 + ;; + + --version ) + version + exit + ;; + + --verbose | -v ) + shift + VERBOSE=1 + ;; + + -? | --usage | --help ) + usage + exit + ;; + + -* ) + echo "Unrecognized option: $1" >&2 + usage + exit $E_BAD_OPTION + ;; + + * ) + break + ;; + esac +done + +if [ ! -z "$1" ]; then + OUT_FILE="$1" + shift +fi + +# Validate parameters; error early, error often. +if [ $SEPARATE -eq 1 -a ! -d $OUT_FILE ]; then + echo "When creating multiple archives, your destination must be a directory." + echo "If it's not, you risk being surprised when your files are overwritten." + exit +elif [ `git config -l | grep -q '^core\.bare=false'; echo $?` -ne 0 ]; then + echo "$PROGRAM must be run from a git working copy (i.e., not a bare repository)." + exit +fi + +# Create the superproject's git-archive +if [ $VERBOSE -eq 1 ]; then + echo -n "creating superproject archive..." +fi +git archive --format=$FORMAT --prefix="$PREFIX" $TREEISH > $TMPDIR/$(basename $(pwd)).$FORMAT +if [ $VERBOSE -eq 1 ]; then + echo "done" +fi +echo $TMPDIR/$(basename $(pwd)).$FORMAT >| $TMPFILE # clobber on purpose +superfile=`head -n 1 $TMPFILE` + +if [ $VERBOSE -eq 1 ]; then + echo -n "looking for subprojects..." +fi +# find all '.git' dirs, these show us the remaining to-be-archived dirs +# we only want directories that are below the current directory +find . -mindepth 2 -name '.git' -type d -print | sed -e 's/^\.\///' -e 's/\.git$//' >> $TOARCHIVE +# as of version 1.7.8, git places the submodule .git directories under the superprojects .git dir +# the submodules get a .git file that points to their .git dir. we need to find all of these too +find . -mindepth 2 -name '.git' -type f -print | xargs grep -l "gitdir" | sed -e 's/^\.\///' -e 's/\.git$//' >> $TOARCHIVE +if [ $VERBOSE -eq 1 ]; then + echo "done" + echo " found:" + cat $TOARCHIVE | while read arch + do + echo " $arch" + done +fi + +if [ $VERBOSE -eq 1 ]; then + echo -n "archiving submodules..." +fi +while read path; do + TREEISH=$(git submodule | grep "^ .*${path%/} " | cut -d ' ' -f 2) # git submodule does not list trailing slashes in $path + cd "$path" + git archive --format=$FORMAT --prefix="${PREFIX}$path" ${TREEISH:-HEAD} > "$TMPDIR"/"$(echo "$path" | sed -e 's/\//./g')"$FORMAT + if [ $FORMAT == 'zip' ]; then + # delete the empty directory entry; zipped submodules won't unzip if we don't do this + zip -d "$(tail -n 1 $TMPFILE)" "${PREFIX}${path%/}" >/dev/null # remove trailing '/' + fi + echo "$TMPDIR"/"$(echo "$path" | sed -e 's/\//./g')"$FORMAT >> $TMPFILE + cd "$OLD_PWD" +done < $TOARCHIVE +if [ $VERBOSE -eq 1 ]; then + echo "done" +fi + +if [ $VERBOSE -eq 1 ]; then + echo -n "concatenating archives into single archive..." +fi +# Concatenate archives into a super-archive. +if [ $SEPARATE -eq 0 ]; then + if [ $FORMAT == 'tar' ]; then + sed -e '1d' $TMPFILE | while read file; do + tar --concatenate -f "$superfile" "$file" && rm -f "$file" + done + elif [ $FORMAT == 'zip' ]; then + sed -e '1d' $TMPFILE | while read file; do + # zip incorrectly stores the full path, so cd and then grow + cd `dirname "$file"` + zip -g "$superfile" `basename "$file"` && rm -f "$file" + done + cd "$OLD_PWD" + fi + + echo "$superfile" >| $TMPFILE # clobber on purpose +fi +if [ $VERBOSE -eq 1 ]; then + echo "done" +fi + +if [ $VERBOSE -eq 1 ]; then + echo -n "moving archive to $OUT_FILE..." +fi +while read file; do + mv "$file" "$OUT_FILE" +done < $TMPFILE +if [ $VERBOSE -eq 1 ]; then + echo "done" +fi From 313c647d00a1945257cd02a676936bf825cfc80a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 19:39:26 +0200 Subject: [PATCH 155/309] [conf] imu in nps for krooz --- conf/firmwares/subsystems/shared/imu_krooz_sd.makefile | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile b/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile index 878dadfac1..baf9c6ae10 100644 --- a/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile +++ b/conf/firmwares/subsystems/shared/imu_krooz_sd.makefile @@ -25,3 +25,8 @@ ap.CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY) ap.CFLAGS += $(IMU_KROOZ_CFLAGS) ap.srcs += $(IMU_KROOZ_SRCS) + +# +# NPS simulator +# +include $(CFG_SHARED)/imu_nps.makefile From 9572ca5b39bba6ab4eb75da16d8ddd2c17d6754d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 19:39:51 +0200 Subject: [PATCH 156/309] [conf] remove unneeded DT_VFILTER --- .../subsystems/lisa_passthrough/booz_stabilization_int.makefile | 2 +- conf/firmwares/subsystems/rotorcraft/ins_hff.makefile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/conf/firmwares/subsystems/lisa_passthrough/booz_stabilization_int.makefile b/conf/firmwares/subsystems/lisa_passthrough/booz_stabilization_int.makefile index 53d7b44202..9798cb93cb 100644 --- a/conf/firmwares/subsystems/lisa_passthrough/booz_stabilization_int.makefile +++ b/conf/firmwares/subsystems/lisa_passthrough/booz_stabilization_int.makefile @@ -14,7 +14,7 @@ stm_passthrough.srcs += $(SRC_SUBSYSTEMS)/ins.c stm_passthrough.srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c stm_passthrough.srcs += $(SRC_FIRMWARE)/navigation.c stm_passthrough.srcs += $(SRC_SUBSYSTEMS)/ins/vf_float.c -stm_passthrough.CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./512.)' +stm_passthrough.CFLAGS += -DUSE_VFF stm_passthrough.CFLAGS += -DSTABILIZATION_ATTITUDE_TYPE_INT stm_passthrough.CFLAGS += -DSTABILIZATION_ATTITUDE_TYPE_H=\"stabilization/stabilization_attitude_int.h\" diff --git a/conf/firmwares/subsystems/rotorcraft/ins_hff.makefile b/conf/firmwares/subsystems/rotorcraft/ins_hff.makefile index 0e1d9dc5ef..fd0ca65228 100644 --- a/conf/firmwares/subsystems/rotorcraft/ins_hff.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ins_hff.makefile @@ -8,7 +8,7 @@ $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/ins_int.c # vertical filter float version $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/vf_float.c -$(TARGET).CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./$(PERIODIC_FREQUENCY).)' +$(TARGET).CFLAGS += -DUSE_VFF # horizontal filter float version $(TARGET).CFLAGS += -DUSE_HFF From f2a5d9ea5cce1e4ec220877fbdfc836dfc767c5f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 22:47:48 +0200 Subject: [PATCH 157/309] [conf] remove joystick subsystem rather add to your airframe file --- conf/firmwares/subsystems/fixedwing/joystick.makefile | 6 ------ 1 file changed, 6 deletions(-) delete mode 100644 conf/firmwares/subsystems/fixedwing/joystick.makefile diff --git a/conf/firmwares/subsystems/fixedwing/joystick.makefile b/conf/firmwares/subsystems/fixedwing/joystick.makefile deleted file mode 100644 index f0787a5567..0000000000 --- a/conf/firmwares/subsystems/fixedwing/joystick.makefile +++ /dev/null @@ -1,6 +0,0 @@ -# Hey Emacs, this is a -*- makefile -*- - -# joystick for fixedwings - -$(TARGET).CFLAGS += -DUSE_JOYSTICK - From 9c279840c28d4dbc7cf37baf8e8d8e6333178ee0 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 28 Aug 2013 20:36:05 +0200 Subject: [PATCH 158/309] [fixedwing] add nav_reset_utm_zone start solving issue #508 --- .../subsystems/navigation/common_nav.c | 30 +++++++++++++++++++ .../subsystems/navigation/common_nav.h | 1 + 2 files changed, 31 insertions(+) diff --git a/sw/airborne/subsystems/navigation/common_nav.c b/sw/airborne/subsystems/navigation/common_nav.c index 317fa475b3..7e641c05d6 100644 --- a/sw/airborne/subsystems/navigation/common_nav.c +++ b/sw/airborne/subsystems/navigation/common_nav.c @@ -61,6 +61,36 @@ void compute_dist2_to_home(void) { static float previous_ground_alt; +/** Reset the UTM zone to current GPS fix */ +unit_t nav_reset_utm_zone(void) { + + struct UtmCoor_f utm0_old; + utm0_old.zone = nav_utm_zone0; + utm0_old.north = nav_utm_north0; + utm0_old.east = nav_utm_east0; + utm0_old.alt = ground_alt; + struct LlaCoor_f lla0; + lla_of_utm_f(&lla0, &utm0_old); + +#ifdef GPS_USE_LATLONG + /* Set the real UTM zone */ + nav_utm_zone0 = (DegOfRad(gps.lla_pos.lon/1e7)+180) / 6 + 1; +#else + nav_utm_zone0 = gps.utm_pos.zone; +#endif + + struct UtmCoor_f utm0; + utm0.zone = nav_utm_zone0; + utm_of_lla_f(&utm0, &lla0); + + nav_utm_east0 = utm0.east; + nav_utm_north0 = utm0.north; + + stateSetLocalUtmOrigin_f(&utm0); + + return 0; +} + /** Reset the geographic reference to the current GPS fix */ unit_t nav_reset_reference( void ) { #ifdef GPS_USE_LATLONG diff --git a/sw/airborne/subsystems/navigation/common_nav.h b/sw/airborne/subsystems/navigation/common_nav.h index c7f0343489..3698d92702 100644 --- a/sw/airborne/subsystems/navigation/common_nav.h +++ b/sw/airborne/subsystems/navigation/common_nav.h @@ -61,6 +61,7 @@ extern uint8_t nav_utm_zone0; void compute_dist2_to_home(void); +unit_t nav_reset_utm_zone(void); unit_t nav_reset_reference( void ) __attribute__ ((unused)); unit_t nav_update_waypoints_alt( void ) __attribute__ ((unused)); void common_nav_periodic_task_4Hz(void); From d744f8ca2c9be9e957fe6acd034e6a032650bcd5 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Thu, 29 Aug 2013 15:22:08 +0200 Subject: [PATCH 159/309] [Messages] Image Analysis Telemetry --- conf/messages.xml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/conf/messages.xml b/conf/messages.xml index 683bac8e3c..3c5a9b2a29 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -614,7 +614,11 @@
- + + + + + From 03c3b8f43a77b06894083e474fbd7560fe776211 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 2 Jul 2013 16:40:40 +0200 Subject: [PATCH 160/309] [superbitrf] Initial commit for superbitrf 2.4GHz radio control --- .../quadrotor_lisa_m_2_pwm_spektrum.xml | 4 +- .../shared/radio_control_superbitrf.makefile | 14 + conf/messages.xml | 7 +- conf/telemetry/default_rotorcraft.xml | 1 + sw/airborne/firmwares/rotorcraft/telemetry.h | 12 + sw/airborne/mcu_periph/gpio.h | 4 + sw/airborne/peripherals/cyrf6936.c | 359 ++++++++++++++++++ sw/airborne/peripherals/cyrf6936.h | 70 ++++ sw/airborne/peripherals/cyrf6936_regs.h | 211 ++++++++++ .../subsystems/radio_control/superbitrf.c | 129 +++++++ .../subsystems/radio_control/superbitrf.h | 86 +++++ 11 files changed, 892 insertions(+), 5 deletions(-) create mode 100644 conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile create mode 100644 sw/airborne/peripherals/cyrf6936.c create mode 100644 sw/airborne/peripherals/cyrf6936.h create mode 100644 sw/airborne/peripherals/cyrf6936_regs.h create mode 100644 sw/airborne/subsystems/radio_control/superbitrf.c create mode 100644 sw/airborne/subsystems/radio_control/superbitrf.h diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index 8881af6298..3244ea3474 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -12,9 +12,7 @@ - - - + diff --git a/conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile b/conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile new file mode 100644 index 0000000000..791751efde --- /dev/null +++ b/conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile @@ -0,0 +1,14 @@ +# +# Makefile for shared radio_control superbitrf subsystem +# + +ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE_SUPERBITRF -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/superbitrf.h\" +ap.CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE1 + +ifneq ($(RADIO_CONTROL_LED),none) +ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) +endif + +ap.srcs += peripherals/cyrf6936.c \ + $(SRC_SUBSYSTEMS)/radio_control.c \ + $(SRC_SUBSYSTEMS)/radio_control/superbitrf.c diff --git a/conf/messages.xml b/conf/messages.xml index 3c5a9b2a29..2999fcab52 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -603,8 +603,11 @@ - - + + + + + diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index 6f83d9b340..0ed6ab52ae 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -26,6 +26,7 @@ + diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index a1b3472812..e08247b3f6 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -134,6 +134,18 @@ #define PERIODIC_SEND_PPM(_trans, _dev) {} #endif +#ifdef RADIO_CONTROL_TYPE_SUPERBITRF +#include "subsystems/radio_control/superbitrf.h" +#define PERIODIC_SEND_SUPERBITRF(_trans, _dev) { \ + DOWNLINK_SEND_SUPERBITRF(_trans, _dev, \ + &superbitrf.status, \ + &superbitrf.cyrf6936.status, \ + 6, \ + superbitrf.cyrf6936.mfg_id);} +#else +#define PERIODIC_SEND_SUPERBITRF(_trans, _dev) {} +#endif + #ifdef ACTUATORS #define PERIODIC_SEND_ACTUATORS(_trans, _dev) DOWNLINK_SEND_ACTUATORS(_trans, _dev, ACTUATORS_NB, actuators) #else diff --git a/sw/airborne/mcu_periph/gpio.h b/sw/airborne/mcu_periph/gpio.h index 1218ae6c05..0c500b3dd6 100644 --- a/sw/airborne/mcu_periph/gpio.h +++ b/sw/airborne/mcu_periph/gpio.h @@ -25,6 +25,9 @@ * Some architecture independent helper functions for GPIOs. */ +#ifndef MCU_PERIPH_GPIO_H +#define MCU_PERIPH_GPIO_H + #include "std.h" #include "mcu_periph/gpio_arch.h" @@ -38,3 +41,4 @@ extern void gpio_setup_output(uint32_t port, uint16_t pin); */ extern void gpio_setup_input(uint32_t port, uint16_t pin); +#endif /* MCU_PERIPH_GPIO_H */ diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c new file mode 100644 index 0000000000..9613d4c095 --- /dev/null +++ b/sw/airborne/peripherals/cyrf6936.c @@ -0,0 +1,359 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/cyrf6936.c + * Driver for the cyrf6936 2.4GHz radio chip + */ + +#include "cyrf6936.h" +#include "mcu_periph/spi.h" +#include "mcu_periph/gpio.h" +#include "mcu_periph/gpio_arch.h" +#include "subsystems/radio_control.h" + +#include "mcu_periph/uart.h" +#include "messages.h" +#include "subsystems/datalink/downlink.h" + +/* Static functions used in the different statuses */ +static bool_t cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data); +static bool_t cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data[], const uint8_t length); +static bool_t cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr); +static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t length); + +//FIXME +void Delay(uint32_t x); +void Delay(uint32_t x) +{ + (void)x; + __asm ("mov r1, #24;" + "mul r0, r0, r1;" + "b _delaycmp;" + "_delayloop:" + "subs r0, r0, #1;" + "_delaycmp:;" + "cmp r0, #0;" + " bne _delayloop;"); +} + +/** + * Initializing the cyrf chip + */ +void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_t slave_idx, const uint32_t rst_port, const uint16_t rst_pin) { + /* Set spi_peripheral and the status */ + cyrf->spi_p = spi_p; + cyrf->status = CYRF6936_UNINIT; + + /* Set the spi transaction */ + cyrf->spi_t.cpol = SPICpolIdleLow; + cyrf->spi_t.cpha = SPICphaEdge1; + cyrf->spi_t.dss = SPIDss8bit; + cyrf->spi_t.bitorder = SPIMSBFirst; + cyrf->spi_t.cdiv = SPIDiv64; + + cyrf->spi_t.input_length = 0; + cyrf->spi_t.output_length = 0; + cyrf->spi_t.input_buf = cyrf->input_buf; + cyrf->spi_t.output_buf = cyrf->output_buf; + cyrf->spi_t.slave_idx = slave_idx; + cyrf->spi_t.select = SPISelectUnselect; + cyrf->spi_t.status = SPITransDone; + + /* Reset the CYRF6936 chip */ + gpio_setup_output(rst_port, rst_pin); + gpio_output_high(rst_port, rst_pin); + Delay(100); + gpio_output_low(rst_port, rst_pin); + Delay(100); + + /* Get the MFG ID */ + cyrf->status = CYRF6936_GET_MFG_ID; + cyrf->buffer_idx = 0; + cyrf6936_write_register(cyrf, CYRF_MFG_ID, 0xFF); +} + +/** + * The on event call for the CYRF6936 chip + */ +void cyrf6936_event(struct Cyrf6936 *cyrf) { + int i; + // Check if cyrf is initialized + if(cyrf->status == CYRF6936_UNINIT) + return; + + // Check if there is still a transaction in progress + if(cyrf->spi_t.status == SPITransPending || cyrf->spi_t.status == SPITransRunning) + return; + + /* Check the status of the cyrf */ + switch (cyrf->status) { + + /* Getting the MFG id */ + case CYRF6936_GET_MFG_ID: + // When the last transaction isn't failed send the next + if(cyrf->spi_t.status != SPITransFailed) + cyrf->buffer_idx++; + + cyrf->spi_t.status = SPITransDone; + + // Switch for the different states + switch (cyrf->buffer_idx) { + case 0: + cyrf6936_write_register(cyrf, CYRF_MFG_ID, 0xFF); + break; + case 1: + cyrf6936_read_block(cyrf, CYRF_MFG_ID, 6); + break; + case 2: + // Copy the MFG id + for(i = 0; i < 6; i++) + cyrf->mfg_id[i] = cyrf->input_buf[i+1]; + + cyrf6936_write_register(cyrf, CYRF_MFG_ID, 0x00); + break; + default: + cyrf->status = CYRF6936_IDLE; + break; + } + break; + + /* Do a multi write */ + case CYRF6936_MULTIWRITE: + // When the last transaction isn't failed send the next + if(cyrf->spi_t.status != SPITransFailed) + cyrf->buffer_idx++; + + cyrf->spi_t.status = SPITransDone; + + // When we are done writing + if(cyrf->buffer_idx == cyrf->buffer_length) { + cyrf->status = CYRF6936_IDLE; + break; + } + + // Write the next register from the buffer + cyrf6936_write_register(cyrf, + ((uint8_t (*)[2])cyrf->buffer)[cyrf->buffer_idx][0], + ((uint8_t (*)[2])cyrf->buffer)[cyrf->buffer_idx][1]); + break; + + /* Do a write of channel, sop, data and crc */ + case CYRF6936_CHAN_SOP_DATA_CRC: + // When the last transaction isn't failed send the next + if(cyrf->spi_t.status != SPITransFailed) + cyrf->buffer_idx++; + + cyrf->spi_t.status = SPITransDone; + + // Switch for the different states + switch (cyrf->buffer_idx) { + case 0: // Write the CRC LSB + cyrf6936_write_register(cyrf, CYRF_CRC_SEED_LSB, cyrf->buffer[0]); + break; + case 1: // Write the CRC MSB + cyrf6936_write_register(cyrf, CYRF_CRC_SEED_MSB, cyrf->buffer[1]); + break; + case 2: // Write the SOP code + cyrf6936_write_block(cyrf, CYRF_SOP_CODE, &(cyrf->buffer[2]), 8); + break; + case 3: // Write the DATA code + cyrf6936_write_block(cyrf, CYRF_DATA_CODE, &(cyrf->buffer[10]), 16); + break; + case 4: // Write the Channel + cyrf6936_write_register(cyrf, CYRF_CHANNEL, cyrf->buffer[26]); + break; + default: + cyrf->status = CYRF6936_IDLE; + break; + } + break; + + /* Do a read of the receive irq status, receive status and the receive packet */ + case CYRF6936_RX_IRQ_STATUS_PACKET: + // When the last transaction isn't failed send the next + if(cyrf->spi_t.status != SPITransFailed) + cyrf->buffer_idx++; + + cyrf->spi_t.status = SPITransDone; + + // Switch for the different states + switch (cyrf->buffer_idx) { + case 0: // Read the receive IRQ status + cyrf6936_read_register(cyrf, CYRF_RX_IRQ_STATUS); + break; + case 1: // Read the receive status + cyrf->rx_irq_status = cyrf->input_buf[1]; + cyrf6936_read_register(cyrf, CYRF_RX_STATUS); + break; + case 2: // Read the receive packet + cyrf->rx_status = cyrf->input_buf[1]; + cyrf6936_read_block(cyrf, CYRF_RX_BUFFER, 16); + break; + default: + // Copy the receive packet + for(i = 0; i < 16; i++) + cyrf->rx_packet[i] = cyrf->input_buf[i+1]; + + cyrf->status = CYRF6936_IDLE; + break; + } + break; + + /* This should not happen */ + default: + break; + } +} + +/** + * Write a byte to a register + */ +static bool_t cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data) { + return cyrf6936_write_block(cyrf, addr, &data, 1); +} + +/** + * Write multiple bytes to a register + */ +static bool_t cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data[], const uint8_t length) { + uint8_t i; + /* Check if there is already a SPI transaction busy */ + if(cyrf->spi_t.status != SPITransDone) + return FALSE; + + /* Set the buffer and commit the transaction */ + cyrf->spi_t.output_length = length+1; + cyrf->spi_t.input_length = 0; + cyrf->output_buf[0] = addr | CYRF_DIR; + + // Copy the data + for(i = 0; i < length; i++) + cyrf->output_buf[i+1] = data[i]; + + // Submit the transaction + return spi_submit(cyrf->spi_p, &(cyrf->spi_t)); +} + +/** + * Read a byte from a register + */ +static bool_t cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr) { + return cyrf6936_read_block(cyrf, addr, 1); +} + +/** + * Read multiple bytes from a register + */ +static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t length) { + if(cyrf->spi_t.status != SPITransDone) + return FALSE; + + /* Set the buffer and commit the transaction */ + cyrf->spi_t.output_length = 1; + cyrf->spi_t.input_length = length + 1; + cyrf->output_buf[0] = addr; + + // Submit the transaction + return spi_submit(cyrf->spi_p, &(cyrf->spi_t)); +} + + +/** + * Write to multiple registers one byte + */ +bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length) { + uint8_t i; + /* Check if the cyrf6936 isn't busy */ + if(cyrf->status != CYRF6936_IDLE) + return FALSE; + + // Set the status + cyrf->status = CYRF6936_MULTIWRITE; + + /* Set the multi write */ + cyrf->buffer_length = length; + cyrf->buffer_idx = 0; + + // Copy the buffer + for(i = 0; i< length; i++) { + cyrf->buffer[i*2] = data[i][0]; + cyrf->buffer[i*2+1] = data[i][1]; + } + + /* Write the first regiter */ + if(length > 0) + cyrf6936_write_register(cyrf, data[0][0], data[0][1]); + + return TRUE; +} + +/** + * Set the channel, SOP code, DATA code and the CRC seed + */ +bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[], const uint8_t data_code[], const uint16_t crc_seed) { + uint8_t i; + /* Check if the cyrf6936 isn't busy */ + if(cyrf->status != CYRF6936_IDLE) + return FALSE; + + // Set the status + cyrf->status = CYRF6936_CHAN_SOP_DATA_CRC; + + // Copy the CRC + cyrf->buffer[0] = crc_seed & 0xFF; + cyrf->buffer[1] = (crc_seed >> 8) & 0xFF; + + // Copy the SOP code + for(i = 0; i < 8; i++) + cyrf->buffer[i+2] = sop_code[i]; + + // Copy the DATA code + for(i = 0; i < 16; i++) + cyrf->buffer[i+10] = data_code[i]; + + // Copy the channel + cyrf->buffer[26] = chan; + + /* Try to write the CRC LSB */ + cyrf->buffer_idx = 0; + cyrf6936_write_register(cyrf, CYRF_CRC_SEED_LSB, cyrf->buffer[0]); + + return TRUE; +} + +/** + * Read the RX IRQ status register, the rx status register and the rx packet + */ +bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf) { + /* Check if the cyrf6936 isn't busy */ + if(cyrf->status != CYRF6936_IDLE) + return FALSE; + + // Set the status + cyrf->status = CYRF6936_RX_IRQ_STATUS_PACKET; + + /* Try to read the RX status */ + cyrf->buffer_idx = 0; + cyrf6936_read_register(cyrf, CYRF_RX_IRQ_STATUS); + + return TRUE; +} diff --git a/sw/airborne/peripherals/cyrf6936.h b/sw/airborne/peripherals/cyrf6936.h new file mode 100644 index 0000000000..b7254ff026 --- /dev/null +++ b/sw/airborne/peripherals/cyrf6936.h @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/yrf6936c.h + * Driver for the cyrf6936 2.4GHz radio chip + */ + +#ifndef CYRF6936_H +#define CYRF6936_H + +#include "cyrf6936_regs.h" +#include "mcu_periph/spi.h" + +#define CYRF6936_MAX_BUFFER 80 /**< The max buffer size in the cyrf6936 structure */ + +/* The different statuses the cyrf6936 chip can be in */ +enum Cyrf6936Status { + CYRF6936_UNINIT, /**< The chip isn't initialized */ + CYRF6936_IDLE, /**< The chip is idle and can be used */ + CYRF6936_GET_MFG_ID, /**< The chip is busy with getting the manufacturer ID */ + CYRF6936_MULTIWRITE, /**< The chip is writing multiple registers */ + CYRF6936_CHAN_SOP_DATA_CRC, /**< The chip is setting the channel, SOP code, DATA code and the CRC seed */ + CYRF6936_RX_IRQ_STATUS_PACKET /**< The chip is getting the receive irq status, receive status and the receive packet */ +}; + +/* The structure for the cyrf6936 chip that handles all the buffers and requests */ +struct Cyrf6936 { + struct spi_periph *spi_p; /**< The SPI peripheral for the connection */ + struct spi_transaction spi_t; /**< The SPI transaction used for the writing and reading of registers */ + volatile enum Cyrf6936Status status; /**< The status of the CYRF6936 chip */ + uint8_t input_buf[17]; /**< The input buffer for the SPI transaction */ + uint8_t output_buf[17]; /**< The output buffer for the SPI transaction */ + + uint8_t buffer[CYRF6936_MAX_BUFFER]; /**< The buffer used to write/read multiple registers */ + uint8_t buffer_length; /**< The length of the buffer used for MULTIWRITE */ + uint8_t buffer_idx; /**< The index of the buffer used for MULTIWRITE and used as sub-status for other statuses */ + + uint8_t mfg_id[6]; /**< The manufacturer id of the CYRF6936 chip */ + uint8_t rx_irq_status; /**< The last receive interrupt status */ + uint8_t rx_status; /**< The last receive status */ + uint8_t rx_packet[16]; /**< The last received packet */ +}; + +extern void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_t slave_idx, const uint32_t rst_port, const uint16_t rst_pin); +void cyrf6936_event(struct Cyrf6936 *cyrf); + +bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length); +bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[], const uint8_t data_code[], const uint16_t crc_seed); +bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf); + +#endif /* CYRF6936_H */ diff --git a/sw/airborne/peripherals/cyrf6936_regs.h b/sw/airborne/peripherals/cyrf6936_regs.h new file mode 100644 index 0000000000..c5926771a7 --- /dev/null +++ b/sw/airborne/peripherals/cyrf6936_regs.h @@ -0,0 +1,211 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file peripherals/cyrf6936_regs.h + * Register defines for the CYRF6936 2.4GHz radio chip + */ + +#ifndef CYRF6936_REGS_H +#define CYRF6936_REGS_H + +/* The SPI interface defines */ +enum { + CYRF_CHANNEL = 0x00, + CYRF_TX_LENGTH = 0x01, + CYRF_TX_CTRL = 0x02, + CYRF_TX_CFG = 0x03, + CYRF_TX_IRQ_STATUS = 0x04, + CYRF_RX_CTRL = 0x05, + CYRF_RX_CFG = 0x06, + CYRF_RX_IRQ_STATUS = 0x07, + CYRF_RX_STATUS = 0x08, + CYRF_RX_COUNT = 0x09, + CYRF_RX_LENGTH = 0x0A, + CYRF_PWR_CTRL = 0x0B, + CYRF_XTAL_CTRL = 0x0C, + CYRF_IO_CFG = 0x0D, + CYRF_GPIO_CTRL = 0x0E, + CYRF_XACT_CFG = 0x0F, + CYRF_FRAMING_CFG = 0x10, + CYRF_DATA32_THOLD = 0x11, + CYRF_DATA64_THOLD = 0x12, + CYRF_RSSI = 0x13, + CYRF_EOP_CTRL = 0x14, + CYRF_CRC_SEED_LSB = 0x15, + CYRF_CRC_SEED_MSB = 0x16, + CYRF_TX_CRC_LSB = 0x17, + CYRF_TX_CRC_MSB = 0x18, + CYRF_RX_CRC_LSB = 0x19, + CYRF_RX_CRC_MSB = 0x1A, + CYRF_TX_OFFSET_LSB = 0x1B, + CYRF_TX_OFFSET_MSB = 0x1C, + CYRF_MODE_OVERRIDE = 0x1D, + CYRF_RX_OVERRIDE = 0x1E, + CYRF_TX_OVERRIDE = 0x1F, + CYRF_TX_BUFFER = 0x20, + CYRF_RX_BUFFER = 0x21, + CYRF_SOP_CODE = 0x22, + CYRF_DATA_CODE = 0x23, + CYRF_PREAMBLE = 0x24, + CYRF_MFG_ID = 0x25, + CYRF_XTAL_CFG = 0x26, + CYRF_CLK_OFFSET = 0x27, + CYRF_CLK_EN = 0x28, + CYRF_RX_ABORT = 0x29, + CYRF_AUTO_CAL_TIME = 0x32, + CYRF_AUTO_CAL_OFFSET = 0x35, + CYRF_ANALOG_CTRL = 0x39, +}; +#define CYRF_DIR (1<<7) /**< Bit for enabling writing */ + +// CYRF_MODE_OVERRIDE +#define CYRF_RST (1<<0) + +// CYRF_CLK_EN +#define CYRF_RXF (1<<1) + +// CYRF_XACT_CFG +enum { + CYRF_MODE_SLEEP = (0x0 <<2), + CYRF_MODE_IDLE = (0x1 <<2), + CYRF_MODE_SYNTH_TX = (0x2 <<2), + CYRF_MODE_SYNTH_RX = (0x3 <<2), + CYRF_MODE_RX = (0x4 <<2), +}; +#define CYRF_FRC_END (1<<5) +#define CYRF_ACK_EN (1<<7) + +// CYRF_IO_CFG +#define CYRF_IRQ_GPIO (1<<0) +#define CYRF_SPI_3PIN (1<<1) +#define CYRF_PACTL_GPIO (1<<2) +#define CYRF_PACTL_OD (1<<3) +#define CYRF_XOUT_OD (1<<4) +#define CYRF_MISO_OD (1<<5) +#define CYRF_IRQ_POL (1<<6) +#define CYRF_IRQ_OD (1<<7) + +// CYRF_FRAMING_CFG +#define CYRF_LEN_EN (1<<5) +#define CYRF_SOP_LEN (1<<6) +#define CYRF_SOP_EN (1<<7) + +// CYRF_RX_STATUS +enum { + CYRF_RX_DATA_MODE_GFSK = 0x00, + CYRF_RX_DATA_MODE_8DR = 0x01, + CYRF_RX_DATA_MODE_DDR = 0x10, + CYRF_RX_DATA_MODE_NV = 0x11, +}; +#define CYRF_RX_CODE (1<<2) +#define CYRF_BAD_CRC (1<<3) +#define CYRF_CRC0 (1<<4) +#define CYRF_EOP_ERR (1<<5) +#define CYRF_PKT_ERR (1<<6) +#define CYRF_RX_ACK (1<<7) + +// CYRF_TX_IRQ_STATUS +#define CYRF_TXE_IRQ (1<<0) +#define CYRF_TXC_IRQ (1<<1) +#define CYRF_TXBERR_IRQ (1<<2) +#define CYRF_TXB0_IRQ (1<<3) +#define CYRF_TXB8_IRQ (1<<4) +#define CYRF_TXB15_IRQ (1<<5) +#define CYRF_LV_IRQ (1<<6) +#define CYRF_OS_IRQ (1<<7) + +// CYRF_RX_IRQ_STATUS +#define CYRF_RXE_IRQ (1<<0) +#define CYRF_RXC_IRQ (1<<1) +#define CYRF_RXBERR_IRQ (1<<2) +#define CYRF_RXB1_IRQ (1<<3) +#define CYRF_RXB8_IRQ (1<<4) +#define CYRF_RXB16_IRQ (1<<5) +#define CYRF_SOPDET_IRQ (1<<6) +#define CYRF_RXOW_IRQ (1<<7) + +// CYRF_TX_CTRL +#define CYRF_TXE_IRQEN (1<<0) +#define CYRF_TXC_IRQEN (1<<1) +#define CYRF_TXBERR_IRQEN (1<<2) +#define CYRF_TXB0_IRQEN (1<<3) +#define CYRF_TXB8_IRQEN (1<<4) +#define CYRF_TXB15_IRQEN (1<<5) +#define CYRF_TX_CLR (1<<6) +#define CYRF_TX_GO (1<<7) + +// CYRF_RX_CTRL +#define CYRF_RXE_IRQEN (1<<0) +#define CYRF_RXC_IRQEN (1<<1) +#define CYRF_RXBERR_IRQEN (1<<2) +#define CYRF_RXB1_IRQEN (1<<3) +#define CYRF_RXB8_IRQEN (1<<4) +#define CYRF_RXB16_IRQEN (1<<5) +#define CYRF_RSVD (1<<6) +#define CYRF_RX_GO (1<<7) + +// CYRF_RX_OVERRIDE +#define CYRF_ACE (1<<1) +#define CYRF_DIS_RXCRC (1<<2) +#define CYRF_DIS_CRC0 (1<<3) +#define CYRF_FRC_RXDR (1<<4) +#define CYRF_MAN_RXACK (1<<5) +#define CYRF_RXTX_DLY (1<<6) +#define CYRF_ACK_RX (1<<7) + +// CYRF_TX_OVERRIDE +#define CYRF_TX_INV (1<<0) +#define CYRF_DIS_TXCRC (1<<2) +#define CYRF_OVRD_ACK (1<<3) +#define CYRF_MAN_TXACK (1<<4) +#define CYRF_FRC_PRE (1<<6) +#define CYRF_ACK_TX (1<<7) + +// CYRF_RX_CFG +#define CYRF_VLD_EN (1<<0) +#define CYRF_RXOW_EN (1<<1) +#define CYRF_FAST_TURN_EN (1<<3) +#define CYRF_HILO (1<<4) +#define CYRF_ATT (1<<5) +#define CYRF_LNA (1<<6) +#define CYRF_AGC_EN (1<<7) + +// CYRF_TX_CFG +enum { + CYRF_PA_M35 = 0x0, + CYRF_PA_M30 = 0x1, + CYRF_PA_M24 = 0x2, + CYRF_PA_M18 = 0x3, + CYRF_PA_M13 = 0x4, + CYRF_PA_M5 = 0x5, + CYRF_PA_0 = 0x6, + CYRF_PA_4 = 0x7, +}; +enum { + CYRF_DATA_MODE_GFSK = (0x0 <<3), + CYRF_DATA_MODE_8DR = (0x1 <<3), + CYRF_DATA_MODE_DDR = (0x2 <<3), + CYRF_DATA_MODE_SDR = (0x3 <<3), +}; +#define CYRF_DATA_CODE_LENGTH (1<<5) + +#endif // CYRF6936_REGS_H diff --git a/sw/airborne/subsystems/radio_control/superbitrf.c b/sw/airborne/subsystems/radio_control/superbitrf.c new file mode 100644 index 0000000000..8f51d733eb --- /dev/null +++ b/sw/airborne/subsystems/radio_control/superbitrf.c @@ -0,0 +1,129 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/radio_control/superbitrf.c + * DSM2 and DSMX implementation for the cyrf6936 2.4GHz radio chip trough SPI + */ + +#include "superbitrf.h" + +#include "subsystems/radio_control.h" +#include "mcu_periph/spi.h" +#include + +/* Default SuperbitRF SPI DEV */ +#ifndef SUPERBITRF_SPI_DEV +#define SUPERBITRF_SPI_DEV spi1 +#endif + +/* Default SuperbitRF RST PORT and PIN */ +#ifndef SUPERBITRF_RST_PORT +#define SUPERBITRF_RST_PORT GPIOC +#endif +#ifndef SUPERBITRF_RST_PIN +#define SUPERBITRF_RST_PIN GPIO12 +#endif + +/* Default SuperbitRF DRDY(IRQ) PORT and PIN */ +#ifndef SUPERBITRF_DRDY_PORT +#define SUPERBITRF_DRDY_PORT GPIOB +#endif +#ifndef SUPERBITRF_DRDY_PIN +#define SUPERBITRF_DRDY_PIN GPIO1 +#endif + +/* The superbitRF structure */ +struct SuperbitRF superbitrf; + +/* The startup configuration for the cyrf6936 */ +static const uint8_t cyrf_stratup_config[][2] = { + {CYRF_MODE_OVERRIDE, CYRF_RST}, // Reset the device + {CYRF_CLK_EN, CYRF_RXF}, // Enable the clock + {CYRF_AUTO_CAL_TIME, 0x3C}, // From manual, needed for initialization + {CYRF_AUTO_CAL_OFFSET, 0x14}, // From manual, needed for initialization + {CYRF_RX_CFG, CYRF_LNA | CYRF_FAST_TURN_EN}, // Enable low noise amplifier and fast turning + {CYRF_TX_OFFSET_LSB, 0x55}, // From manual, typical configuration + {CYRF_TX_OFFSET_MSB, 0x05}, // From manual, typical configuration + {CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END}, // Force in Synth RX mode + {CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_SDR | CYRF_PA_4}, // Enable 64 chip codes, SDR mode and amplifier +4dBm + {CYRF_DATA64_THOLD, 0x0E}, // From manual, typical configuration + {CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX}, // Set in Synth RX mode (again, really needed?) +}; +/* The binding configuration for the cyrf6936 */ +static const uint8_t cyrf_bind_config[][2] = { + {CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_SDR | CYRF_PA_4}, // Enable 64 chip codes, SDR mode and amplifier +4dBm + {CYRF_FRAMING_CFG, CYRF_SOP_LEN | 0xE}, // Set SOP CODE to 64 chips and SOP Correlator Threshold to 0xE + {CYRF_RX_OVERRIDE, CYRF_FRC_RXDR | CYRF_DIS_RXCRC}, // Force receive data rate and disable receive CRC checker + {CYRF_EOP_CTRL, 0x02}, // Only enable EOP symbol count of 2 + {CYRF_TX_OVERRIDE, CYRF_DIS_TXCRC}, // Disable transmit CRC generate +}; + +/** + * Initialize the superbitrf + */ +void radio_control_impl_init(void) { + // Set the status to uninitialized + superbitrf.status = SUPERBITRF_UNINIT; + + // Initialize the binding pin + gpio_setup_input(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN); + + // Initialize the cyrf6936 chip + cyrf6936_init(&superbitrf.cyrf6936, &(SUPERBITRF_SPI_DEV), 1, SUPERBITRF_RST_PORT, SUPERBITRF_RST_PIN); +} + +/** + * The superbitrf on event call + */ +void superbitrf_event(void) { + // Check the status + switch(superbitrf.status) { + + /* When the superbitrf isn't initialized */ + case SUPERBITRF_UNINIT: + // Try to write the startup config + if(cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_stratup_config, 11)) { + // Check if need to go to bind or transfer + if(gpio_get(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN) == 0) + superbitrf.status = SUPERBITRF_INIT_BINDING; + else + superbitrf.status = SUPERBITRF_INIT_TRANSFER; + } + break; + + /* When the superbitrf is initializing binding */ + case SUPERBITRF_INIT_BINDING: + // Try to write the binding config + if(cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_bind_config, 5)) + superbitrf.status = SUPERBITRF_BINDING; + break; + + /* When the superbitrf is in binding mode */ + case SUPERBITRF_BINDING: + break; + + /* Should not come here */ + default: + break; + } + +} diff --git a/sw/airborne/subsystems/radio_control/superbitrf.h b/sw/airborne/subsystems/radio_control/superbitrf.h new file mode 100644 index 0000000000..a9f7e20dcf --- /dev/null +++ b/sw/airborne/subsystems/radio_control/superbitrf.h @@ -0,0 +1,86 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file subsystems/radio_control/superbitrf.h + * DSM2 and DSMX implementation for the cyrf6936 2.4GHz radio chip trough SPI + */ + +#ifndef RADIO_CONTROL_SUPERBITRF_H +#define RADIO_CONTROL_SUPERBITRF_H + +#include "peripherals/cyrf6936.h" +#include "mcu_periph/gpio.h" + +/* Theoretically you could have 14 channel over DSM2/DSMX */ +#ifndef RADIO_CONTROL_NB_CHANNEL +#define RADIO_CONTROL_NB_CHANNEL 14 +#endif + +/* The channel ordering is always the same for DSM2 and DSMX */ +#define RADIO_THROTTLE 0 +#define RADIO_ROLL 1 +#define RADIO_PITCH 2 +#define RADIO_YAW 3 +#define RADIO_GEAR 4 +#define RADIO_FLAP 5 +#define RADIO_AUX1 5 +#define RADIO_AUX2 6 +#define RADIO_AUX3 7 +#define RADIO_AUX4 8 +#define RADIO_AUX5 9 +#define RADIO_AUX6 10 +#define RADIO_AUX7 11 +#define RADIO_AUX8 12 +#define RADIO_AUX9 13 + +/* Map the MODE default to the gear switch */ +#ifndef RADIO_MODE +#define RADIO_MODE RADIO_GEAR +#endif + +/* The different statuses the superbitRF can be in */ +enum SuperbitRFStatus { + SUPERBITRF_UNINIT, /**< The chip isn't initialized */ + SUPERBITRF_INIT_BINDING, /**< The chip is initializing binding mode */ + SUPERBITRF_INIT_TRANSFER, /**< The chip is initializing transfer mode */ + SUPERBITRF_BINDING, /**< The chip is in binding mode */ + SUPERBITRF_TRANSFER, /**< The chip is in transfer mode */ +}; + +/* The superbitrf structure */ +struct SuperbitRF { + struct Cyrf6936 cyrf6936; /**< The cyrf chip used */ + volatile enum SuperbitRFStatus status; /**< The status of the superbitRF */ +}; + +/* The superbitrf functions and structures */ +extern struct SuperbitRF superbitrf; +void superbitrf_event(void); + +/* The radio control event handler */ +#define RadioControlEvent(_received_frame_handler) { \ + cyrf6936_event(&superbitrf.cyrf6936); \ + superbitrf_event(); \ +} + +#endif /* RADIO_CONTROL_SUPERBITRF_H */ From 55add10b2fb86c5b30378699e0bc69b5f980ffcf Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 3 Jul 2013 16:54:58 +0200 Subject: [PATCH 161/309] [superbitrf] Now got a full RC working, still needs testing. Binding could be improved but already works about 30% of the times you try. --- conf/messages.xml | 4 +- conf/telemetry/default_rotorcraft.xml | 2 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 2 + sw/airborne/peripherals/cyrf6936.c | 37 +- sw/airborne/peripherals/cyrf6936.h | 3 + .../subsystems/radio_control/superbitrf.c | 395 +++++++++++++++++- .../subsystems/radio_control/superbitrf.h | 61 ++- 7 files changed, 475 insertions(+), 29 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index 2999fcab52..6c9b867c8c 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -604,8 +604,10 @@ - + + + diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index 0ed6ab52ae..b647b9c609 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -18,6 +18,7 @@ + @@ -26,7 +27,6 @@ - diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index e08247b3f6..afed5e1137 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -140,6 +140,8 @@ DOWNLINK_SEND_SUPERBITRF(_trans, _dev, \ &superbitrf.status, \ &superbitrf.cyrf6936.status, \ + &superbitrf.packet_count, \ + &superbitrf.packet_count, \ 6, \ superbitrf.cyrf6936.mfg_id);} #else diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 9613d4c095..996285c5f2 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -28,6 +28,7 @@ #include "mcu_periph/spi.h" #include "mcu_periph/gpio.h" #include "mcu_periph/gpio_arch.h" +#include "mcu_periph/sys_time.h" #include "subsystems/radio_control.h" #include "mcu_periph/uart.h" @@ -40,21 +41,6 @@ static bool_t cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, co static bool_t cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr); static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t length); -//FIXME -void Delay(uint32_t x); -void Delay(uint32_t x) -{ - (void)x; - __asm ("mov r1, #24;" - "mul r0, r0, r1;" - "b _delaycmp;" - "_delayloop:" - "subs r0, r0, #1;" - "_delaycmp:;" - "cmp r0, #0;" - " bne _delayloop;"); -} - /** * Initializing the cyrf chip */ @@ -62,6 +48,7 @@ void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_ /* Set spi_peripheral and the status */ cyrf->spi_p = spi_p; cyrf->status = CYRF6936_UNINIT; + cyrf->has_packet = FALSE; /* Set the spi transaction */ cyrf->spi_t.cpol = SPICpolIdleLow; @@ -78,12 +65,12 @@ void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_ cyrf->spi_t.select = SPISelectUnselect; cyrf->spi_t.status = SPITransDone; - /* Reset the CYRF6936 chip */ + /* Reset the CYRF6936 chip (busy waiting) */ gpio_setup_output(rst_port, rst_pin); gpio_output_high(rst_port, rst_pin); - Delay(100); + sys_time_usleep(100); gpio_output_low(rst_port, rst_pin); - Delay(100); + sys_time_usleep(100); /* Get the MFG ID */ cyrf->status = CYRF6936_GET_MFG_ID; @@ -156,6 +143,10 @@ void cyrf6936_event(struct Cyrf6936 *cyrf) { ((uint8_t (*)[2])cyrf->buffer)[cyrf->buffer_idx][1]); break; + /* Do a write of the data code */ + case CYRF6936_DATA_CODE: + break; + /* Do a write of channel, sop, data and crc */ case CYRF6936_CHAN_SOP_DATA_CRC: // When the last transaction isn't failed send the next @@ -213,6 +204,7 @@ void cyrf6936_event(struct Cyrf6936 *cyrf) { for(i = 0; i < 16; i++) cyrf->rx_packet[i] = cyrf->input_buf[i+1]; + cyrf->has_packet = TRUE; cyrf->status = CYRF6936_IDLE; break; } @@ -276,6 +268,15 @@ static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, con return spi_submit(cyrf->spi_p, &(cyrf->spi_t)); } +/** + * Write to one register + */ +bool_t cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data) { + const uint8_t data_multi[][2] = { + {addr, data} + }; + return cyrf6936_multi_write(cyrf, data_multi, 1); +} /** * Write to multiple registers one byte diff --git a/sw/airborne/peripherals/cyrf6936.h b/sw/airborne/peripherals/cyrf6936.h index b7254ff026..7a7943f566 100644 --- a/sw/airborne/peripherals/cyrf6936.h +++ b/sw/airborne/peripherals/cyrf6936.h @@ -38,6 +38,7 @@ enum Cyrf6936Status { CYRF6936_IDLE, /**< The chip is idle and can be used */ CYRF6936_GET_MFG_ID, /**< The chip is busy with getting the manufacturer ID */ CYRF6936_MULTIWRITE, /**< The chip is writing multiple registers */ + CYRF6936_DATA_CODE, /**< The chip is writing a data code */ CYRF6936_CHAN_SOP_DATA_CRC, /**< The chip is setting the channel, SOP code, DATA code and the CRC seed */ CYRF6936_RX_IRQ_STATUS_PACKET /**< The chip is getting the receive irq status, receive status and the receive packet */ }; @@ -54,6 +55,7 @@ struct Cyrf6936 { uint8_t buffer_length; /**< The length of the buffer used for MULTIWRITE */ uint8_t buffer_idx; /**< The index of the buffer used for MULTIWRITE and used as sub-status for other statuses */ + bool_t has_packet; /**< When the CYRF6936 is done reading the receive registers */ uint8_t mfg_id[6]; /**< The manufacturer id of the CYRF6936 chip */ uint8_t rx_irq_status; /**< The last receive interrupt status */ uint8_t rx_status; /**< The last receive status */ @@ -63,6 +65,7 @@ struct Cyrf6936 { extern void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_t slave_idx, const uint32_t rst_port, const uint16_t rst_pin); void cyrf6936_event(struct Cyrf6936 *cyrf); +bool_t cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data); bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length); bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[], const uint8_t data_code[], const uint16_t crc_seed); bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf); diff --git a/sw/airborne/subsystems/radio_control/superbitrf.c b/sw/airborne/subsystems/radio_control/superbitrf.c index 8f51d733eb..510a16ee0b 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf.c +++ b/sw/airborne/subsystems/radio_control/superbitrf.c @@ -26,8 +26,10 @@ #include "superbitrf.h" +#include #include "subsystems/radio_control.h" #include "mcu_periph/spi.h" +#include "mcu_periph/sys_time.h" #include /* Default SuperbitRF SPI DEV */ @@ -54,6 +56,10 @@ /* The superbitRF structure */ struct SuperbitRF superbitrf; +/* The internal functions */ +static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[]); +static inline void superbitrf_radio_to_channels(char* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels); + /* The startup configuration for the cyrf6936 */ static const uint8_t cyrf_stratup_config[][2] = { {CYRF_MODE_OVERRIDE, CYRF_RST}, // Reset the device @@ -76,17 +82,100 @@ static const uint8_t cyrf_bind_config[][2] = { {CYRF_EOP_CTRL, 0x02}, // Only enable EOP symbol count of 2 {CYRF_TX_OVERRIDE, CYRF_DIS_TXCRC}, // Disable transmit CRC generate }; +/* The transfer configuration for the cyrf6936 */ +static const uint8_t cyrf_transfer_config[][2] = { + {CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_8DR | CYRF_PA_4}, // Enable 64 chip codes, 8DR mode and amplifier +4dBm + {CYRF_FRAMING_CFG, CYRF_SOP_EN | CYRF_SOP_LEN | CYRF_LEN_EN | 0xE}, // Set SOP CODE enable, SOP CODE to 64 chips, Packet length enable, and SOP Correlator Threshold to 0xE + {CYRF_TX_OVERRIDE, 0x00}, // Reset TX overrides + {CYRF_RX_OVERRIDE, 0x00}, // Reset RX overrides +}; +/* Abort the receive of the cyrf6936 */ +const uint8_t cyrf_abort_receive[][2] = { + {CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END}, + {CYRF_RX_ABORT, 0x00} +}; +/* Start the receive of the cyrf6936 */ +const uint8_t cyrf_start_receive[][2] = { + {CYRF_RX_IRQ_STATUS, CYRF_RXOW_IRQ}, // Clear the IRQ + {CYRF_RX_CTRL, CYRF_RX_GO | CYRF_RXC_IRQEN | CYRF_RXE_IRQEN} // Start receiving and set the IRQ +}; + +/* The PN codes used for DSM2 and DSMX channel hopping */ +static const uint8_t pn_codes[5][9][8] = { +{ /* Row 0 */ + /* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8}, + /* Col 1 */ {0x88, 0x17, 0x13, 0x3B, 0x2D, 0xBF, 0x06, 0xD6}, + /* Col 2 */ {0xF1, 0x94, 0x30, 0x21, 0xA1, 0x1C, 0x88, 0xA9}, + /* Col 3 */ {0xD0, 0xD2, 0x8E, 0xBC, 0x82, 0x2F, 0xE3, 0xB4}, + /* Col 4 */ {0x8C, 0xFA, 0x47, 0x9B, 0x83, 0xA5, 0x66, 0xD0}, + /* Col 5 */ {0x07, 0xBD, 0x9F, 0x26, 0xC8, 0x31, 0x0F, 0xB8}, + /* Col 6 */ {0xEF, 0x03, 0x95, 0x89, 0xB4, 0x71, 0x61, 0x9D}, + /* Col 7 */ {0x40, 0xBA, 0x97, 0xD5, 0x86, 0x4F, 0xCC, 0xD1}, + /* Col 8 */ {0xD7, 0xA1, 0x54, 0xB1, 0x5E, 0x89, 0xAE, 0x86} +}, +{ /* Row 1 */ + /* Col 0 */ {0x83, 0xF7, 0xA8, 0x2D, 0x7A, 0x44, 0x64, 0xD3}, + /* Col 1 */ {0x3F, 0x2C, 0x4E, 0xAA, 0x71, 0x48, 0x7A, 0xC9}, + /* Col 2 */ {0x17, 0xFF, 0x9E, 0x21, 0x36, 0x90, 0xC7, 0x82}, + /* Col 3 */ {0xBC, 0x5D, 0x9A, 0x5B, 0xEE, 0x7F, 0x42, 0xEB}, + /* Col 4 */ {0x24, 0xF5, 0xDD, 0xF8, 0x7A, 0x77, 0x74, 0xE7}, + /* Col 5 */ {0x3D, 0x70, 0x7C, 0x94, 0xDC, 0x84, 0xAD, 0x95}, + /* Col 6 */ {0x1E, 0x6A, 0xF0, 0x37, 0x52, 0x7B, 0x11, 0xD4}, + /* Col 7 */ {0x62, 0xF5, 0x2B, 0xAA, 0xFC, 0x33, 0xBF, 0xAF}, + /* Col 8 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97} +}, +{ /* Row 2 */ + /* Col 0 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97}, + /* Col 1 */ {0x8E, 0x4A, 0xD0, 0xA9, 0xA7, 0xFF, 0x20, 0xCA}, + /* Col 2 */ {0x4C, 0x97, 0x9D, 0xBF, 0xB8, 0x3D, 0xB5, 0xBE}, + /* Col 3 */ {0x0C, 0x5D, 0x24, 0x30, 0x9F, 0xCA, 0x6D, 0xBD}, + /* Col 4 */ {0x50, 0x14, 0x33, 0xDE, 0xF1, 0x78, 0x95, 0xAD}, + /* Col 5 */ {0x0C, 0x3C, 0xFA, 0xF9, 0xF0, 0xF2, 0x10, 0xC9}, + /* Col 6 */ {0xF4, 0xDA, 0x06, 0xDB, 0xBF, 0x4E, 0x6F, 0xB3}, + /* Col 7 */ {0x9E, 0x08, 0xD1, 0xAE, 0x59, 0x5E, 0xE8, 0xF0}, + /* Col 8 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E} +}, +{ /* Row 3 */ + /* Col 0 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E}, + /* Col 1 */ {0x80, 0x69, 0x26, 0x80, 0x08, 0xF8, 0x49, 0xE7}, + /* Col 2 */ {0x7D, 0x2D, 0x49, 0x54, 0xD0, 0x80, 0x40, 0xC1}, + /* Col 3 */ {0xB6, 0xF2, 0xE6, 0x1B, 0x80, 0x5A, 0x36, 0xB4}, + /* Col 4 */ {0x42, 0xAE, 0x9C, 0x1C, 0xDA, 0x67, 0x05, 0xF6}, + /* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80}, + /* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88}, + /* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88}, + /* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40} +}, +{ /* Row 4 */ + /* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93}, + /* Col 1 */ {0xDC, 0x68, 0x08, 0x99, 0x97, 0xAE, 0xAF, 0x8C}, + /* Col 2 */ {0xC3, 0x0E, 0x01, 0x16, 0x0E, 0x32, 0x06, 0xBA}, + /* Col 3 */ {0xE0, 0x83, 0x01, 0xFA, 0xAB, 0x3E, 0x8F, 0xAC}, + /* Col 4 */ {0x5C, 0xD5, 0x9C, 0xB8, 0x46, 0x9C, 0x7D, 0x84}, + /* Col 5 */ {0xF1, 0xC6, 0xFE, 0x5C, 0x9D, 0xA5, 0x4F, 0xB7}, + /* Col 6 */ {0x58, 0xB5, 0xB3, 0xDD, 0x0E, 0x28, 0xF1, 0xB0}, + /* Col 7 */ {0x5F, 0x30, 0x3B, 0x56, 0x96, 0x45, 0xF4, 0xA1}, + /* Col 8 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8} +}, +}; +static const uint8_t pn_bind[] = { 0x98, 0x88, 0x1B, 0xE4, 0x30, 0x79, 0x03, 0x84 }; /** * Initialize the superbitrf */ void radio_control_impl_init(void) { - // Set the status to uninitialized + // Set the status to uninitialized and set the timer to 0 superbitrf.status = SUPERBITRF_UNINIT; + superbitrf.state = 0; + superbitrf.timer = 0; + superbitrf.packet_count = 0; // Initialize the binding pin gpio_setup_input(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN); + // Initialize the IRQ/DRDY pin + gpio_setup_input(SUPERBITRF_DRDY_PORT, SUPERBITRF_DRDY_PIN); + // Initialize the cyrf6936 chip cyrf6936_init(&superbitrf.cyrf6936, &(SUPERBITRF_SPI_DEV), 1, SUPERBITRF_RST_PORT, SUPERBITRF_RST_PIN); } @@ -95,7 +184,30 @@ void radio_control_impl_init(void) { * The superbitrf on event call */ void superbitrf_event(void) { - // Check the status + uint8_t data_code[16]; + + // Check if the cyrf6936 isn't busy + if(superbitrf.cyrf6936.status != CYRF6936_IDLE) + return; + + // First handle the IRQ + if(gpio_get(SUPERBITRF_DRDY_PORT, SUPERBITRF_DRDY_PIN) == 0) { + // Receive the packet + cyrf6936_read_rx_irq_status_packet(&superbitrf.cyrf6936); + } + + /* Check if it is a valid receive */ + if(superbitrf.cyrf6936.has_packet && (superbitrf.cyrf6936.rx_irq_status & CYRF_RXC_IRQ)) { + superbitrf.packet_count++; + + // Handle the packet received + superbitrf_receive_packet_cb(superbitrf.cyrf6936.rx_status, superbitrf.cyrf6936.rx_packet); + + // Reset the packet receiving + superbitrf.cyrf6936.has_packet = FALSE; + } + + // Check the status of the superbitrf switch(superbitrf.status) { /* When the superbitrf isn't initialized */ @@ -112,18 +224,291 @@ void superbitrf_event(void) { /* When the superbitrf is initializing binding */ case SUPERBITRF_INIT_BINDING: - // Try to write the binding config - if(cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_bind_config, 5)) + /* Switch the different states */ + switch (superbitrf.state) { + case 0: + // Try to write the binding config + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_bind_config, 5); + superbitrf.state++; + break; + case 1: + // Set the data code and channel + memcpy(data_code, pn_codes[0][8], 8); + memcpy(data_code + 8, pn_bind, 8); + cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, 1, pn_codes[0][0], data_code, 0x0000); + superbitrf.status = SUPERBITRF_BINDING; + break; + default: + // Should not happen + superbitrf.state = 0; + break; + } break; + /* When the superbitrf is initializing transfer */ + case SUPERBITRF_INIT_TRANSFER: + // Try to write the transfer config + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4); + superbitrf.status = SUPERBITRF_SYNCING_A; + break; + /* When the superbitrf is in binding mode */ case SUPERBITRF_BINDING: + /* Switch the different states */ + switch (superbitrf.state) { + case 0: + // When there is a timeout + if (superbitrf.timer < get_sys_time_usec()) { + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + superbitrf.state++; + } + break; + case 1: + // Switch channel + superbitrf.channel = (superbitrf.channel + 2) % 0x4F; //TODO fix define + cyrf6936_write(&superbitrf.cyrf6936, CYRF_CHANNEL, superbitrf.channel); + + superbitrf.state++; + break; + case 2: + // Start receiving + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + superbitrf.state++; + break; + default: + // Set the timer + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_BIND_RECV_TIME) % 0xFFFFFFFF; + superbitrf.state = 0; + break; + } + break; + + /* When the receiver is synchronizing with the transmitter */ + case SUPERBITRF_SYNCING_A: + case SUPERBITRF_SYNCING_B: + /* Switch the different states */ + switch (superbitrf.state) { + case 0: + // When there is a timeout + if (superbitrf.timer < get_sys_time_usec()) { + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + superbitrf.state++; + } + break; + case 1: + // Switch channel, sop code, data code and crc + superbitrf.channel = (superbitrf.channel + 1) % 0x4F; //TODO fix define + superbitrf.crc_seed = ~ superbitrf.crc_seed; + + cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channel, + pn_codes[superbitrf.channel % 5][superbitrf.sop_col], + pn_codes[superbitrf.channel % 5][superbitrf.data_col], + superbitrf.crc_seed); + + superbitrf.state++; + break; + case 2: + // Start receiving + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + superbitrf.state++; + break; + default: + // Set the timer + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_SYNC_RECV_TIME) % 0xFFFFFFFF; + superbitrf.state = 0; + break; + } + break; + + /* Normal transfer mode */ + case SUPERBITRF_TRANSFER: + /* Switch the different states */ + switch (superbitrf.state) { + case 0: + // When there is a timeout + if (superbitrf.timer < get_sys_time_usec()) + superbitrf.status = SUPERBITRF_SYNCING_A; + break; + case 1: + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + superbitrf.state++; + break; + case 2: + // Switch channel, sop code, data code and crc + superbitrf.channel_idx = (superbitrf.channel_idx + 1) %2; + superbitrf.channel = superbitrf.channels[superbitrf.channel_idx]; + superbitrf.crc_seed = ~ superbitrf.crc_seed; + + cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channel, + pn_codes[superbitrf.channel % 5][superbitrf.sop_col], + pn_codes[superbitrf.channel % 5][superbitrf.data_col], + superbitrf.crc_seed); + + superbitrf.state++; + break; + case 3: + // Start receiving + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + superbitrf.state++; + break; + default: + // Set the timer + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_RECV_TIME) % 0xFFFFFFFF; + superbitrf.state = 0; + break; + } break; /* Should not come here */ default: break; } - +} + +/** + * When we receive a packet this callback is called + */ +static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[]) { + int i; + uint16_t sum; + + /* Switch on the status of the superbitRF */ + switch (superbitrf.status) { + + /* When we are in binding mode */ + case SUPERBITRF_BINDING: + // Check if the MFG id is exactly the same + if (packet[0] != packet[4] || packet[1] != packet[5] || packet[2] != packet[6] || packet[3] != packet[7]) { + // Start receiving without changing channel + superbitrf.state = 2; + break; + } + + // Calculate the first sum + sum = 384 - 0x10; + for (i = 0; i < 8; i++) + sum += packet[i]; + + // Check the first sum + if (packet[8] != sum >> 8 || packet[9] != (sum & 0xFF)) { + // Start receiving without changing channel + superbitrf.state = 2; + break; + } + + // Calculate second sum + for (i = 8; i < 14; i++) + sum += packet[i]; + + // Check the second sum + if (packet[14] != sum >> 8 || packet[15] != (sum & 0xFF)) { + // Start receiving without changing channel + superbitrf.state = 2; + break; + } + + // Update the mfg id, number of channels and protocol + superbitrf.bind_mfg_id[0] = ~packet[0]; + superbitrf.bind_mfg_id[1] = ~packet[1]; + superbitrf.bind_mfg_id[2] = ~packet[2]; + superbitrf.bind_mfg_id[3] = ~packet[3]; + superbitrf.num_channels = packet[11]; + superbitrf.protocol = packet[12]; + superbitrf.resolution = (superbitrf.protocol & 0x10)>>4; + + // Calculate some values based on the bind MFG id + superbitrf.crc_seed = ~((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1]); + superbitrf.sop_col = (superbitrf.bind_mfg_id[0] + superbitrf.bind_mfg_id[1] + superbitrf.bind_mfg_id[2] + 2) & 0x07; + superbitrf.data_col = 7 - superbitrf.sop_col; + + // Update the status of the receiver + superbitrf.state = 0; + superbitrf.status = SUPERBITRF_INIT_TRANSFER; + break; + + /* When we receive a packet during syncing first channel A */ + case SUPERBITRF_SYNCING_A: + // Check the MFG id + if(packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + break; + + superbitrf.channels[0] = superbitrf.channel; + superbitrf.channels[1] = superbitrf.channel; + + superbitrf.status = SUPERBITRF_SYNCING_B; //TODO: Fix it + break; + + /* When we receive a packet during syncing second channel B */ + case SUPERBITRF_SYNCING_B: + // Check the MFG id + if(packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + break; + + // Set the channel + if (superbitrf.crc_seed == ~((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { + superbitrf.channels[0] = superbitrf.channel; + superbitrf.channel_idx = 0; + } + else { + superbitrf.channels[1] = superbitrf.channel; + superbitrf.channel_idx = 1; + } + + // When the channels aren't the same go to transfer mode + if(superbitrf.channels[1] != superbitrf.channels[0]) { + superbitrf.state = 1; + superbitrf.status = SUPERBITRF_TRANSFER; + } + break; + + /* When we receive a packet during transfer */ + case SUPERBITRF_TRANSFER: + // Check the MFG id + if(packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + break; + + // Parse the packet + superbitrf_radio_to_channels(&packet[2], superbitrf.num_channels, superbitrf.resolution, superbitrf.rc_values); + superbitrf.frame_available = TRUE; + + // Go to next receive + superbitrf.state = 1; + break; + + /* Should not come here */ + default: + break; + } +} + +/** + * Parse a radio channel packet + */ +static inline void superbitrf_radio_to_channels(char* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels) { + int i; + uint8_t bit_shift = (is_11bit)? 11:10; + int16_t value_max = (is_11bit)? 0x07FF: 0x03FF; + + for (i=0; i<7; i++) { + const int16_t tmp = ((data[2*i]<<8) + data[2*i+1]) & 0x7FFF; + const uint8_t chan = (tmp >> bit_shift) & 0x0F; + const int16_t val = (tmp&value_max); + + if(chan < nb_channels) { + channels[chan] = val; + + // Scale the channel + if(is_11bit) { + channels[chan] -= 0x400; + channels[chan] *= MAX_PPRZ/0x2AC; + } else { + channels[chan] -= 0x200; + channels[chan] *= MAX_PPRZ/0x156; + } + } + } } diff --git a/sw/airborne/subsystems/radio_control/superbitrf.h b/sw/airborne/subsystems/radio_control/superbitrf.h index a9f7e20dcf..65a6771b6c 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf.h +++ b/sw/airborne/subsystems/radio_control/superbitrf.h @@ -17,7 +17,6 @@ * along with paparazzi; see the file COPYING. If not, write to * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. - * */ /** @@ -58,29 +57,83 @@ #define RADIO_MODE RADIO_GEAR #endif +/* The timings in microseconds */ +#define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ +#define SUPERBITRF_SYNC_RECV_TIME 12000 /**< The time to wait for a sync packet on a channel in microseconds */ +#define SUPERBITRF_RECV_TIME 24000 /**< The time to wait for a transfer packet on a channel in microseconds */ + /* The different statuses the superbitRF can be in */ enum SuperbitRFStatus { SUPERBITRF_UNINIT, /**< The chip isn't initialized */ SUPERBITRF_INIT_BINDING, /**< The chip is initializing binding mode */ SUPERBITRF_INIT_TRANSFER, /**< The chip is initializing transfer mode */ SUPERBITRF_BINDING, /**< The chip is in binding mode */ + SUPERBITRF_SYNCING_A, /**< The chip is in synchronizing mode for channel A */ + SUPERBITRF_SYNCING_B, /**< The chip is in synchronizing mode for channel B */ SUPERBITRF_TRANSFER, /**< The chip is in transfer mode */ }; +/* The different resolutions a transmitter can be in */ +enum dsm_resolution { + SUPERBITRF_10_BIT_RESOLUTION = 0x00, /**< The transmitter has a 10 bit resolution */ + SUPERBITRF_11_BIT_RESOLUTION = 0x01, /**< The transmitter has a 11 bit resolution */ +}; + /* The superbitrf structure */ struct SuperbitRF { struct Cyrf6936 cyrf6936; /**< The cyrf chip used */ volatile enum SuperbitRFStatus status; /**< The status of the superbitRF */ + uint8_t state; /**< The states each status can be in */ + uint32_t timer; /**< The timer in usec */ + + uint8_t channels[23]; /**< The channels used for DSM2/DSMX */ + uint8_t channel_idx; /**< The current channel index */ + uint8_t channel; /**< The current channel number */ + uint32_t packet_count; /**< How many packets are received(also the invalid) */ + + uint8_t bind_mfg_id[4]; /**< The MFG id where the receiver is bound to */ + uint8_t num_channels; /**< The number of channels the transmitter has */ + uint8_t protocol; /**< The protocol the transmitter uses */ + volatile enum dsm_resolution resolution; /**< The resolution that the transmitter has */ + uint16_t crc_seed; /**< The CRC seed that is calculated with the bind MFG id */ + uint8_t sop_col; /**< The sop code column number calculated with the bind MFG id */ + uint8_t data_col; /**< The data code column number calculated with the bind MFG id */ + + bool_t frame_available; /**< When a frame is available */ + int16_t rc_values[14]; /**< The rc values from the packet */ }; /* The superbitrf functions and structures */ extern struct SuperbitRF superbitrf; void superbitrf_event(void); +/* Macro that normalize superbitrf rc_values to radio values */ +#define NormalizeRcDl(_in, _out, _count) { \ + uint8_t i; \ + for(i = 0; i < _count; i++) { \ + if(i == RADIO_THROTTLE) { \ + _out[i] = (_in[i] + MAX_PPRZ) / 2; \ + Bound(_out[i], 0, MAX_PPRZ); \ + } else { \ + _out[i] = -_in[i]; \ + Bound(_out[i], MIN_PPRZ, MAX_PPRZ); \ + } \ + } \ +} + /* The radio control event handler */ -#define RadioControlEvent(_received_frame_handler) { \ - cyrf6936_event(&superbitrf.cyrf6936); \ - superbitrf_event(); \ +#define RadioControlEvent(_received_frame_handler) { \ + cyrf6936_event(&superbitrf.cyrf6936); \ + superbitrf_event(); \ + if(superbitrf.frame_available) { \ + radio_control.frame_cpt++; \ + radio_control.time_since_last_frame = 0; \ + radio_control.radio_ok_cpt = 0; \ + radio_control.status = RC_OK; \ + NormalizeRcDl(superbitrf.rc_values,radio_control.values); \ + _received_frame_handler(); \ + superbitrf.frame_available = FALSE; \ + } \ } #endif /* RADIO_CONTROL_SUPERBITRF_H */ From 7c69924c1c94d29bad5e105b152a2fdc147b138b Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 3 Jul 2013 17:20:41 +0200 Subject: [PATCH 162/309] [superbitrf] Less RC Lost and fixed message Implemented to make it only resyncing when it lost 2 packets of data. Also fixed the message to show the correct status of the CYRF6936. --- conf/messages.xml | 2 +- sw/airborne/subsystems/radio_control/superbitrf.c | 11 ++++++++++- sw/airborne/subsystems/radio_control/superbitrf.h | 1 + 3 files changed, 12 insertions(+), 2 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index 6c9b867c8c..6d9c56b387 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -605,7 +605,7 @@ - + diff --git a/sw/airborne/subsystems/radio_control/superbitrf.c b/sw/airborne/subsystems/radio_control/superbitrf.c index 510a16ee0b..8ccd83521f 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf.c +++ b/sw/airborne/subsystems/radio_control/superbitrf.c @@ -329,8 +329,16 @@ void superbitrf_event(void) { switch (superbitrf.state) { case 0: // When there is a timeout - if (superbitrf.timer < get_sys_time_usec()) + if (superbitrf.timer < get_sys_time_usec()) { + superbitrf.timeouts++; + superbitrf.state++; + } + + // We really lost it + if(superbitrf.timeouts > 1) { + superbitrf.state = 0; superbitrf.status = SUPERBITRF_SYNCING_A; + } break; case 1: // Abort the receive @@ -477,6 +485,7 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] // Go to next receive superbitrf.state = 1; + superbitrf.timeouts = 0; break; /* Should not come here */ diff --git a/sw/airborne/subsystems/radio_control/superbitrf.h b/sw/airborne/subsystems/radio_control/superbitrf.h index 65a6771b6c..d6d408f7b2 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf.h +++ b/sw/airborne/subsystems/radio_control/superbitrf.h @@ -85,6 +85,7 @@ struct SuperbitRF { volatile enum SuperbitRFStatus status; /**< The status of the superbitRF */ uint8_t state; /**< The states each status can be in */ uint32_t timer; /**< The timer in usec */ + uint8_t timeouts; /**< The amount of timeouts */ uint8_t channels[23]; /**< The channels used for DSM2/DSMX */ uint8_t channel_idx; /**< The current channel index */ From 66c80469a431e7b1443dbf772ebfda695e464117 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 9 Jul 2013 16:17:44 +0200 Subject: [PATCH 163/309] [superbitrf] Downlink is now functional Still needs some extensive testing to make it more relaible. --- .../quadrotor_lisa_m_2_pwm_spektrum.xml | 44 ++--- ...e => radio_control_superbitrf_rc.makefile} | 7 +- .../shared/telemetry_superbitrf.makefile | 11 ++ conf/messages.xml | 4 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 8 +- sw/airborne/peripherals/cyrf6936.c | 65 +++++- sw/airborne/peripherals/cyrf6936.h | 9 +- sw/airborne/subsystems/datalink/datalink.h | 3 +- sw/airborne/subsystems/datalink/downlink.h | 1 + .../{radio_control => datalink}/superbitrf.c | 187 +++++++++++++----- .../{radio_control => datalink}/superbitrf.h | 94 +++------ .../subsystems/radio_control/superbitrf_rc.c | 37 ++++ .../subsystems/radio_control/superbitrf_rc.h | 89 +++++++++ 13 files changed, 406 insertions(+), 153 deletions(-) rename conf/firmwares/subsystems/shared/{radio_control_superbitrf.makefile => radio_control_superbitrf_rc.makefile} (57%) create mode 100644 conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile rename sw/airborne/subsystems/{radio_control => datalink}/superbitrf.c (75%) rename sw/airborne/subsystems/{radio_control => datalink}/superbitrf.h (55%) create mode 100644 sw/airborne/subsystems/radio_control/superbitrf_rc.c create mode 100644 sw/airborne/subsystems/radio_control/superbitrf_rc.h diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index 3244ea3474..4d08f9e5ec 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -12,7 +12,7 @@ - + @@ -28,7 +28,7 @@ - + @@ -39,10 +39,10 @@ - - - - + + + + @@ -59,9 +59,9 @@ - - - + + +
@@ -88,7 +88,7 @@ - +
@@ -153,22 +153,22 @@ - - - + + + - - - + + + - - - + + + - - - + + +
diff --git a/conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile similarity index 57% rename from conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile rename to conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile index 791751efde..3774d22f3b 100644 --- a/conf/firmwares/subsystems/shared/radio_control_superbitrf.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile @@ -2,13 +2,14 @@ # Makefile for shared radio_control superbitrf subsystem # -ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE_SUPERBITRF -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/superbitrf.h\" -ap.CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE1 +ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE_SUPERBITRF -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/superbitrf_rc.h\" +ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI1 -DUSE_SPI_SLAVE1 ifneq ($(RADIO_CONTROL_LED),none) ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) endif ap.srcs += peripherals/cyrf6936.c \ + $(SRC_SUBSYSTEMS)/datalink/superbitrf.c\ $(SRC_SUBSYSTEMS)/radio_control.c \ - $(SRC_SUBSYSTEMS)/radio_control/superbitrf.c + $(SRC_SUBSYSTEMS)/radio_control/superbitrf_rc.c diff --git a/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile b/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile new file mode 100644 index 0000000000..20781731ec --- /dev/null +++ b/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile @@ -0,0 +1,11 @@ +# +# The superbitRF module as telemetry downlink/uplink +# +# + +ap.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=SuperbitRF +ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=SUPERBITRF +ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI1 -DUSE_SPI_SLAVE1 +ap.srcs += peripherals/cyrf6936.c +ap.srcs += subsystems/datalink/downlink.c subsystems/datalink/superbitrf.c subsystems/datalink/pprz_transport.c +ap.srcs += $(SRC_FIRMWARE)/datalink.c $(SRC_FIRMWARE)/telemetry.c diff --git a/conf/messages.xml b/conf/messages.xml index 6d9c56b387..f2199afb15 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -605,8 +605,10 @@ - + + + diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index afed5e1137..80f5ab8366 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -134,14 +134,16 @@ #define PERIODIC_SEND_PPM(_trans, _dev) {} #endif -#ifdef RADIO_CONTROL_TYPE_SUPERBITRF -#include "subsystems/radio_control/superbitrf.h" +#ifdef USE_SUPERBITRF +#include "subsystems/datalink/superbitrf.h" #define PERIODIC_SEND_SUPERBITRF(_trans, _dev) { \ DOWNLINK_SEND_SUPERBITRF(_trans, _dev, \ &superbitrf.status, \ &superbitrf.cyrf6936.status, \ &superbitrf.packet_count, \ - &superbitrf.packet_count, \ + &superbitrf.timing1, \ + &superbitrf.timing2, \ + &superbitrf.bind_mfg_id32, \ 6, \ superbitrf.cyrf6936.mfg_id);} #else diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 996285c5f2..1ea90971df 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -48,7 +48,7 @@ void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_ /* Set spi_peripheral and the status */ cyrf->spi_p = spi_p; cyrf->status = CYRF6936_UNINIT; - cyrf->has_packet = FALSE; + cyrf->has_irq = FALSE; /* Set the spi transaction */ cyrf->spi_t.cpol = SPICpolIdleLow; @@ -191,11 +191,15 @@ void cyrf6936_event(struct Cyrf6936 *cyrf) { case 0: // Read the receive IRQ status cyrf6936_read_register(cyrf, CYRF_RX_IRQ_STATUS); break; - case 1: // Read the receive status + case 1: // Read the send IRQ status cyrf->rx_irq_status = cyrf->input_buf[1]; + cyrf6936_read_register(cyrf, CYRF_TX_IRQ_STATUS); + break; + case 2: // Read the receive status + cyrf->tx_irq_status = cyrf->input_buf[1]; cyrf6936_read_register(cyrf, CYRF_RX_STATUS); break; - case 2: // Read the receive packet + case 3: // Read the receive packet cyrf->rx_status = cyrf->input_buf[1]; cyrf6936_read_block(cyrf, CYRF_RX_BUFFER, 16); break; @@ -204,7 +208,35 @@ void cyrf6936_event(struct Cyrf6936 *cyrf) { for(i = 0; i < 16; i++) cyrf->rx_packet[i] = cyrf->input_buf[i+1]; - cyrf->has_packet = TRUE; + cyrf->has_irq = TRUE; + cyrf->status = CYRF6936_IDLE; + break; + } + break; + + /* The CYRF6936 is busy sending a packet */ + case CYRF6936_SEND: + // When the last transaction isn't failed send the next + if(cyrf->spi_t.status != SPITransFailed) + cyrf->buffer_idx++; + + cyrf->spi_t.status = SPITransDone; + + // Switch for the different states + switch (cyrf->buffer_idx) { + case 0: // Set the packet length + cyrf6936_write_register(cyrf, CYRF_TX_LENGTH, cyrf->buffer[0]); + break; + case 1: // Clear the TX buffer + cyrf6936_write_register(cyrf, CYRF_TX_CTRL, CYRF_TX_CLR); + break; + case 2: // Write the send packet + cyrf6936_write_block(cyrf, CYRF_TX_BUFFER, &cyrf->buffer[1], 16); + break; + case 3: // Send the packet + cyrf6936_write_register(cyrf, CYRF_TX_CTRL, CYRF_TX_GO | CYRF_TXC_IRQEN | CYRF_TXE_IRQEN); + break; + default: cyrf->status = CYRF6936_IDLE; break; } @@ -358,3 +390,28 @@ bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf) { return TRUE; } + +/** + * Send a packet with a certain length + */ +bool_t cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t length) { + int i; + + /* Check if the cyrf6936 isn't busy */ + if(cyrf->status != CYRF6936_IDLE) + return FALSE; + + // Set the status + cyrf->status = CYRF6936_SEND; + + // Copy the length and the data + cyrf->buffer[0] = length; + for(i = 0; i < length; i++) + cyrf->buffer[i+1] = data[i]; + + /* Try to set the packet length */ + cyrf->buffer_idx = 0; + cyrf6936_write_register(cyrf, CYRF_TX_LENGTH, cyrf->buffer[0]); + + return TRUE; +} diff --git a/sw/airborne/peripherals/cyrf6936.h b/sw/airborne/peripherals/cyrf6936.h index 7a7943f566..2336257a02 100644 --- a/sw/airborne/peripherals/cyrf6936.h +++ b/sw/airborne/peripherals/cyrf6936.h @@ -20,7 +20,7 @@ */ /** - * @file peripherals/yrf6936c.h + * @file peripherals/cyrf6936.h * Driver for the cyrf6936 2.4GHz radio chip */ @@ -40,7 +40,8 @@ enum Cyrf6936Status { CYRF6936_MULTIWRITE, /**< The chip is writing multiple registers */ CYRF6936_DATA_CODE, /**< The chip is writing a data code */ CYRF6936_CHAN_SOP_DATA_CRC, /**< The chip is setting the channel, SOP code, DATA code and the CRC seed */ - CYRF6936_RX_IRQ_STATUS_PACKET /**< The chip is getting the receive irq status, receive status and the receive packet */ + CYRF6936_RX_IRQ_STATUS_PACKET, /**< The chip is getting the receive irq status, receive status and the receive packet */ + CYRF6936_SEND /**< The chip is busy sending a packet */ }; /* The structure for the cyrf6936 chip that handles all the buffers and requests */ @@ -55,8 +56,9 @@ struct Cyrf6936 { uint8_t buffer_length; /**< The length of the buffer used for MULTIWRITE */ uint8_t buffer_idx; /**< The index of the buffer used for MULTIWRITE and used as sub-status for other statuses */ - bool_t has_packet; /**< When the CYRF6936 is done reading the receive registers */ + bool_t has_irq; /**< When the CYRF6936 is done reading the irq */ uint8_t mfg_id[6]; /**< The manufacturer id of the CYRF6936 chip */ + uint8_t tx_irq_status; /**< The last send interrupt status */ uint8_t rx_irq_status; /**< The last receive interrupt status */ uint8_t rx_status; /**< The last receive status */ uint8_t rx_packet[16]; /**< The last received packet */ @@ -69,5 +71,6 @@ bool_t cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t d bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length); bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[], const uint8_t data_code[], const uint16_t crc_seed); bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf); +bool_t cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t length); #endif /* CYRF6936_H */ diff --git a/sw/airborne/subsystems/datalink/datalink.h b/sw/airborne/subsystems/datalink/datalink.h index 1259ba9ff1..990f51cddb 100644 --- a/sw/airborne/subsystems/datalink/datalink.h +++ b/sw/airborne/subsystems/datalink/datalink.h @@ -46,6 +46,7 @@ #define PPRZ 1 #define XBEE 2 #define UDP 3 +#define SUPERBITRF 4 EXTERN bool_t dl_msg_available; /** Flag provided to control calls to ::dl_parse_msg. NOT used in this module*/ @@ -90,7 +91,7 @@ EXTERN void dl_parse_msg(void); #elif defined DATALINK && DATALINK == UDP #define DatalinkEvent() { \ - UdpCheckAndParse(); \ + UdpCheckAndParse(); \ DlCheckAndParse(); \ } diff --git a/sw/airborne/subsystems/datalink/downlink.h b/sw/airborne/subsystems/datalink/downlink.h index 39883053b6..50c8e562c9 100644 --- a/sw/airborne/subsystems/datalink/downlink.h +++ b/sw/airborne/subsystems/datalink/downlink.h @@ -50,6 +50,7 @@ #include "subsystems/datalink/pprz_transport.h" #include "subsystems/datalink/xbee.h" #include "subsystems/datalink/w5100.h" +#include "subsystems/datalink/superbitrf.h" #if USE_AUDIO_TELEMETRY #include "subsystems/datalink/audio_telemetry.h" #endif diff --git a/sw/airborne/subsystems/radio_control/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c similarity index 75% rename from sw/airborne/subsystems/radio_control/superbitrf.c rename to sw/airborne/subsystems/datalink/superbitrf.c index 8ccd83521f..87b8d332e1 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -10,24 +10,24 @@ * * paparazzi is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to + * along with paparazzi; see the file COPYING. If not, write to * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. */ /** - * @file subsystems/radio_control/superbitrf.c - * DSM2 and DSMX implementation for the cyrf6936 2.4GHz radio chip trough SPI + * @file subsystems/datalink/superbitrf.c + * DSM2 and DSMX datalink implementation for the cyrf6936 2.4GHz radio chip trough SPI */ -#include "superbitrf.h" +#include "subsystems/datalink/superbitrf.h" #include -#include "subsystems/radio_control.h" +#include "paparazzi.h" #include "mcu_periph/spi.h" #include "mcu_periph/sys_time.h" #include @@ -57,8 +57,9 @@ struct SuperbitRF superbitrf; /* The internal functions */ -static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[]); -static inline void superbitrf_radio_to_channels(char* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels); +static inline void superbitrf_radio_to_channels(uint8_t* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels); +static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, uint8_t packet[]); +static inline void superbitrf_send_packet_cb(bool_t error); /* The startup configuration for the cyrf6936 */ static const uint8_t cyrf_stratup_config[][2] = { @@ -163,13 +164,17 @@ static const uint8_t pn_bind[] = { 0x98, 0x88, 0x1B, 0xE4, 0x30, 0x79, 0x03, 0x8 /** * Initialize the superbitrf */ -void radio_control_impl_init(void) { +void superbitrf_init(void) { // Set the status to uninitialized and set the timer to 0 superbitrf.status = SUPERBITRF_UNINIT; superbitrf.state = 0; superbitrf.timer = 0; superbitrf.packet_count = 0; + // Setup the transmit buffer + superbitrf.tx_insert_idx = 0; + superbitrf.tx_extract_idx = 0; + // Initialize the binding pin gpio_setup_input(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN); @@ -184,27 +189,38 @@ void radio_control_impl_init(void) { * The superbitrf on event call */ void superbitrf_event(void) { - uint8_t data_code[16]; + uint8_t i, packet_size, data_code[16], tx_packet[16]; - // Check if the cyrf6936 isn't busy + // Check if the cyrf6936 isn't busy and the uperbitrf is initialized if(superbitrf.cyrf6936.status != CYRF6936_IDLE) return; - // First handle the IRQ - if(gpio_get(SUPERBITRF_DRDY_PORT, SUPERBITRF_DRDY_PIN) == 0) { - // Receive the packet - cyrf6936_read_rx_irq_status_packet(&superbitrf.cyrf6936); - } + // When the device is initialized handle the IRQ + if(superbitrf.status != SUPERBITRF_UNINIT) { + // First handle the IRQ + if(gpio_get(SUPERBITRF_DRDY_PORT, SUPERBITRF_DRDY_PIN) == 0) { + // Receive the packet + cyrf6936_read_rx_irq_status_packet(&superbitrf.cyrf6936); + } - /* Check if it is a valid receive */ - if(superbitrf.cyrf6936.has_packet && (superbitrf.cyrf6936.rx_irq_status & CYRF_RXC_IRQ)) { - superbitrf.packet_count++; + /* Check if it is a valid receive */ + if(superbitrf.cyrf6936.has_irq && (superbitrf.cyrf6936.rx_irq_status & CYRF_RXC_IRQ)) { + // Handle the packet received + superbitrf_receive_packet_cb((superbitrf.cyrf6936.rx_irq_status & CYRF_RXE_IRQ), superbitrf.cyrf6936.rx_status, superbitrf.cyrf6936.rx_packet); + superbitrf.packet_count++; - // Handle the packet received - superbitrf_receive_packet_cb(superbitrf.cyrf6936.rx_status, superbitrf.cyrf6936.rx_packet); + // Reset the packet receiving + superbitrf.cyrf6936.has_irq = FALSE; + } - // Reset the packet receiving - superbitrf.cyrf6936.has_packet = FALSE; + /* Check if it has a valid send */ + if(superbitrf.cyrf6936.has_irq && (superbitrf.cyrf6936.tx_irq_status & CYRF_TXC_IRQ)) { + // Handle the send packet + superbitrf_send_packet_cb((superbitrf.cyrf6936.rx_irq_status & CYRF_TXE_IRQ)); + + // Reset the packet receiving + superbitrf.cyrf6936.has_irq = FALSE; + } } // Check the status of the superbitrf @@ -248,9 +264,9 @@ void superbitrf_event(void) { /* When the superbitrf is initializing transfer */ case SUPERBITRF_INIT_TRANSFER: - // Try to write the transfer config - cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4); - superbitrf.status = SUPERBITRF_SYNCING_A; + // Try to write the transfer config + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4); + superbitrf.status = SUPERBITRF_SYNCING_A; break; /* When the superbitrf is in binding mode */ @@ -259,20 +275,29 @@ void superbitrf_event(void) { switch (superbitrf.state) { case 0: // When there is a timeout - if (superbitrf.timer < get_sys_time_usec()) { - // Abort the receive - cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + if (superbitrf.timer < get_sys_time_usec()) superbitrf.state++; - } break; case 1: - // Switch channel - superbitrf.channel = (superbitrf.channel + 2) % 0x4F; //TODO fix define - cyrf6936_write(&superbitrf.cyrf6936, CYRF_CHANNEL, superbitrf.channel); + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); superbitrf.state++; break; case 2: + // Switch channel + superbitrf.channel = (superbitrf.channel + 2) % 0x4F; //TODO fix define + cyrf6936_write(&superbitrf.cyrf6936, CYRF_CHANNEL, superbitrf.channel); + + superbitrf.state += 2; // Already aborted + break; + case 3: + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + + superbitrf.state++; + break; + case 4: // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; @@ -292,16 +317,18 @@ void superbitrf_event(void) { switch (superbitrf.state) { case 0: // When there is a timeout - if (superbitrf.timer < get_sys_time_usec()) { - // Abort the receive - cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + if (superbitrf.timer < get_sys_time_usec()) superbitrf.state++; - } break; case 1: + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + superbitrf.state++; + break; + case 2: // Switch channel, sop code, data code and crc - superbitrf.channel = (superbitrf.channel + 1) % 0x4F; //TODO fix define - superbitrf.crc_seed = ~ superbitrf.crc_seed; + superbitrf.channel = (superbitrf.channel + 1) % 0x62; //TODO fix define + superbitrf.crc_seed = ~superbitrf.crc_seed; cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channel, pn_codes[superbitrf.channel % 5][superbitrf.sop_col], @@ -310,7 +337,7 @@ void superbitrf_event(void) { superbitrf.state++; break; - case 2: + case 3: // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; @@ -346,6 +373,24 @@ void superbitrf_event(void) { superbitrf.state++; break; case 2: + // Send a packet + tx_packet[0] = ~superbitrf.bind_mfg_id[2]; + tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1; + packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); + if(packet_size > 14) + packet_size = 14; + + for(i = 0; i < packet_size; i++) + tx_packet[i+2] = superbitrf.tx_buffer[(superbitrf.tx_extract_idx+i) %128]; + + cyrf6936_send(&superbitrf.cyrf6936, tx_packet, packet_size+2); + superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; + superbitrf.state++; + break; + case 3: + //TODO: check timeout? (Waiting for send) + break; + case 4: // Switch channel, sop code, data code and crc superbitrf.channel_idx = (superbitrf.channel_idx + 1) %2; superbitrf.channel = superbitrf.channels[superbitrf.channel_idx]; @@ -358,7 +403,7 @@ void superbitrf_event(void) { superbitrf.state++; break; - case 3: + case 5: // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; @@ -380,7 +425,7 @@ void superbitrf_event(void) { /** * When we receive a packet this callback is called */ -static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[]) { +static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, uint8_t packet[]) { int i; uint16_t sum; @@ -392,7 +437,7 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] // Check if the MFG id is exactly the same if (packet[0] != packet[4] || packet[1] != packet[5] || packet[2] != packet[6] || packet[3] != packet[7]) { // Start receiving without changing channel - superbitrf.state = 2; + superbitrf.state = 3; break; } @@ -404,7 +449,7 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] // Check the first sum if (packet[8] != sum >> 8 || packet[9] != (sum & 0xFF)) { // Start receiving without changing channel - superbitrf.state = 2; + superbitrf.state = 3; break; } @@ -415,7 +460,7 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] // Check the second sum if (packet[14] != sum >> 8 || packet[15] != (sum & 0xFF)) { // Start receiving without changing channel - superbitrf.state = 2; + superbitrf.state = 3; break; } @@ -424,6 +469,8 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] superbitrf.bind_mfg_id[1] = ~packet[1]; superbitrf.bind_mfg_id[2] = ~packet[2]; superbitrf.bind_mfg_id[3] = ~packet[3]; + superbitrf.bind_mfg_id32 = ((superbitrf.bind_mfg_id[3] &0xFF) << 24 | (superbitrf.bind_mfg_id[2] &0xFF) << 16 | + (superbitrf.bind_mfg_id[1] &0xFF) << 8 | (superbitrf.bind_mfg_id[0] &0xFF)) &0xFFFFFFFF; superbitrf.num_channels = packet[11]; superbitrf.protocol = packet[12]; superbitrf.resolution = (superbitrf.protocol & 0x10)>>4; @@ -441,23 +488,34 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] /* When we receive a packet during syncing first channel A */ case SUPERBITRF_SYNCING_A: // Check the MFG id - if(packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + if((error && !(status & CYRF_BAD_CRC)) || + packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) break; + // If the CRC is wrong invert + if (error && (status & CYRF_BAD_CRC)) + superbitrf.crc_seed = ~superbitrf.crc_seed; + superbitrf.channels[0] = superbitrf.channel; superbitrf.channels[1] = superbitrf.channel; - superbitrf.status = SUPERBITRF_SYNCING_B; //TODO: Fix it + superbitrf.state = 1; + superbitrf.status = SUPERBITRF_SYNCING_B; break; /* When we receive a packet during syncing second channel B */ case SUPERBITRF_SYNCING_B: // Check the MFG id - if(packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + if((error && !(status & CYRF_BAD_CRC)) || + packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) break; + // If the CRC is wrong invert + if (error && (status & CYRF_BAD_CRC)) + superbitrf.crc_seed = ~superbitrf.crc_seed; + // Set the channel - if (superbitrf.crc_seed == ~((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { + if(superbitrf.crc_seed == ~((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { superbitrf.channels[0] = superbitrf.channel; superbitrf.channel_idx = 0; } @@ -470,6 +528,7 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] if(superbitrf.channels[1] != superbitrf.channels[0]) { superbitrf.state = 1; superbitrf.status = SUPERBITRF_TRANSFER; + superbitrf.timeouts = 0; } break; @@ -481,7 +540,13 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] // Parse the packet superbitrf_radio_to_channels(&packet[2], superbitrf.num_channels, superbitrf.resolution, superbitrf.rc_values); - superbitrf.frame_available = TRUE; + superbitrf.rc_frame_available = TRUE; + + // Calculate the timing (seperately for the channel switches) + if(superbitrf.channels[0] == superbitrf.channel) + superbitrf.timing1 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_TIME); + else + superbitrf.timing2 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_TIME); // Go to next receive superbitrf.state = 1; @@ -494,10 +559,27 @@ static inline void superbitrf_receive_packet_cb(uint8_t status, uint8_t packet[] } } +static inline void superbitrf_send_packet_cb(bool_t error) { + /* Switch on the status of the superbitRF */ + switch (superbitrf.status) { + + /* When we are in transfer mode */ + case SUPERBITRF_TRANSFER: + // When we successfully or unsuccessfully send a packet + if(superbitrf.state == 3) + superbitrf.state++; + break; + + /* Should not come here */ + default: + break; + } +} + /** * Parse a radio channel packet */ -static inline void superbitrf_radio_to_channels(char* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels) { +static inline void superbitrf_radio_to_channels(uint8_t* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels) { int i; uint8_t bit_shift = (is_11bit)? 11:10; int16_t value_max = (is_11bit)? 0x07FF: 0x03FF; @@ -521,3 +603,6 @@ static inline void superbitrf_radio_to_channels(char* data, uint8_t nb_channels, } } } + + + diff --git a/sw/airborne/subsystems/radio_control/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h similarity index 55% rename from sw/airborne/subsystems/radio_control/superbitrf.h rename to sw/airborne/subsystems/datalink/superbitrf.h index d6d408f7b2..d3c965c825 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -10,52 +10,27 @@ * * paparazzi is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to + * along with paparazzi; see the file COPYING. If not, write to * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. */ /** - * @file subsystems/radio_control/superbitrf.h - * DSM2 and DSMX implementation for the cyrf6936 2.4GHz radio chip trough SPI + * @file subsystems/datalink/superbitrf.h + * DSM2 and DSMX datalink implementation for the cyrf6936 2.4GHz radio chip trough SPI */ -#ifndef RADIO_CONTROL_SUPERBITRF_H -#define RADIO_CONTROL_SUPERBITRF_H +#ifndef DATALINK_SUPERBITRF_H +#define DATALINK_SUPERBITRF_H -#include "peripherals/cyrf6936.h" #include "mcu_periph/gpio.h" - -/* Theoretically you could have 14 channel over DSM2/DSMX */ -#ifndef RADIO_CONTROL_NB_CHANNEL -#define RADIO_CONTROL_NB_CHANNEL 14 -#endif - -/* The channel ordering is always the same for DSM2 and DSMX */ -#define RADIO_THROTTLE 0 -#define RADIO_ROLL 1 -#define RADIO_PITCH 2 -#define RADIO_YAW 3 -#define RADIO_GEAR 4 -#define RADIO_FLAP 5 -#define RADIO_AUX1 5 -#define RADIO_AUX2 6 -#define RADIO_AUX3 7 -#define RADIO_AUX4 8 -#define RADIO_AUX5 9 -#define RADIO_AUX6 10 -#define RADIO_AUX7 11 -#define RADIO_AUX8 12 -#define RADIO_AUX9 13 - -/* Map the MODE default to the gear switch */ -#ifndef RADIO_MODE -#define RADIO_MODE RADIO_GEAR -#endif +#include "peripherals/cyrf6936.h" +#include "subsystems/datalink/datalink.h" +#include "subsystems/datalink/pprz_transport.h" /* The timings in microseconds */ #define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ @@ -84,7 +59,7 @@ struct SuperbitRF { struct Cyrf6936 cyrf6936; /**< The cyrf chip used */ volatile enum SuperbitRFStatus status; /**< The status of the superbitRF */ uint8_t state; /**< The states each status can be in */ - uint32_t timer; /**< The timer in usec */ + uint32_t timer; /**< The timer in microseconds */ uint8_t timeouts; /**< The amount of timeouts */ uint8_t channels[23]; /**< The channels used for DSM2/DSMX */ @@ -93,6 +68,7 @@ struct SuperbitRF { uint32_t packet_count; /**< How many packets are received(also the invalid) */ uint8_t bind_mfg_id[4]; /**< The MFG id where the receiver is bound to */ + uint32_t bind_mfg_id32; /**< The MFG id where the receiver is bound to in uint32 */ uint8_t num_channels; /**< The number of channels the transmitter has */ uint8_t protocol; /**< The protocol the transmitter uses */ volatile enum dsm_resolution resolution; /**< The resolution that the transmitter has */ @@ -100,41 +76,29 @@ struct SuperbitRF { uint8_t sop_col; /**< The sop code column number calculated with the bind MFG id */ uint8_t data_col; /**< The data code column number calculated with the bind MFG id */ - bool_t frame_available; /**< When a frame is available */ + bool_t rc_frame_available; /**< When a RC frame is available */ + uint32_t timing1; /**< Time between last receive in microseconds */ + uint32_t timing2; /**< Time between second last receive in microseconds */ int16_t rc_values[14]; /**< The rc values from the packet */ + + uint8_t tx_buffer[128]; /**< The transmit buffer */ + uint8_t tx_insert_idx; /**< The transmit buffer insert index */ + uint8_t tx_extract_idx; /**< The transmit buffer extract index */ }; /* The superbitrf functions and structures */ extern struct SuperbitRF superbitrf; +void superbitrf_init(void); void superbitrf_event(void); -/* Macro that normalize superbitrf rc_values to radio values */ -#define NormalizeRcDl(_in, _out, _count) { \ - uint8_t i; \ - for(i = 0; i < _count; i++) { \ - if(i == RADIO_THROTTLE) { \ - _out[i] = (_in[i] + MAX_PPRZ) / 2; \ - Bound(_out[i], 0, MAX_PPRZ); \ - } else { \ - _out[i] = -_in[i]; \ - Bound(_out[i], MIN_PPRZ, MAX_PPRZ); \ - } \ - } \ -} +/* The datalink defines */ +#define SuperbitRFInit() { }//superbitrf_init(); } +#define SuperbitRFCheckFreeSpace(_x) (((superbitrf.tx_insert_idx+1) %128) != superbitrf.tx_extract_idx) +#define SuperbitRFTransmit(_x) { \ + superbitrf.tx_buffer[superbitrf.tx_insert_idx] = _x; \ + superbitrf.tx_insert_idx = (superbitrf.tx_insert_idx+1) %128; \ + } +#define SuperbitRFSendMessage() { } +#define SuperbitRFCheckAndParse() { } -/* The radio control event handler */ -#define RadioControlEvent(_received_frame_handler) { \ - cyrf6936_event(&superbitrf.cyrf6936); \ - superbitrf_event(); \ - if(superbitrf.frame_available) { \ - radio_control.frame_cpt++; \ - radio_control.time_since_last_frame = 0; \ - radio_control.radio_ok_cpt = 0; \ - radio_control.status = RC_OK; \ - NormalizeRcDl(superbitrf.rc_values,radio_control.values); \ - _received_frame_handler(); \ - superbitrf.frame_available = FALSE; \ - } \ -} - -#endif /* RADIO_CONTROL_SUPERBITRF_H */ +#endif /* DATALINK_SUPERBITRF_H */ diff --git a/sw/airborne/subsystems/radio_control/superbitrf_rc.c b/sw/airborne/subsystems/radio_control/superbitrf_rc.c new file mode 100644 index 0000000000..f3609ed3b8 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/superbitrf_rc.c @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/radio_control/superbitrf_rc.c + * DSM2 and DSMX radio control implementation for the cyrf6936 2.4GHz radio chip trough SPI + */ + +#include "superbitrf_rc.h" +#include "subsystems/radio_control.h" + +/** + * Initialization + */ +//#if DATALINK == SUPERBITRF +//void radio_control_impl_init(void) {} +//#else +void radio_control_impl_init(void) { superbitrf_init(); } +//#endif diff --git a/sw/airborne/subsystems/radio_control/superbitrf_rc.h b/sw/airborne/subsystems/radio_control/superbitrf_rc.h new file mode 100644 index 0000000000..de410a56d3 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/superbitrf_rc.h @@ -0,0 +1,89 @@ +/* + * Copyright (C) 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/radio_control/superbitrf_rc.h + * DSM2 and DSMX radio control implementation for the cyrf6936 2.4GHz radio chip trough SPI + */ + +#ifndef RADIO_CONTROL_SUPERBITRF_RC_H +#define RADIO_CONTROL_SUPERBITRF_RC_H + +#include "subsystems/datalink/superbitrf.h" + +/* Theoretically you could have 14 channel over DSM2/DSMX */ +#ifndef RADIO_CONTROL_NB_CHANNEL +#define RADIO_CONTROL_NB_CHANNEL 14 +#endif + +/* The channel ordering is always the same for DSM2 and DSMX */ +#define RADIO_THROTTLE 0 +#define RADIO_ROLL 1 +#define RADIO_PITCH 2 +#define RADIO_YAW 3 +#define RADIO_GEAR 4 +#define RADIO_FLAP 5 +#define RADIO_AUX1 5 +#define RADIO_AUX2 6 +#define RADIO_AUX3 7 +#define RADIO_AUX4 8 +#define RADIO_AUX5 9 +#define RADIO_AUX6 10 +#define RADIO_AUX7 11 +#define RADIO_AUX8 12 +#define RADIO_AUX9 13 + +/* Map the MODE default to the gear switch */ +#ifndef RADIO_MODE +#define RADIO_MODE RADIO_GEAR +#endif + +/* Macro that normalize superbitrf rc_values to radio values */ +#define NormalizeRcDl(_in, _out, _count) { \ + uint8_t i; \ + for(i = 0; i < _count; i++) { \ + if(i == RADIO_THROTTLE) { \ + _out[i] = (_in[i] + MAX_PPRZ) / 2; \ + Bound(_out[i], 0, MAX_PPRZ); \ + } else { \ + _out[i] = -_in[i]; \ + Bound(_out[i], MIN_PPRZ, MAX_PPRZ); \ + } \ + } \ +} + +/* The radio control event handler */ +#define RadioControlEvent(_received_frame_handler) { \ + cyrf6936_event(&superbitrf.cyrf6936); \ + superbitrf_event(); \ + if(superbitrf.rc_frame_available) { \ + radio_control.frame_cpt++; \ + radio_control.time_since_last_frame = 0; \ + radio_control.radio_ok_cpt = 0; \ + radio_control.status = RC_OK; \ + NormalizeRcDl(superbitrf.rc_values,radio_control.values \ + ,superbitrf.num_channels); \ + _received_frame_handler(); \ + superbitrf.rc_frame_available = FALSE; \ + } \ +} + +#endif /* RADIO_CONTROL_SUPERBITRF_RC_H */ From 1964c097220780737da115cca3876fba66f06420 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Mon, 15 Jul 2013 18:21:25 +0200 Subject: [PATCH 164/309] DSMX implementation --- .../quadrotor_lisa_m_2_pwm_spektrum.xml | 4 +- conf/messages.xml | 4 + conf/telemetry/default_rotorcraft.xml | 2 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 4 + sw/airborne/peripherals/cyrf6936.c | 6 +- sw/airborne/peripherals/cyrf6936.h | 1 + sw/airborne/subsystems/datalink/datalink.h | 6 + sw/airborne/subsystems/datalink/superbitrf.c | 308 +++++++++++++++--- sw/airborne/subsystems/datalink/superbitrf.h | 26 +- 9 files changed, 316 insertions(+), 45 deletions(-) diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index 4d08f9e5ec..e347f81c0a 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -159,7 +159,7 @@ - + @@ -189,7 +189,7 @@
- + diff --git a/conf/messages.xml b/conf/messages.xml index f2199afb15..75f5034bf9 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -607,6 +607,10 @@ + + + + diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index b647b9c609..976962721c 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -18,7 +18,7 @@ - + diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 80f5ab8366..e5f9df37e6 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -141,6 +141,10 @@ &superbitrf.status, \ &superbitrf.cyrf6936.status, \ &superbitrf.packet_count, \ + &superbitrf.transfer_timeouts, \ + &superbitrf.resync_count, \ + &superbitrf.uplink_count, \ + &superbitrf.rc_count, \ &superbitrf.timing1, \ &superbitrf.timing2, \ &superbitrf.bind_mfg_id32, \ diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 1ea90971df..5bcd995155 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -199,8 +199,12 @@ void cyrf6936_event(struct Cyrf6936 *cyrf) { cyrf->tx_irq_status = cyrf->input_buf[1]; cyrf6936_read_register(cyrf, CYRF_RX_STATUS); break; - case 3: // Read the receive packet + case 3: // Set the packet length cyrf->rx_status = cyrf->input_buf[1]; + cyrf6936_read_register(cyrf, CYRF_RX_COUNT); + break; + case 4: // Read the receive packet + cyrf->rx_count = cyrf->input_buf[1]; cyrf6936_read_block(cyrf, CYRF_RX_BUFFER, 16); break; default: diff --git a/sw/airborne/peripherals/cyrf6936.h b/sw/airborne/peripherals/cyrf6936.h index 2336257a02..c384a9878b 100644 --- a/sw/airborne/peripherals/cyrf6936.h +++ b/sw/airborne/peripherals/cyrf6936.h @@ -61,6 +61,7 @@ struct Cyrf6936 { uint8_t tx_irq_status; /**< The last send interrupt status */ uint8_t rx_irq_status; /**< The last receive interrupt status */ uint8_t rx_status; /**< The last receive status */ + uint8_t rx_count; /**< The length of the received packet */ uint8_t rx_packet[16]; /**< The last received packet */ }; diff --git a/sw/airborne/subsystems/datalink/datalink.h b/sw/airborne/subsystems/datalink/datalink.h index 990f51cddb..ad1f8bb08c 100644 --- a/sw/airborne/subsystems/datalink/datalink.h +++ b/sw/airborne/subsystems/datalink/datalink.h @@ -95,6 +95,12 @@ EXTERN void dl_parse_msg(void); DlCheckAndParse(); \ } +#elif defined DATALINK && DATALINK == SUPERBITRF + +#define DatalinkEvent() { \ + SuperbitRFCheckAndParse(); \ + DlCheckAndParse(); \ + } #else diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 87b8d332e1..cf50df9918 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -53,6 +53,11 @@ #define SUPERBITRF_DRDY_PIN GPIO1 #endif +/* Default forcing in DSM2 mode is false */ +#ifndef SUPERBITRF_FORCE_DSM2 +#define SUPERBITRF_FORCE_DSM2 FALSE +#endif + /* The superbitRF structure */ struct SuperbitRF superbitrf; @@ -60,6 +65,7 @@ struct SuperbitRF superbitrf; static inline void superbitrf_radio_to_channels(uint8_t* data, uint8_t nb_channels, bool_t is_11bit, int16_t* channels); static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, uint8_t packet[]); static inline void superbitrf_send_packet_cb(bool_t error); +static inline void superbitrf_gen_dsmx_channels(void); /* The startup configuration for the cyrf6936 */ static const uint8_t cyrf_stratup_config[][2] = { @@ -189,7 +195,7 @@ void superbitrf_init(void) { * The superbitrf on event call */ void superbitrf_event(void) { - uint8_t i, packet_size, data_code[16], tx_packet[16]; + uint8_t i, pn_row, packet_size, data_code[16], tx_packet[16]; // Check if the cyrf6936 isn't busy and the uperbitrf is initialized if(superbitrf.cyrf6936.status != CYRF6936_IDLE) @@ -264,8 +270,12 @@ void superbitrf_event(void) { /* When the superbitrf is initializing transfer */ case SUPERBITRF_INIT_TRANSFER: + // Generate the DSMX channels + superbitrf_gen_dsmx_channels(); + // Try to write the transfer config cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4); + superbitrf.resync_count = 0; superbitrf.status = SUPERBITRF_SYNCING_A; break; @@ -326,18 +336,65 @@ void superbitrf_event(void) { superbitrf.state++; break; case 2: + // When DSMX we don't need to switch + if(IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) { + superbitrf.state++; + break; + } + // Switch channel, sop code, data code and crc - superbitrf.channel = (superbitrf.channel + 1) % 0x62; //TODO fix define + superbitrf.channel_idx = (superbitrf.channel_idx + 1) %2; + pn_row = superbitrf.channels[superbitrf.channel_idx] % 5; + + cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channels[superbitrf.channel_idx], + pn_codes[pn_row][superbitrf.sop_col], + pn_codes[pn_row][superbitrf.data_col], + superbitrf.crc_seed); + superbitrf.state++; + break; + case 3: + // Send a packet + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { + tx_packet[0] = ~superbitrf.bind_mfg_id[2]; + tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1; + } else { + tx_packet[0] = superbitrf.bind_mfg_id[2]; + tx_packet[1] = (superbitrf.bind_mfg_id[3])+1; + } + + packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); + if(packet_size > 14) + packet_size = 14; + + for(i = 0; i < packet_size; i++) + tx_packet[i+2] = superbitrf.tx_buffer[(superbitrf.tx_extract_idx+i) %128]; + + cyrf6936_send(&superbitrf.cyrf6936, tx_packet, packet_size+2); + superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; + superbitrf.state++; + break; + case 4: + //TODO: check timeout? (Waiting for send) + break; + case 5: + // Switch channel, sop code, data code and crc + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) + superbitrf.channel = (superbitrf.channel + 1) % 0x62; //TODO fix define + else { + superbitrf.channel_idx = (superbitrf.channel_idx + 1) %23; + superbitrf.channel = superbitrf.channels[superbitrf.channel_idx]; + } superbitrf.crc_seed = ~superbitrf.crc_seed; + pn_row = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? superbitrf.channel % 5 : (superbitrf.channel-2) % 5; cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channel, - pn_codes[superbitrf.channel % 5][superbitrf.sop_col], - pn_codes[superbitrf.channel % 5][superbitrf.data_col], + pn_codes[pn_row][superbitrf.sop_col], + pn_codes[pn_row][superbitrf.data_col], superbitrf.crc_seed); superbitrf.state++; break; - case 3: + case 6: // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; @@ -357,13 +414,16 @@ void superbitrf_event(void) { case 0: // When there is a timeout if (superbitrf.timer < get_sys_time_usec()) { + superbitrf.channel_idx = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? (superbitrf.channel_idx + 2) %2 : (superbitrf.channel_idx + 2) %23; + superbitrf.transfer_timeouts++; superbitrf.timeouts++; superbitrf.state++; } - // We really lost it - if(superbitrf.timeouts > 1) { + // We really lost the communication + if(superbitrf.timeouts > 2) { superbitrf.state = 0; + superbitrf.resync_count++; superbitrf.status = SUPERBITRF_SYNCING_A; } break; @@ -371,11 +431,34 @@ void superbitrf_event(void) { // Abort the receive cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); superbitrf.state++; + + // When we don't have enough time + if(superbitrf.timeouts > 0 || superbitrf.timing2 < 10000 || superbitrf.timing1 > 10000) { + superbitrf.state = 8; + // Set the timer + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; + break; + } + + // Set the timer for sending + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATAWAIT_TIME) % 0xFFFFFFFF; break; case 2: + // Wait before sending + superbitrf.state++; + //if (superbitrf.timer < get_sys_time_usec()) + //superbitrf.state++; + break; + case 3: // Send a packet - tx_packet[0] = ~superbitrf.bind_mfg_id[2]; - tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1; + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { + tx_packet[0] = ~superbitrf.bind_mfg_id[2]; + tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1; + } else { + tx_packet[0] = superbitrf.bind_mfg_id[2]; + tx_packet[1] = (superbitrf.bind_mfg_id[3])+1; + } + packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); if(packet_size > 14) packet_size = 14; @@ -387,30 +470,49 @@ void superbitrf_event(void) { superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; superbitrf.state++; break; - case 3: + case 4: //TODO: check timeout? (Waiting for send) break; - case 4: + case 5: + // Start receiving + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + superbitrf.state++; + + // Set the timer + superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATAWAIT_TIME + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; + break; + case 6: + // Waiting for data receive + if (superbitrf.timer < get_sys_time_usec()) + superbitrf.state++; + break; + case 7: + // Abort the receive + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); + superbitrf.state++; + break; + case 8: // Switch channel, sop code, data code and crc - superbitrf.channel_idx = (superbitrf.channel_idx + 1) %2; + superbitrf.channel_idx = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? (superbitrf.channel_idx + 1) %2 : (superbitrf.channel_idx + 1) %23; superbitrf.channel = superbitrf.channels[superbitrf.channel_idx]; - superbitrf.crc_seed = ~ superbitrf.crc_seed; + superbitrf.crc_seed = ~superbitrf.crc_seed; + pn_row = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? superbitrf.channel % 5 : (superbitrf.channel-2) % 5; cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channel, - pn_codes[superbitrf.channel % 5][superbitrf.sop_col], - pn_codes[superbitrf.channel % 5][superbitrf.data_col], + pn_codes[pn_row][superbitrf.sop_col], + pn_codes[pn_row][superbitrf.data_col], superbitrf.crc_seed); superbitrf.state++; break; - case 5: + case 9: // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; break; default: // Set the timer - superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_RECV_TIME) % 0xFFFFFFFF; + superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATARECV_TIME + SUPERBITRF_RECV_TIME) % 0xFFFFFFFF; superbitrf.state = 0; break; } @@ -488,34 +590,68 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui /* When we receive a packet during syncing first channel A */ case SUPERBITRF_SYNCING_A: // Check the MFG id - if((error && !(status & CYRF_BAD_CRC)) || - packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + if(error && !(status & CYRF_BAD_CRC)) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; + } + if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && + (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF))) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + break; + } + if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && + (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (superbitrf.bind_mfg_id[3]&0xFF))) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + break; + } // If the CRC is wrong invert if (error && (status & CYRF_BAD_CRC)) superbitrf.crc_seed = ~superbitrf.crc_seed; - superbitrf.channels[0] = superbitrf.channel; - superbitrf.channels[1] = superbitrf.channel; + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { + superbitrf.channels[0] = superbitrf.channel; + superbitrf.channels[1] = superbitrf.channel; - superbitrf.state = 1; - superbitrf.status = SUPERBITRF_SYNCING_B; + superbitrf.state = 1; + superbitrf.status = SUPERBITRF_SYNCING_B; + } else { + superbitrf.timeouts = 0; + superbitrf.state = 1; + superbitrf.status = SUPERBITRF_TRANSFER; + } break; /* When we receive a packet during syncing second channel B */ case SUPERBITRF_SYNCING_B: // Check the MFG id - if((error && !(status & CYRF_BAD_CRC)) || - packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + if(error && !(status & CYRF_BAD_CRC)) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; + } + if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && + (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF))) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + break; + } + if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && + (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (superbitrf.bind_mfg_id[3]&0xFF))) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + break; + } // If the CRC is wrong invert if (error && (status & CYRF_BAD_CRC)) superbitrf.crc_seed = ~superbitrf.crc_seed; // Set the channel - if(superbitrf.crc_seed == ~((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { + if(superbitrf.channels[0] != superbitrf.channel) { superbitrf.channels[0] = superbitrf.channel; superbitrf.channel_idx = 0; } @@ -535,22 +671,62 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui /* When we receive a packet during transfer */ case SUPERBITRF_TRANSFER: // Check the MFG id - if(packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)) + if(error && !(status & CYRF_BAD_CRC)) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; + } + /*if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && + (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF))) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + break; + } + if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && + (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (superbitrf.bind_mfg_id[3]&0xFF))) { + // Start receiving TODO: Fix nicely + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + break; + }*/ - // Parse the packet - superbitrf_radio_to_channels(&packet[2], superbitrf.num_channels, superbitrf.resolution, superbitrf.rc_values); - superbitrf.rc_frame_available = TRUE; + // If the CRC is wrong invert + if (error && (status & CYRF_BAD_CRC)) + superbitrf.crc_seed = ~superbitrf.crc_seed; - // Calculate the timing (seperately for the channel switches) - if(superbitrf.channels[0] == superbitrf.channel) + // Check if it is a RC packet + if(packet[1] == (~superbitrf.bind_mfg_id[3]&0xFF) || packet[1] == (superbitrf.bind_mfg_id[3]&0xFF)) { + superbitrf.rc_count++; + + // Parse the packet + superbitrf_radio_to_channels(&packet[2], superbitrf.num_channels, superbitrf.resolution, superbitrf.rc_values); + superbitrf.rc_frame_available = TRUE; + + // Calculate the timing (seperately for the channel switches) + superbitrf.timing2 = superbitrf.timing1; superbitrf.timing1 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_TIME); - else - superbitrf.timing2 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_TIME); - // Go to next receive - superbitrf.state = 1; - superbitrf.timeouts = 0; + // Go to next receive + superbitrf.state = 1; + superbitrf.timeouts = 0; + } else if(superbitrf.state == 5) { + superbitrf.uplink_count++; + + // When it is a data packet, parse the packet if not busy already + if(!dl_msg_available) { + for(i = 2; i < superbitrf.cyrf6936.rx_count; i++) { + parse_pprz(&superbitrf.rx_transport, packet[i]); + + // When we have a full message + if (superbitrf.rx_transport.trans.msg_received) { + pprz_parse_payload(&superbitrf.rx_transport); + superbitrf.rx_transport.trans.msg_received = FALSE; + } + } + } + + // Update the state + superbitrf.state = 7; + } break; /* Should not come here */ @@ -563,10 +739,18 @@ static inline void superbitrf_send_packet_cb(bool_t error) { /* Switch on the status of the superbitRF */ switch (superbitrf.status) { + /* When we are synchronizing */ + case SUPERBITRF_SYNCING_A: + case SUPERBITRF_SYNCING_B: + // When we successfully or unsuccessfully send a data packet + if(superbitrf.state == 4) + superbitrf.state++; + break; + /* When we are in transfer mode */ case SUPERBITRF_TRANSFER: // When we successfully or unsuccessfully send a packet - if(superbitrf.state == 3) + if(superbitrf.state == 4) superbitrf.state++; break; @@ -604,5 +788,53 @@ static inline void superbitrf_radio_to_channels(uint8_t* data, uint8_t nb_channe } } +/** + * Generate the channels + */ +static inline void superbitrf_gen_dsmx_channels(void) { + // Calculate the DSMX channels + int idx = 0; + uint32_t id = ~((superbitrf.bind_mfg_id[0] << 24) | (superbitrf.bind_mfg_id[1] << 16) | + (superbitrf.bind_mfg_id[2] << 8) | (superbitrf.bind_mfg_id[3] << 0)); + uint32_t id_tmp = id; + + // While not all channels are set + while(idx < 23) { + int i; + int count_3_27 = 0, count_28_51 = 0, count_52_76 = 0; + + id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization + uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3 + if (((next_ch ^ id) & 0x01 ) == 0) + continue; + + // Go trough all already set channels + for (i = 0; i < idx; i++) { + // Channel is already used + if(superbitrf.channels[i] == next_ch) + break; + + // Count the channel groups + if(superbitrf.channels[i] <= 27) + count_3_27++; + else if (superbitrf.channels[i] <= 51) + count_28_51++; + else + count_52_76++; + } + + // When channel is already used continue + if (i != idx) + continue; + + // Set the channel when channel groups aren't full + if ((next_ch < 28 && count_3_27 < 8) // Channels 3-27: max 8 + || (next_ch >= 28 && next_ch < 52 && count_28_51 < 7) // Channels 28-52: max 7 + || (next_ch >= 52 && count_52_76 < 8)) { // Channels 52-76: max 8 + superbitrf.channels[idx++] = next_ch; + } + } +} + diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index d3c965c825..2f7a786e1b 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -34,8 +34,10 @@ /* The timings in microseconds */ #define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ -#define SUPERBITRF_SYNC_RECV_TIME 12000 /**< The time to wait for a sync packet on a channel in microseconds */ -#define SUPERBITRF_RECV_TIME 24000 /**< The time to wait for a transfer packet on a channel in microseconds */ +#define SUPERBITRF_SYNC_RECV_TIME 7000 /**< The time to wait for a sync packet on a channel in microseconds */ +#define SUPERBITRF_RECV_TIME 25000 /**< The time to wait for a transfer packet on a channel in microseconds */ +#define SUPERBITRF_DATAWAIT_TIME 500 /**< The time to wait after RC receive to send a data packet in microseconds */ +#define SUPERBITRF_DATARECV_TIME 2000 /**< The time to wait for a data packet on a channel in microseconds */ /* The different statuses the superbitRF can be in */ enum SuperbitRFStatus { @@ -54,6 +56,18 @@ enum dsm_resolution { SUPERBITRF_11_BIT_RESOLUTION = 0x01, /**< The transmitter has a 11 bit resolution */ }; +/* The different protocols a transmitter can send */ +enum dsm_protocol { + DSM_DSM2_1 = 0x01, /**< The original DSM2 protocol with 1 packet of data */ + DSM_DSM2_2 = 0x02, /**< The original DSM2 protocol with 2 packets of data */ + DSM_DSM2P = 0x10, /**< Our own DSM2 Paparazzi protocol */ + DSM_DSMXP = 0x11, /**< Our own DSMX Paparazzi protocol */ + DSM_DSMX_1 = 0xA2, /**< The original DSMX protocol with 1 packet of data */ + DSM_DSMX_2 = 0xB2, /**< The original DSMX protocol with 2 packets of data */ +}; +#define IS_DSM2(x) (x == DSM_DSM2P || x == DSM_DSM2_1 || x == DSM_DSM2_2) +#define IS_DSMX(x) (!IS_DSM2(x)) + /* The superbitrf structure */ struct SuperbitRF { struct Cyrf6936 cyrf6936; /**< The cyrf chip used */ @@ -61,16 +75,20 @@ struct SuperbitRF { uint8_t state; /**< The states each status can be in */ uint32_t timer; /**< The timer in microseconds */ uint8_t timeouts; /**< The amount of timeouts */ + uint32_t transfer_timeouts; /**< The amount of timeouts during transfer */ + uint32_t resync_count; /**< The amount of resyncs needed during transfer */ uint8_t channels[23]; /**< The channels used for DSM2/DSMX */ uint8_t channel_idx; /**< The current channel index */ uint8_t channel; /**< The current channel number */ uint32_t packet_count; /**< How many packets are received(also the invalid) */ + uint32_t uplink_count; /**< How many valid uplink packages are received */ + uint32_t rc_count; /**< How many valid RC packages are received */ uint8_t bind_mfg_id[4]; /**< The MFG id where the receiver is bound to */ uint32_t bind_mfg_id32; /**< The MFG id where the receiver is bound to in uint32 */ uint8_t num_channels; /**< The number of channels the transmitter has */ - uint8_t protocol; /**< The protocol the transmitter uses */ + volatile enum dsm_protocol protocol; /**< The protocol the transmitter uses */ volatile enum dsm_resolution resolution; /**< The resolution that the transmitter has */ uint16_t crc_seed; /**< The CRC seed that is calculated with the bind MFG id */ uint8_t sop_col; /**< The sop code column number calculated with the bind MFG id */ @@ -81,6 +99,8 @@ struct SuperbitRF { uint32_t timing2; /**< Time between second last receive in microseconds */ int16_t rc_values[14]; /**< The rc values from the packet */ + struct pprz_transport rx_transport; /**< The receive transport */ + uint8_t tx_buffer[128]; /**< The transmit buffer */ uint8_t tx_insert_idx; /**< The transmit buffer insert index */ uint8_t tx_extract_idx; /**< The transmit buffer extract index */ From 06df13cf95ea4007e12c2ef48e068b00c113a55a Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 16 Jul 2013 20:13:20 +0200 Subject: [PATCH 165/309] Some small fixes --- sw/airborne/subsystems/datalink/superbitrf.c | 84 +++++++++++++++----- sw/airborne/subsystems/datalink/superbitrf.h | 2 +- 2 files changed, 63 insertions(+), 23 deletions(-) diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index cf50df9918..08e1a3128e 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -336,15 +336,9 @@ void superbitrf_event(void) { superbitrf.state++; break; case 2: - // When DSMX we don't need to switch - if(IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) { - superbitrf.state++; - break; - } - // Switch channel, sop code, data code and crc - superbitrf.channel_idx = (superbitrf.channel_idx + 1) %2; - pn_row = superbitrf.channels[superbitrf.channel_idx] % 5; + superbitrf.channel_idx = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? (superbitrf.channel_idx + 1) %2 : (superbitrf.channel_idx + 1) %23; + pn_row = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? superbitrf.channels[superbitrf.channel_idx] % 5 : (superbitrf.channels[superbitrf.channel_idx]-2) % 5; cyrf6936_write_chan_sop_data_crc(&superbitrf.cyrf6936, superbitrf.channels[superbitrf.channel_idx], pn_codes[pn_row][superbitrf.sop_col], @@ -377,13 +371,15 @@ void superbitrf_event(void) { //TODO: check timeout? (Waiting for send) break; case 5: - // Switch channel, sop code, data code and crc - if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) - superbitrf.channel = (superbitrf.channel + 1) % 0x62; //TODO fix define - else { - superbitrf.channel_idx = (superbitrf.channel_idx + 1) %23; + // When DSMX we don't need to switch + if(IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) { + superbitrf.state++; superbitrf.channel = superbitrf.channels[superbitrf.channel_idx]; + break; } + + // Switch channel, sop code, data code and crc + superbitrf.channel = (superbitrf.channel + 1) % 0x62; //TODO fix define superbitrf.crc_seed = ~superbitrf.crc_seed; pn_row = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? superbitrf.channel % 5 : (superbitrf.channel-2) % 5; @@ -596,13 +592,15 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui break; } if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && - (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF))) { + (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && + packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; } if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && - (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (superbitrf.bind_mfg_id[3]&0xFF))) { + (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (superbitrf.bind_mfg_id[3]&0xFF) && + packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; @@ -612,6 +610,25 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui if (error && (status & CYRF_BAD_CRC)) superbitrf.crc_seed = ~superbitrf.crc_seed; + // When we receive a data packet + if(packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)) { + superbitrf.uplink_count++; + + // When it is a data packet, parse the packet if not busy already + if(!dl_msg_available) { + for(i = 2; i < superbitrf.cyrf6936.rx_count; i++) { + parse_pprz(&superbitrf.rx_transport, packet[i]); + + // When we have a full message + if (superbitrf.rx_transport.trans.msg_received) { + pprz_parse_payload(&superbitrf.rx_transport); + superbitrf.rx_transport.trans.msg_received = FALSE; + } + } + } + break; + } + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { superbitrf.channels[0] = superbitrf.channel; superbitrf.channels[1] = superbitrf.channel; @@ -634,13 +651,15 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui break; } if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && - (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF))) { + (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && + packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; } if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && - (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (superbitrf.bind_mfg_id[3]&0xFF))) { + (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (superbitrf.bind_mfg_id[3]&0xFF) && + packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; @@ -650,6 +669,25 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui if (error && (status & CYRF_BAD_CRC)) superbitrf.crc_seed = ~superbitrf.crc_seed; + // When we receive a data packet + if(packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)) { + superbitrf.uplink_count++; + + // When it is a data packet, parse the packet if not busy already + if(!dl_msg_available) { + for(i = 2; i < superbitrf.cyrf6936.rx_count; i++) { + parse_pprz(&superbitrf.rx_transport, packet[i]); + + // When we have a full message + if (superbitrf.rx_transport.trans.msg_received) { + pprz_parse_payload(&superbitrf.rx_transport); + superbitrf.rx_transport.trans.msg_received = FALSE; + } + } + } + break; + } + // Set the channel if(superbitrf.channels[0] != superbitrf.channel) { superbitrf.channels[0] = superbitrf.channel; @@ -676,18 +714,20 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; } - /*if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && - (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF))) { + if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && + (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && + packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; } if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && - (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || packet[1] != (superbitrf.bind_mfg_id[3]&0xFF))) { + (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (superbitrf.bind_mfg_id[3]&0xFF) && + packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; - }*/ + } // If the CRC is wrong invert if (error && (status & CYRF_BAD_CRC)) @@ -708,7 +748,7 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui // Go to next receive superbitrf.state = 1; superbitrf.timeouts = 0; - } else if(superbitrf.state == 5) { + } else { superbitrf.uplink_count++; // When it is a data packet, parse the packet if not busy already diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index 2f7a786e1b..c6ac544d6e 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -37,7 +37,7 @@ #define SUPERBITRF_SYNC_RECV_TIME 7000 /**< The time to wait for a sync packet on a channel in microseconds */ #define SUPERBITRF_RECV_TIME 25000 /**< The time to wait for a transfer packet on a channel in microseconds */ #define SUPERBITRF_DATAWAIT_TIME 500 /**< The time to wait after RC receive to send a data packet in microseconds */ -#define SUPERBITRF_DATARECV_TIME 2000 /**< The time to wait for a data packet on a channel in microseconds */ +#define SUPERBITRF_DATARECV_TIME 9000 /**< The time to wait for a data packet on a channel in microseconds */ /* The different statuses the superbitRF can be in */ enum SuperbitRFStatus { From bfc5598ad88b9fd116e51e5ee82467c9eaab061a Mon Sep 17 00:00:00 2001 From: Piotr Esden-Tempski Date: Tue, 23 Jul 2013 23:20:37 -0700 Subject: [PATCH 166/309] Initial commit for Lisa/S V0.1 support. --- conf/airframes/esden/calib/ls01-default.xml | 34 ++ conf/airframes/esden/quady_ls01pwm.xml | 233 ++++++++++ conf/boards/lisa_s_0.1.makefile | 72 +++ conf/firmwares/rotorcraft.makefile | 10 + .../shared/imu_lisa_s_v0.1.makefile | 70 +++ sw/airborne/arch/stm32/lisa-s.ld | 36 ++ sw/airborne/boards/lisa_s/baro_board.h | 67 +++ sw/airborne/boards/lisa_s_0.1.h | 421 ++++++++++++++++++ 8 files changed, 943 insertions(+) create mode 100644 conf/airframes/esden/calib/ls01-default.xml create mode 100644 conf/airframes/esden/quady_ls01pwm.xml create mode 100644 conf/boards/lisa_s_0.1.makefile create mode 100644 conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile create mode 100644 sw/airborne/arch/stm32/lisa-s.ld create mode 100644 sw/airborne/boards/lisa_s/baro_board.h create mode 100644 sw/airborne/boards/lisa_s_0.1.h diff --git a/conf/airframes/esden/calib/ls01-default.xml b/conf/airframes/esden/calib/ls01-default.xml new file mode 100644 index 0000000000..a7171f0158 --- /dev/null +++ b/conf/airframes/esden/calib/ls01-default.xml @@ -0,0 +1,34 @@ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml new file mode 100644 index 0000000000..9dc6032179 --- /dev/null +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -0,0 +1,233 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + +
+ + + +
+ + + +
+ +
+ + + +
+ +
+ +
+ + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ +
+ +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/boards/lisa_s_0.1.makefile b/conf/boards/lisa_s_0.1.makefile new file mode 100644 index 0000000000..ffaeaf9a6c --- /dev/null +++ b/conf/boards/lisa_s_0.1.makefile @@ -0,0 +1,72 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# lisa_s_0.1.makefile +# +# http://paparazzi.enac.fr/wiki/Lisa/S +# + +BOARD=lisa_s +BOARD_VERSION=0.1 +BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\" + +ARCH=stm32 +$(TARGET).ARCHDIR = $(ARCH) +$(TARGET).LDSCRIPT=$(SRC_ARCH)/lisa-s.ld + +# ----------------------------------------------------------------------- + +# default flash mode is via usb dfu bootloader (luftboot) +# other possibilities: JTAG, SWD, SERIAL +FLASH_MODE ?= SWD + +# +# +# some default values shared between different firmwares +# +# + +# +# default LED configuration +# +RADIO_CONTROL_LED ?= none +BARO_LED ?= none +AHRS_ALIGNER_LED ?= 2 +GPS_LED ?= 3 +SYS_TIME_LED ?= 1 + +# +# default uart configuration +# +RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2 +RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT ?= none + +MODEM_PORT ?= UART1 +MODEM_BAUD ?= B57600 + +GPS_PORT ?= UART3 +GPS_BAUD ?= B38400 + +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# e.g. +# +ACTUATORS ?= actuators_pwm + +# Thish should be disabled as we don't have adc inputs on Lisa/S +ifndef ADC_IR1 +ADC_IR1 = 1 +ADC_IR1_CHAN = 0 +endif +ifndef ADC_IR2 +ADC_IR2 = 2 +ADC_IR2_CHAN = 1 +endif +ifndef ADC_IR3 +ADC_IR_TOP = 3 +ADC_IR_TOP_CHAN = 2 +endif +ADC_IR_NB_SAMPLES ?= 16 diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index b5cd13d64e..575c28dabb 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -187,6 +187,16 @@ LISA_M_BARO ?= BARO_BOARD_BMP085 endif ap.CFLAGS += -D$(LISA_M_BARO) +# Lisa/S baro +else ifeq ($(BOARD), lisa_s) +# defaults to SPI baro MS5611 on the board + include $(CFG_SHARED)/spi_master.makefile + ap.CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE1 + ap.CFLAGS += -DMS5611_SPI_DEV=spi1 + ap.CFLAGS += -DMS5611_SLAVE_DEV=SPI_SLAVE1 + ap.srcs += boards/lisa_m/baro_ms5611_spi.c + ap.CFLAGS += -DBARO_MS5611_SPI + # Lia baro (no bmp onboard) else ifeq ($(BOARD), lia) # fixme, reuse the baro drivers in lisa_m dir diff --git a/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile b/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile new file mode 100644 index 0000000000..536031592b --- /dev/null +++ b/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile @@ -0,0 +1,70 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# Common part for Aspirin IMU v2.1 and v2.2 +# +# +# required xml: +#
+# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +#
+# +# + + +# for fixedwing firmware and ap only +ifeq ($(TARGET), ap) + IMU_ASPIRIN_2_CFLAGS = -DUSE_IMU +endif + +IMU_ASPIRIN_2_CFLAGS += -DIMU_TYPE_H=\"imu/imu_aspirin_2_spi.h\" +IMU_ASPIRIN_2_SRCS = $(SRC_SUBSYSTEMS)/imu.c +IMU_ASPIRIN_2_SRCS += $(SRC_SUBSYSTEMS)/imu/imu_aspirin_2_spi.c +IMU_ASPIRIN_2_SRCS += peripherals/mpu60x0.c +IMU_ASPIRIN_2_SRCS += peripherals/mpu60x0_spi.c + +include $(CFG_SHARED)/spi_master.makefile + +IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_SLAVE_IDX=SPI_SLAVE0 +IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_DEV=spi1 + +IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI1 +# Slave select configuration +# SLAVE0 is on PA4 (NSS) (MPU600 CS) +IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE0 + +# SLAVE1 is on PC4, which is the baro CS +IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE1 + +ap.CFLAGS += $(IMU_ASPIRIN_2_CFLAGS) +ap.srcs += $(IMU_ASPIRIN_2_SRCS) + +# +# NPS simulator +# +include $(CFG_SHARED)/imu_nps.makefile diff --git a/sw/airborne/arch/stm32/lisa-s.ld b/sw/airborne/arch/stm32/lisa-s.ld new file mode 100644 index 0000000000..a919196043 --- /dev/null +++ b/sw/airborne/arch/stm32/lisa-s.ld @@ -0,0 +1,36 @@ +/* + * Hey Emacs, this is a -*- makefile -*- + * + * Copyright (C) 2012 Piotr Esden-Tempski + * + * This file is part of Paparazzi. + * + * Paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * Paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/* Linker script for Lisa-S (STM32F103REY6, 512K flash, 64K RAM). */ + +/* Define memory regions. */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + /* Leaving 2k of space at the end of rom for stored settings */ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K +} + +/* Include the common ld script. */ +INCLUDE libopencm3_stm32f1.ld + diff --git a/sw/airborne/boards/lisa_s/baro_board.h b/sw/airborne/boards/lisa_s/baro_board.h new file mode 100644 index 0000000000..42014ddeee --- /dev/null +++ b/sw/airborne/boards/lisa_s/baro_board.h @@ -0,0 +1,67 @@ + +/* + * board specific functions for the lisa_m board + * + */ + +#ifndef BOARDS_LISA_M_BARO_H +#define BOARDS_LISA_M_BARO_H + +#include "std.h" + +// for right now we abuse this file for the ms5611 baro on aspirin as well +#if !BARO_MS5611_I2C && !BARO_MS5611 + +#include "mcu_periph/i2c.h" + +// absolute addr +#define BMP085_ADDR 0xEE +// Over sample setting (0-3) +#define BMP085_OSS 3 + +enum LisaBaroStatus { + LBS_UNINITIALIZED, + LBS_REQUEST, + LBS_READING, + LBS_READ, + LBS_REQUEST_TEMP, + LBS_READING_TEMP, + LBS_READ_TEMP, +}; + +struct BaroBoard { + enum LisaBaroStatus status; +}; + +struct bmp085_baro_calibration { + // These values come from EEPROM on sensor + int16_t ac1; + int16_t ac2; + int16_t ac3; + uint16_t ac4; + uint16_t ac5; + uint16_t ac6; + int16_t b1; + int16_t b2; + int16_t mb; + int16_t mc; + int16_t md; + + // These values are calculated + int32_t b5; +}; + +extern struct BaroBoard baro_board; +extern struct i2c_transaction baro_trans; +extern struct bmp085_baro_calibration calibration; + +extern void baro_board_send_reset(void); +extern void baro_board_send_config(void); + +#endif // !BARO_MS5611_xx + +extern void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)); + +#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler,_b_diff_handler) + +#endif /* BOARDS_LISA_M_BARO_H */ diff --git a/sw/airborne/boards/lisa_s_0.1.h b/sw/airborne/boards/lisa_s_0.1.h new file mode 100644 index 0000000000..fa3c3d49cb --- /dev/null +++ b/sw/airborne/boards/lisa_s_0.1.h @@ -0,0 +1,421 @@ +#ifndef CONFIG_LISA_S_0_1_H +#define CONFIG_LISA_S_0_1_H + +#define BOARD_LISA_S + +/* Lisa/M has a 12MHz external clock and 72MHz internal. */ +#define EXT_CLK 12000000 +#define AHB_CLK 72000000 + +/* + * Onboard LEDs + */ + +/* red, on PA8 */ +#ifndef USE_LED_1 +#define USE_LED_1 1 +#endif +#define LED_1_GPIO GPIOC +#define LED_1_GPIO_CLK RCC_APB2ENR_IOPCEN +#define LED_1_GPIO_PIN GPIO10 +#define LED_1_GPIO_ON gpio_clear +#define LED_1_GPIO_OFF gpio_set +#define LED_1_AFIO_REMAP ((void)0) + +/* green, shared with JTAG_TRST */ +#ifndef USE_LED_2 +#define USE_LED_2 1 +#endif +#define LED_2_GPIO GPIOC +#define LED_2_GPIO_CLK RCC_APB2ENR_IOPCEN +#define LED_2_GPIO_PIN GPIO11 +#define LED_2_GPIO_ON gpio_clear +#define LED_2_GPIO_OFF gpio_set +#define LED_2_AFIO_REMAP ((void)0) + +/* green, shared with ADC12 (ADC_6 on connector ANALOG2) */ +#ifndef USE_LED_3 +#define USE_LED_3 1 +#endif +#define LED_3_GPIO GPIOD +#define LED_3_GPIO_CLK RCC_APB2ENR_IOPDEN +#define LED_3_GPIO_PIN GPIO2 +#define LED_3_GPIO_ON gpio_clear +#define LED_3_GPIO_OFF gpio_set +#define LED_3_AFIO_REMAP ((void)0) + +/* + * not actual LEDS, used as GPIOs + */ + +/* PB1, DRDY on EXT SPI connector*/ +#define LED_BODY_GPIO GPIOB +#define LED_BODY_GPIO_CLK RCC_APB2ENR_IOPBEN +#define LED_BODY_GPIO_PIN GPIO1 +#define LED_BODY_GPIO_ON gpio_set +#define LED_BODY_GPIO_OFF gpio_clear +#define LED_BODY_AFIO_REMAP ((void)0) + +/* PC12, on GPIO connector*/ +#define LED_12_GPIO GPIOC +#define LED_12_GPIO_CLK RCC_APB2ENR_IOPCEN +#define LED_12_GPIO_PIN GPIO12 +#define LED_12_GPIO_ON gpio_clear +#define LED_12_GPIO_OFF gpio_set +#define LED_12_AFIO_REMAP ((void)0) + + +/* Default actuators driver */ +#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" +#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y) +#define ActuatorsDefaultInit() ActuatorsPwmInit() +#define ActuatorsDefaultCommit() ActuatorsPwmCommit() + + +#define DefaultVoltageOfAdc(adc) (0.0045*adc) + +/* Onboard ADCs */ +/* + ADC1 PC3/ADC13 + ADC2 PC0/ADC10 + ADC3 PC1/ADC11 + ADC4 PC5/ADC15 + ADC6 PC2/ADC12 + BATT PC4/ADC14 +*/ +/* We should remove the first three adc channels, as Lisa/S does not provide those. */ +#define BOARD_ADC_CHANNEL_1 10 +#define BOARD_ADC_CHANNEL_2 11 +#define BOARD_ADC_CHANNEL_3 12 +// we can only use ADC1,2,3; the last channel is for bat monitoring +#define BOARD_ADC_CHANNEL_4 2 + +/* provide defines that can be used to access the ADC_x in the code or airframe file + * these directly map to the index number of the 4 adc channels defined above + * 4th (index 3) is used for bat monitoring by default + */ +#define ADC_1 0 +#define ADC_2 1 +#define ADC_3 2 + +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY 3 +#endif + +/* GPIO mapping for ADC1 pins, overwrites the default in arch/stm32/mcu_periph/adc_arch.c */ +// FIXME, this is not very nice, is also locm3 lib specific +#ifdef USE_AD1 +#define ADC1_GPIO_INIT(gpio) { \ + gpio_set_mode(GPIOA, GPIO_MODE_INPUT, \ + GPIO_CNF_INPUT_ANALOG, \ + GPIO2); \ + } +#endif // USE_AD1 + +#define BOARD_HAS_BARO 1 + +/* SPI slave mapping */ + +/* IMU_MPU_CS */ +#define SPI_SELECT_SLAVE0_PORT GPIOA +#define SPI_SELECT_SLAVE0_PIN GPIO4 + +/* IMU_BARO_CS */ +#define SPI_SELECT_SLAVE1_PORT GPIOC +#define SPI_SELECT_SLAVE1_PIN GPIO4 + +/* RADIO_SS */ +#define SPI_SELECT_SLAVE2_PORT GPIOB +#define SPI_SELECT_SLAVE2_PIN GPIO12 + +/* + * UART pin configuration + * + * sets on which pins the UARTs are connected + */ +/* DIAG port */ +#define UART1_GPIO_AF 0 +#define UART1_GPIO_PORT_RX GPIO_BANK_USART1_RX +#define UART1_GPIO_RX GPIO_USART1_RX +#define UART1_GPIO_PORT_TX GPIO_BANK_USART1_TX +#define UART1_GPIO_TX GPIO_USART1_TX + +/* GPS */ +#define UART3_GPIO_AF 0 +#define UART3_GPIO_PORT_RX GPIO_BANK_USART3_RX +#define UART3_GPIO_RX GPIO_USART3_RX +#define UART3_GPIO_PORT_TX GPIO_BANK_USART3_TX +#define UART3_GPIO_TX GPIO_USART3_TX + +/* LED1 & LED2 */ +/* +#define UART3_GPIO_AF AFIO_MAPR_USART3_REMAP_PARTIAL_REMAP +#define UART3_GPIO_PORT_RX GPIO_BANK_USART3_PR_RX +#define UART3_GPIO_RX GPIO_USART3_PR_RX +#define UART3_GPIO_PORT_TX GPIO_BANK_USART3_PR_TX +#define UART3_GPIO_TX GPIO_USART3_PR_TX +*/ + +/* + * Spektrum + */ +/* The line that is pulled low at power up to initiate the bind process */ +#define SPEKTRUM_BIND_PIN GPIO2 +#define SPEKTRUM_BIND_PIN_PORT GPIOB + +/* Diag Port RX */ +#define SPEKTRUM_UART1_RCC_REG &RCC_APB2ENR +#define SPEKTRUM_UART1_RCC_DEV RCC_APB2ENR_USART1EN +#define SPEKTRUM_UART1_BANK GPIO_BANK_USART1_RX +#define SPEKTRUM_UART1_PIN GPIO_USART1_RX +#define SPEKTRUM_UART1_AF 0 +#define SPEKTRUM_UART1_IRQ NVIC_USART1_IRQ +#define SPEKTRUM_UART1_ISR usart1_isr +#define SPEKTRUM_UART1_DEV USART1 + +/* AUX Radio RX */ +#define SPEKTRUM_UART2_RCC_REG &RCC_APB1ENR +#define SPEKTRUM_UART2_RCC_DEV RCC_APB1ENR_USART2EN +#define SPEKTRUM_UART2_BANK GPIO_BANK_USART2_RX +#define SPEKTRUM_UART2_PIN GPIO_USART2_RX +#define SPEKTRUM_UART2_AF 0 +#define SPEKTRUM_UART2_IRQ NVIC_USART2_IRQ +#define SPEKTRUM_UART2_ISR usart2_isr +#define SPEKTRUM_UART2_DEV USART2 + +/* LED2 */ +#define SPEKTRUM_UART3_RCC_REG &RCC_APB1ENR +#define SPEKTRUM_UART3_RCC_DEV RCC_APB1ENR_USART3EN +#define SPEKTRUM_UART3_BANK GPIO_BANK_USART3_PR_RX +#define SPEKTRUM_UART3_PIN GPIO_USART3_PR_RX +#define SPEKTRUM_UART3_AF AFIO_MAPR_USART3_REMAP_PARTIAL_REMAP +#define SPEKTRUM_UART3_IRQ NVIC_USART3_IRQ +#define SPEKTRUM_UART3_ISR usart3_isr +#define SPEKTRUM_UART3_DEV USART3 + +/* LED3 */ +#define SPEKTRUM_UART5_RCC_REG &RCC_APB1ENR +#define SPEKTRUM_UART5_RCC_DEV RCC_APB1ENR_UART5EN +#define SPEKTRUM_UART5_BANK GPIO_BANK_UART5_RX +#define SPEKTRUM_UART5_PIN GPIO_UART5_RX +#define SPEKTRUM_UART5_AF 0 +#define SPEKTRUM_UART5_IRQ NVIC_UART5_IRQ +#define SPEKTRUM_UART5_ISR uart5_isr +#define SPEKTRUM_UART5_DEV UART5 + +/* PPM + */ + +/* + * On Lisa/S there is no really dedicated port available. But we could use a + * bunch of different pins to do PPM Input. + */ + +/* + * Default is PPM config 2, input on GPIO01 (Servo pin 6) + */ + +#ifndef PPM_CONFIG +#define PPM_CONFIG 3 +#endif + + +#if PPM_CONFIG == 1 +/* input on PA01 (UART1_RX) Diag port */ +#define USE_PPM_TIM1 1 +#define PPM_CHANNEL TIM_IC3 +#define PPM_TIMER_INPUT TIM_IC_IN_TI3 +#define PPM_IRQ NVIC_TIM1_UP_IRQ +#define PPM_IRQ2 NVIC_TIM1_CC_IRQ +// Capture/Compare InteruptEnable and InterruptFlag +#define PPM_CC_IE TIM_DIER_CC3IE +#define PPM_CC_IF TIM_SR_CC3IF +#define PPM_GPIO_PORT GPIOA +#define PPM_GPIO_PIN GPIO10 +#define PPM_GPIO_AF 0 + +#elif PPM_CONFIG == 2 +/* input on PA1 (Servo 6 pin) + On Lisa/S we could also use TIM5 IC2 instead. */ +#define USE_PPM_TIM2 1 +#define PPM_CHANNEL TIM_IC2 +#define PPM_TIMER_INPUT TIM_IC_IN_TI2 +#define PPM_IRQ NVIC_TIM2_IRQ +// Capture/Compare InteruptEnable and InterruptFlag +#define PPM_CC_IE TIM_DIER_CC2IE +#define PPM_CC_IF TIM_SR_CC2IF +#define PPM_GPIO_PORT GPIOA +#define PPM_GPIO_PIN GPIO1 +#define PPM_GPIO_AF 0 + +// Move default ADC timer +#if USE_AD_TIM2 +#undef USE_AD_TIM2 +#endif +#define USE_AD_TIM1 1 + +#elif PPM_CONFIG == 3 +/* input on PA3 (Aux RX pin) + On Lisa/S we could also use TIM5 IC4 instead. */ +#define USE_PPM_TIM2 1 +#define PPM_CHANNEL TIM_IC4 +#define PPM_TIMER_INPUT TIM_IC_IN_TI2 +#define PPM_IRQ NVIC_TIM2_IRQ +// Capture/Compare InteruptEnable and InterruptFlag +#define PPM_CC_IE TIM_DIER_CC4IE +#define PPM_CC_IF TIM_SR_CC4IF +#define PPM_GPIO_PORT GPIOA +#define PPM_GPIO_PIN GPIO3 +#define PPM_GPIO_AF 0 + +// Move default ADC timer +#if USE_AD_TIM2 +#undef USE_AD_TIM2 +#endif +#define USE_AD_TIM1 1 + +#else +#error "Unknown PPM config" + +#endif // PPM_CONFIG + +/* ADC */ + +// active ADC +#define USE_AD1 1 +#define USE_AD1_1 1 +#define USE_AD1_2 1 +#define USE_AD1_3 1 +#define USE_AD1_4 1 + +/* + * I2C + * + */ +/* Servo1 & Servo2 */ +#define I2C1_GPIO_PORT GPIOB +#define I2C1_GPIO_SCL GPIO6 +#define I2C1_GPIO_SDA GPIO7 + +/* GPS TX & RX */ +#define I2C2_GPIO_PORT GPIOB +#define I2C2_GPIO_SCL GPIO10 +#define I2C2_GPIO_SDA GPIO11 + +/* + * PWM + * + */ +#define PWM_USE_TIM4 1 +#define PWM_USE_TIM5 1 + + +#if USE_SERVOS_1AND2 + #if USE_I2C1 + #error "You cannot USE_SERVOS_1AND2 and USE_I2C1 at the same time" + #else + #define ACTUATORS_PWM_NB 6 + #define USE_PWM1 1 + #define USE_PWM2 1 + #define PWM_USE_TIM4 1 + #endif +#else + #define ACTUATORS_PWM_NB 4 +#endif + +#define USE_PWM3 1 +#define USE_PWM4 1 +#define USE_PWM5 1 +#define USE_PWM6 1 + +// Servo numbering on LisaM silkscreen/docs starts with 1 + +/* PWM_SERVO_x is the index of the servo in the actuators_pwm_values array */ +/* Because PWM1 and 2 can be disabled we put them at the index 4 & 5 so that it + * is easy to disable. + */ +#if USE_PWM1 +#define PWM_SERVO_1 4 +#define PWM_SERVO_1_TIMER TIM4 +#define PWM_SERVO_1_RCC_IOP RCC_APB2ENR_IOPBEN +#define PWM_SERVO_1_GPIO GPIOB +#define PWM_SERVO_1_PIN GPIO6 +#define PWM_SERVO_1_AF 0 +#define PWM_SERVO_1_OC TIM_OC1 +#define PWM_SERVO_1_OC_BIT (1<<0) +#else +#define PWM_SERVO_1_OC_BIT 0 +#endif + +#if USE_PWM2 +#define PWM_SERVO_2 5 +#define PWM_SERVO_2_TIMER TIM4 +#define PWM_SERVO_2_RCC_IOP RCC_APB2ENR_IOPBEN +#define PWM_SERVO_2_GPIO GPIOB +#define PWM_SERVO_2_PIN GPIO7 +#define PWM_SERVO_2_AF 0 +#define PWM_SERVO_2_OC TIM_OC2 +#define PWM_SERVO_2_OC_BIT (1<<1) +#else +#define PWM_SERVO_2_OC_BIT 0 +#endif + +#if USE_PWM3 +#define PWM_SERVO_3 0 +#define PWM_SERVO_3_TIMER TIM4 +#define PWM_SERVO_3_RCC_IOP RCC_APB2ENR_IOPBEN +#define PWM_SERVO_3_GPIO GPIOB +#define PWM_SERVO_3_PIN GPIO8 +#define PWM_SERVO_3_AF 0 +#define PWM_SERVO_3_OC TIM_OC3 +#define PWM_SERVO_3_OC_BIT (1<<2) +#else +#define PWM_SERVO_3_OC_BIT 0 +#endif + +#if USE_PWM4 +#define PWM_SERVO_4 1 +#define PWM_SERVO_4_TIMER TIM4 +#define PWM_SERVO_4_RCC_IOP RCC_APB2ENR_IOPBEN +#define PWM_SERVO_4_GPIO GPIOB +#define PWM_SERVO_4_PIN GPIO9 +#define PWM_SERVO_4_AF 0 +#define PWM_SERVO_4_OC TIM_OC4 +#define PWM_SERVO_4_OC_BIT (1<<3) +#else +#define PWM_SERVO_4_OC_BIT 0 +#endif + +#if USE_PWM5 +#define PWM_SERVO_5 2 +#define PWM_SERVO_5_TIMER TIM5 +#define PWM_SERVO_5_RCC_IOP RCC_APB2ENR_IOPAEN +#define PWM_SERVO_5_GPIO GPIOA +#define PWM_SERVO_5_PIN GPIO0 +#define PWM_SERVO_5_AF 0 +#define PWM_SERVO_5_OC TIM_OC1 +#define PWM_SERVO_5_OC_BIT (1<<0) +#else +#define PWM_SERVO_5_OC_BIT 0 +#endif + +#if USE_PWM6 +#define PWM_SERVO_6 3 +#define PWM_SERVO_6_TIMER TIM5 +#define PWM_SERVO_6_RCC_IOP RCC_APB2ENR_IOPAEN +#define PWM_SERVO_6_GPIO GPIOA +#define PWM_SERVO_6_PIN GPIO1 +#define PWM_SERVO_6_AF 0 +#define PWM_SERVO_6_OC TIM_OC2 +#define PWM_SERVO_6_OC_BIT (1<<1) +#else +#define PWM_SERVO_6_OC_BIT 0 +#endif + +/* servos 1-4 or 3-4 on TIM4 depending on USE_SERVOS_1AND2 */ +#define PWM_TIM4_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT) +/* servos 5-6 on TIM5 */ +#define PWM_TIM5_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT) + +#endif /* CONFIG_LISA_S_0_1_H */ From 83492da11e950ed7c20210dd3e46c9f302819faa Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 20 Aug 2013 15:43:58 +0200 Subject: [PATCH 167/309] Walkera Heli flying good. --- conf/airframes/esden/quady_ls01pwm.xml | 173 +++++++------- .../quadrotor_lisa_m_2_pwm_spektrum.xml | 2 +- conf/airframes/walkera_heli.xml | 218 ++++++++++++++++++ conf/boards/lisa_s_0.1.makefile | 4 +- .../radio_control_superbitrf_rc.makefile | 2 +- .../shared/telemetry_superbitrf.makefile | 7 +- conf/messages.xml | 4 +- conf/telemetry/default_rotorcraft.xml | 15 ++ sw/airborne/boards/lisa_s_0.1.h | 8 + sw/airborne/firmwares/rotorcraft/telemetry.h | 4 +- sw/airborne/subsystems/datalink/superbitrf.c | 72 ++++-- sw/airborne/subsystems/datalink/superbitrf.h | 6 +- 12 files changed, 408 insertions(+), 107 deletions(-) create mode 100644 conf/airframes/walkera_heli.xml diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index 9dc6032179..2360926974 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -12,25 +12,25 @@ - - - - + + + + - - - + + + - - - - + + + +
@@ -39,91 +39,95 @@ - - - + + +
- + - +
- - + +
- +
- - - + + + - + + + + +
- - - - - - - + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - + - +
@@ -131,19 +135,19 @@
- - - - + + + + - - - + + + - + - - + +
@@ -159,11 +163,11 @@
- +
- +
@@ -174,10 +178,11 @@ - - - - + + + + + @@ -185,21 +190,21 @@ - + - + - - - + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ +
+ + + +
+ +
+ +
+ + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/boards/lisa_s_0.1.makefile b/conf/boards/lisa_s_0.1.makefile index ffaeaf9a6c..51d99547e3 100644 --- a/conf/boards/lisa_s_0.1.makefile +++ b/conf/boards/lisa_s_0.1.makefile @@ -28,10 +28,10 @@ FLASH_MODE ?= SWD # # default LED configuration # -RADIO_CONTROL_LED ?= none +RADIO_CONTROL_LED ?= 3 BARO_LED ?= none AHRS_ALIGNER_LED ?= 2 -GPS_LED ?= 3 +GPS_LED ?= none SYS_TIME_LED ?= 1 # diff --git a/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile index 3774d22f3b..deac945a9a 100644 --- a/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile @@ -3,7 +3,7 @@ # ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE_SUPERBITRF -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/superbitrf_rc.h\" -ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI1 -DUSE_SPI_SLAVE1 +ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI2 -DUSE_SPI_SLAVE2 ifneq ($(RADIO_CONTROL_LED),none) ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) diff --git a/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile b/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile index 20781731ec..01f59768ea 100644 --- a/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile +++ b/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile @@ -2,10 +2,15 @@ # The superbitRF module as telemetry downlink/uplink # # +ap.CFLAGS += -DUSE_$(MODEM_PORT) +ap.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) ap.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=SuperbitRF ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=SUPERBITRF -ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI1 -DUSE_SPI_SLAVE1 + +#ap.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=SuperbitRF +#ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=SUPERBITRF +#ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI2 -DUSE_SPI_SLAVE2 ap.srcs += peripherals/cyrf6936.c ap.srcs += subsystems/datalink/downlink.c subsystems/datalink/superbitrf.c subsystems/datalink/pprz_transport.c ap.srcs += $(SRC_FIRMWARE)/datalink.c $(SRC_FIRMWARE)/telemetry.c diff --git a/conf/messages.xml b/conf/messages.xml index 75f5034bf9..0704620416 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -606,7 +606,9 @@ - + + + diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index 976962721c..30b46ac09f 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -6,6 +6,21 @@ + + + + + + + + + + + + + + + diff --git a/sw/airborne/boards/lisa_s_0.1.h b/sw/airborne/boards/lisa_s_0.1.h index fa3c3d49cb..1182c1954e 100644 --- a/sw/airborne/boards/lisa_s_0.1.h +++ b/sw/airborne/boards/lisa_s_0.1.h @@ -418,4 +418,12 @@ /* servos 5-6 on TIM5 */ #define PWM_TIM5_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT) +/* SuperbitRF mounted */ +#define SUPERBITRF_SPI_DEV spi2 +#define SUPERBITRF_RST_PORT GPIOC +#define SUPERBITRF_RST_PIN GPIO9 +#define SUPERBITRF_DRDY_PORT GPIOC +#define SUPERBITRF_DRDY_PIN GPIO6 +#define SUPERBITRF_FORCE_DSM2 FALSE + #endif /* CONFIG_LISA_S_0_1_H */ diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index e5f9df37e6..4891f0a0df 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -140,7 +140,9 @@ DOWNLINK_SEND_SUPERBITRF(_trans, _dev, \ &superbitrf.status, \ &superbitrf.cyrf6936.status, \ - &superbitrf.packet_count, \ + &superbitrf.irq_count, \ + &superbitrf.rx_packet_count, \ + &superbitrf.tx_packet_count, \ &superbitrf.transfer_timeouts, \ &superbitrf.resync_count, \ &superbitrf.uplink_count, \ diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 08e1a3128e..3557037123 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -36,27 +36,33 @@ #ifndef SUPERBITRF_SPI_DEV #define SUPERBITRF_SPI_DEV spi1 #endif +PRINT_CONFIG_VAR(SUPERBITRF_SPI_DEV); /* Default SuperbitRF RST PORT and PIN */ #ifndef SUPERBITRF_RST_PORT #define SUPERBITRF_RST_PORT GPIOC #endif +PRINT_CONFIG_VAR(SUPERBITRF_RST_PORT); #ifndef SUPERBITRF_RST_PIN #define SUPERBITRF_RST_PIN GPIO12 #endif +PRINT_CONFIG_VAR(SUPERBITRF_RST_PIN); /* Default SuperbitRF DRDY(IRQ) PORT and PIN */ #ifndef SUPERBITRF_DRDY_PORT #define SUPERBITRF_DRDY_PORT GPIOB #endif +PRINT_CONFIG_VAR(SUPERBITRF_DRDY_PORT); #ifndef SUPERBITRF_DRDY_PIN #define SUPERBITRF_DRDY_PIN GPIO1 #endif +PRINT_CONFIG_VAR(SUPERBITRF_DRDY_PIN); /* Default forcing in DSM2 mode is false */ #ifndef SUPERBITRF_FORCE_DSM2 #define SUPERBITRF_FORCE_DSM2 FALSE #endif +PRINT_CONFIG_VAR(SUPERBITRF_FORCE_DSM2); /* The superbitRF structure */ struct SuperbitRF superbitrf; @@ -175,7 +181,8 @@ void superbitrf_init(void) { superbitrf.status = SUPERBITRF_UNINIT; superbitrf.state = 0; superbitrf.timer = 0; - superbitrf.packet_count = 0; + superbitrf.rx_packet_count = 0; + superbitrf.tx_packet_count = 0; // Setup the transmit buffer superbitrf.tx_insert_idx = 0; @@ -188,7 +195,7 @@ void superbitrf_init(void) { gpio_setup_input(SUPERBITRF_DRDY_PORT, SUPERBITRF_DRDY_PIN); // Initialize the cyrf6936 chip - cyrf6936_init(&superbitrf.cyrf6936, &(SUPERBITRF_SPI_DEV), 1, SUPERBITRF_RST_PORT, SUPERBITRF_RST_PIN); + cyrf6936_init(&superbitrf.cyrf6936, &(SUPERBITRF_SPI_DEV), 2, SUPERBITRF_RST_PORT, SUPERBITRF_RST_PIN); } /** @@ -196,6 +203,7 @@ void superbitrf_init(void) { */ void superbitrf_event(void) { uint8_t i, pn_row, packet_size, data_code[16], tx_packet[16]; + static bool_t start_transfer = TRUE; // Check if the cyrf6936 isn't busy and the uperbitrf is initialized if(superbitrf.cyrf6936.status != CYRF6936_IDLE) @@ -207,13 +215,14 @@ void superbitrf_event(void) { if(gpio_get(SUPERBITRF_DRDY_PORT, SUPERBITRF_DRDY_PIN) == 0) { // Receive the packet cyrf6936_read_rx_irq_status_packet(&superbitrf.cyrf6936); + superbitrf.irq_count++; } /* Check if it is a valid receive */ if(superbitrf.cyrf6936.has_irq && (superbitrf.cyrf6936.rx_irq_status & CYRF_RXC_IRQ)) { // Handle the packet received superbitrf_receive_packet_cb((superbitrf.cyrf6936.rx_irq_status & CYRF_RXE_IRQ), superbitrf.cyrf6936.rx_status, superbitrf.cyrf6936.rx_packet); - superbitrf.packet_count++; + superbitrf.rx_packet_count++; // Reset the packet receiving superbitrf.cyrf6936.has_irq = FALSE; @@ -223,6 +232,7 @@ void superbitrf_event(void) { if(superbitrf.cyrf6936.has_irq && (superbitrf.cyrf6936.tx_irq_status & CYRF_TXC_IRQ)) { // Handle the send packet superbitrf_send_packet_cb((superbitrf.cyrf6936.rx_irq_status & CYRF_TXE_IRQ)); + superbitrf.tx_packet_count++; // Reset the packet receiving superbitrf.cyrf6936.has_irq = FALSE; @@ -238,9 +248,9 @@ void superbitrf_event(void) { if(cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_stratup_config, 11)) { // Check if need to go to bind or transfer if(gpio_get(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN) == 0) - superbitrf.status = SUPERBITRF_INIT_BINDING; - else - superbitrf.status = SUPERBITRF_INIT_TRANSFER; + start_transfer = FALSE; + + superbitrf.status = SUPERBITRF_INIT_BINDING; } break; @@ -268,16 +278,18 @@ void superbitrf_event(void) { } break; - /* When the superbitrf is initializing transfer */ - case SUPERBITRF_INIT_TRANSFER: - // Generate the DSMX channels - superbitrf_gen_dsmx_channels(); + /* When the superbitrf is initializing transfer */ + case SUPERBITRF_INIT_TRANSFER: + // Generate the DSMX channels + superbitrf_gen_dsmx_channels(); - // Try to write the transfer config - cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4); + // Try to write the transfer config + if(cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4)) { superbitrf.resync_count = 0; superbitrf.status = SUPERBITRF_SYNCING_A; - break; + superbitrf.state = 1; + } + break; /* When the superbitrf is in binding mode */ case SUPERBITRF_BINDING: @@ -313,6 +325,38 @@ void superbitrf_event(void) { superbitrf.state++; break; default: + // Check if need to go to transfer + if(start_transfer) { + // Initialize the binding values + #ifdef RADIO_TRANSMITTER_ID + PRINT_CONFIG_VAR(RADIO_TRANSMITTER_ID); + superbitrf.bind_mfg_id32 = RADIO_TRANSMITTER_ID; + superbitrf.bind_mfg_id[0] = (superbitrf.bind_mfg_id32 &0xFF); + superbitrf.bind_mfg_id[1] = (superbitrf.bind_mfg_id32 >>8 &0xFF); + superbitrf.bind_mfg_id[2] = (superbitrf.bind_mfg_id32 >>16 &0xFF); + superbitrf.bind_mfg_id[3] = (superbitrf.bind_mfg_id32 >>24 &0xFF); + + // Calculate some values based on the bind MFG id + superbitrf.crc_seed = ~((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1]); + superbitrf.sop_col = (superbitrf.bind_mfg_id[0] + superbitrf.bind_mfg_id[1] + superbitrf.bind_mfg_id[2] + 2) & 0x07; + superbitrf.data_col = 7 - superbitrf.sop_col; + #endif + #ifdef RADIO_TRANSMITTER_CHAN + PRINT_CONFIG_VAR(RADIO_TRANSMITTER_CHAN); + superbitrf.num_channels = RADIO_TRANSMITTER_CHAN; + #endif + #ifdef RADIO_TRANSMITTER_PROTOCOL + PRINT_CONFIG_VAR(RADIO_TRANSMITTER_PROTOCOL); + superbitrf.protocol = RADIO_TRANSMITTER_PROTOCOL; + superbitrf.resolution = (superbitrf.protocol & 0x10)>>4; + #endif + + // Start transfer + superbitrf.state = 0; + superbitrf.status = SUPERBITRF_INIT_TRANSFER; + break; + } + // Set the timer superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_BIND_RECV_TIME) % 0xFFFFFFFF; superbitrf.state = 0; @@ -568,7 +612,7 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui superbitrf.bind_mfg_id[2] = ~packet[2]; superbitrf.bind_mfg_id[3] = ~packet[3]; superbitrf.bind_mfg_id32 = ((superbitrf.bind_mfg_id[3] &0xFF) << 24 | (superbitrf.bind_mfg_id[2] &0xFF) << 16 | - (superbitrf.bind_mfg_id[1] &0xFF) << 8 | (superbitrf.bind_mfg_id[0] &0xFF)) &0xFFFFFFFF; + (superbitrf.bind_mfg_id[1] &0xFF) << 8 | (superbitrf.bind_mfg_id[0] &0xFF)); superbitrf.num_channels = packet[11]; superbitrf.protocol = packet[12]; superbitrf.resolution = (superbitrf.protocol & 0x10)>>4; diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index c6ac544d6e..f3b19b4498 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -37,7 +37,7 @@ #define SUPERBITRF_SYNC_RECV_TIME 7000 /**< The time to wait for a sync packet on a channel in microseconds */ #define SUPERBITRF_RECV_TIME 25000 /**< The time to wait for a transfer packet on a channel in microseconds */ #define SUPERBITRF_DATAWAIT_TIME 500 /**< The time to wait after RC receive to send a data packet in microseconds */ -#define SUPERBITRF_DATARECV_TIME 9000 /**< The time to wait for a data packet on a channel in microseconds */ +#define SUPERBITRF_DATARECV_TIME 10000 /**< The time to wait for a data packet on a channel in microseconds */ /* The different statuses the superbitRF can be in */ enum SuperbitRFStatus { @@ -81,7 +81,9 @@ struct SuperbitRF { uint8_t channels[23]; /**< The channels used for DSM2/DSMX */ uint8_t channel_idx; /**< The current channel index */ uint8_t channel; /**< The current channel number */ - uint32_t packet_count; /**< How many packets are received(also the invalid) */ + uint32_t irq_count; /**< How many interrupts are made */ + uint32_t rx_packet_count; /**< How many packets are received(also the invalid) */ + uint32_t tx_packet_count; /**< How many packets are send(also the invalid) */ uint32_t uplink_count; /**< How many valid uplink packages are received */ uint32_t rc_count; /**< How many valid RC packages are received */ From 2064e65ae710c34a40a8f2c185fb38cb5820f606 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 21 Aug 2013 14:36:05 +0200 Subject: [PATCH 168/309] Fixed binding --- conf/airframes/esden/quady_ls01pwm.xml | 6 +- conf/airframes/walkera_heli.xml | 51 +++- .../walkera_heli.xml.2013-08-21_140323 | 249 ++++++++++++++++++ conf/telemetry/default_rotorcraft.xml | 8 +- sw/airborne/peripherals/cyrf6936.c | 4 +- sw/airborne/subsystems/datalink/superbitrf.c | 111 +++++--- sw/airborne/subsystems/datalink/superbitrf.h | 4 +- 7 files changed, 370 insertions(+), 63 deletions(-) create mode 100644 conf/airframes/walkera_heli.xml.2013-08-21_140323 diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index 2360926974..b008276b18 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -179,9 +179,9 @@ - - - + + + diff --git a/conf/airframes/walkera_heli.xml b/conf/airframes/walkera_heli.xml index 7d73c38286..3fbc382ca2 100644 --- a/conf/airframes/walkera_heli.xml +++ b/conf/airframes/walkera_heli.xml @@ -27,8 +27,8 @@ - - + + @@ -40,21 +40,52 @@ - -
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
- +
+
@@ -131,9 +162,9 @@ - - - + + + @@ -167,7 +198,7 @@ - +
@@ -180,7 +211,7 @@
- + diff --git a/conf/airframes/walkera_heli.xml.2013-08-21_140323 b/conf/airframes/walkera_heli.xml.2013-08-21_140323 new file mode 100644 index 0000000000..b31e3d5882 --- /dev/null +++ b/conf/airframes/walkera_heli.xml.2013-08-21_140323 @@ -0,0 +1,249 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + +
+ + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index 30b46ac09f..51a5588909 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -99,13 +99,7 @@
- - - - - - - + diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 5bcd995155..691049baac 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -67,9 +67,9 @@ void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_ /* Reset the CYRF6936 chip (busy waiting) */ gpio_setup_output(rst_port, rst_pin); - gpio_output_high(rst_port, rst_pin); + gpio_set(rst_port, rst_pin); sys_time_usleep(100); - gpio_output_low(rst_port, rst_pin); + gpio_clear(rst_port, rst_pin); sys_time_usleep(100); /* Get the MFG ID */ diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 3557037123..4231d1dd90 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -202,7 +202,8 @@ void superbitrf_init(void) { * The superbitrf on event call */ void superbitrf_event(void) { - uint8_t i, pn_row, packet_size, data_code[16], tx_packet[16]; + uint8_t i, pn_row, data_code[16]; + static uint8_t packet_size, tx_packet[16]; static bool_t start_transfer = TRUE; // Check if the cyrf6936 isn't busy and the uperbitrf is initialized @@ -286,6 +287,8 @@ void superbitrf_event(void) { // Try to write the transfer config if(cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4)) { superbitrf.resync_count = 0; + superbitrf.packet_loss = FALSE; + superbitrf.packet_loss_bit = 0; superbitrf.status = SUPERBITRF_SYNCING_A; superbitrf.state = 1; } @@ -391,24 +394,32 @@ void superbitrf_event(void) { superbitrf.state++; break; case 3: - // Send a packet - if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { - tx_packet[0] = ~superbitrf.bind_mfg_id[2]; - tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1; - } else { - tx_packet[0] = superbitrf.bind_mfg_id[2]; - tx_packet[1] = (superbitrf.bind_mfg_id[3])+1; + // Create a new packet when no packet loss + if(!superbitrf.packet_loss) { + superbitrf.packet_loss_bit = !superbitrf.packet_loss_bit; + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { + tx_packet[0] = ~superbitrf.bind_mfg_id[2]; + tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit; + } else { + tx_packet[0] = superbitrf.bind_mfg_id[2]; + tx_packet[1] = (superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit; + } + + packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); + if(packet_size > 14) + packet_size = 14; + + for(i = 0; i < packet_size; i++) + tx_packet[i+2] = superbitrf.tx_buffer[(superbitrf.tx_extract_idx+i) %128]; } - packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); - if(packet_size > 14) - packet_size = 14; - - for(i = 0; i < packet_size; i++) - tx_packet[i+2] = superbitrf.tx_buffer[(superbitrf.tx_extract_idx+i) %128]; - + // Send a packet cyrf6936_send(&superbitrf.cyrf6936, tx_packet, packet_size+2); - superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; + + // Update the packet extraction + if(!superbitrf.packet_loss) + superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; + superbitrf.state++; break; case 4: @@ -485,29 +496,37 @@ void superbitrf_event(void) { break; case 2: // Wait before sending - superbitrf.state++; - //if (superbitrf.timer < get_sys_time_usec()) - //superbitrf.state++; + //superbitrf.state++; + if (superbitrf.timer < get_sys_time_usec()) + superbitrf.state++; break; case 3: - // Send a packet - if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { - tx_packet[0] = ~superbitrf.bind_mfg_id[2]; - tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1; - } else { - tx_packet[0] = superbitrf.bind_mfg_id[2]; - tx_packet[1] = (superbitrf.bind_mfg_id[3])+1; + // Create a new packet when no packet loss + if(!superbitrf.packet_loss) { + superbitrf.packet_loss_bit = !superbitrf.packet_loss_bit; + if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { + tx_packet[0] = ~superbitrf.bind_mfg_id[2]; + tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit; + } else { + tx_packet[0] = superbitrf.bind_mfg_id[2]; + tx_packet[1] = (superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit; + } + + packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); + if(packet_size > 14) + packet_size = 14; + + for(i = 0; i < packet_size; i++) + tx_packet[i+2] = superbitrf.tx_buffer[(superbitrf.tx_extract_idx+i) %128]; } - packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); - if(packet_size > 14) - packet_size = 14; - - for(i = 0; i < packet_size; i++) - tx_packet[i+2] = superbitrf.tx_buffer[(superbitrf.tx_extract_idx+i) %128]; - + // Send a packet cyrf6936_send(&superbitrf.cyrf6936, tx_packet, packet_size+2); - superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; + + // Update the packet extraction + if(!superbitrf.packet_loss) + superbitrf.tx_extract_idx = (superbitrf.tx_extract_idx+packet_size) %128; + superbitrf.state++; break; case 4: @@ -658,8 +677,14 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui if(packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)) { superbitrf.uplink_count++; + // Check if it is a data loss packet + if(packet[1] != (~superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit) && packet[1] != (superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit)) + superbitrf.packet_loss = TRUE; + else + superbitrf.packet_loss = FALSE; + // When it is a data packet, parse the packet if not busy already - if(!dl_msg_available) { + if(!dl_msg_available && !superbitrf.packet_loss) { for(i = 2; i < superbitrf.cyrf6936.rx_count; i++) { parse_pprz(&superbitrf.rx_transport, packet[i]); @@ -696,14 +721,14 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui } if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && - packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1))) { + packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1 && packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+2))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; } if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (superbitrf.bind_mfg_id[3]&0xFF) && - packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1))) { + packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1 && packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+2))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; @@ -760,14 +785,14 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui } if((IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) && (packet[0] != (~superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF) && - packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1))) { + packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+1 && packet[1] != (~superbitrf.bind_mfg_id[3]&0xFF)+2))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; } if((IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) && (packet[0] != (superbitrf.bind_mfg_id[2]&0xFF) || (packet[1] != (superbitrf.bind_mfg_id[3]&0xFF) && - packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1))) { + packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+1 && packet[1] != (superbitrf.bind_mfg_id[3]&0xFF)+2))) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; @@ -795,8 +820,14 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui } else { superbitrf.uplink_count++; + // Check if it is a data loss packet + if(packet[1] != (~superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit) && packet[1] != (superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit)) + superbitrf.packet_loss = TRUE; + else + superbitrf.packet_loss = FALSE; + // When it is a data packet, parse the packet if not busy already - if(!dl_msg_available) { + if(!dl_msg_available && !superbitrf.packet_loss) { for(i = 2; i < superbitrf.cyrf6936.rx_count; i++) { parse_pprz(&superbitrf.rx_transport, packet[i]); diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index f3b19b4498..4312c0f300 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -36,7 +36,7 @@ #define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ #define SUPERBITRF_SYNC_RECV_TIME 7000 /**< The time to wait for a sync packet on a channel in microseconds */ #define SUPERBITRF_RECV_TIME 25000 /**< The time to wait for a transfer packet on a channel in microseconds */ -#define SUPERBITRF_DATAWAIT_TIME 500 /**< The time to wait after RC receive to send a data packet in microseconds */ +#define SUPERBITRF_DATAWAIT_TIME 100 /**< The time to wait after RC receive to send a data packet in microseconds */ #define SUPERBITRF_DATARECV_TIME 10000 /**< The time to wait for a data packet on a channel in microseconds */ /* The different statuses the superbitRF can be in */ @@ -77,6 +77,8 @@ struct SuperbitRF { uint8_t timeouts; /**< The amount of timeouts */ uint32_t transfer_timeouts; /**< The amount of timeouts during transfer */ uint32_t resync_count; /**< The amount of resyncs needed during transfer */ + uint8_t packet_loss_bit; /**< The packet loss indicating bit */ + bool_t packet_loss; /**< When we have packet loss last packet */ uint8_t channels[23]; /**< The channels used for DSM2/DSMX */ uint8_t channel_idx; /**< The current channel index */ From d3ab30d97e5d4cca9164f3635174b2ace4575f30 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 21 Aug 2013 14:47:51 +0200 Subject: [PATCH 169/309] Edited config example --- conf/conf.xml.example | 252 ++++++++++++++++++++++-------------------- 1 file changed, 133 insertions(+), 119 deletions(-) diff --git a/conf/conf.xml.example b/conf/conf.xml.example index eac6d746c4..44f7ffad91 100644 --- a/conf/conf.xml.example +++ b/conf/conf.xml.example @@ -1,49 +1,14 @@ - - - - - - - - + name="BOOZ2" + ac_id="150" + airframe="airframes/examples/booz2.xml" + radio="radios/cockpitSX.xml" + telemetry="telemetry/default_rotorcraft.xml" + flight_plan="flight_plans/dummy.xml" + settings="settings/rotorcraft_basic.xml" + gui_color="white" + /> + + + - + name="Microjet" + ac_id="5" + airframe="airframes/examples/microjet.xml" + radio="radios/cockpitMM.xml" + telemetry="telemetry/default_fixedwing.xml" + flight_plan="flight_plans/basic.xml" + settings="settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/infrared.xml" + gui_color="#6293ba" + /> - - - - + + + + + + - From 0e94c634a96f9d95e362206ce598d7f30381dc73 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Thu, 22 Aug 2013 16:26:56 +0200 Subject: [PATCH 170/309] Better Body to IMU and superbitrf telemetry --- conf/airframes/esden/quady_ls01pwm.xml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index b008276b18..07c92c0557 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -48,9 +48,9 @@
- - - + + +
@@ -200,7 +200,7 @@ - + From 5f34ae6e8ee4ab0395f2dbbd1c7a2b442ad9e038 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 27 Aug 2013 19:31:51 +0200 Subject: [PATCH 171/309] Fast commit --- conf/airframes/walkera_V120D02S.xml | 248 +++++++++++++++++++ conf/settings/superbitrf.xml | 14 ++ sw/airborne/subsystems/datalink/superbitrf.c | 14 +- sw/airborne/subsystems/datalink/superbitrf.h | 2 +- 4 files changed, 270 insertions(+), 8 deletions(-) create mode 100644 conf/airframes/walkera_V120D02S.xml create mode 100644 conf/settings/superbitrf.xml diff --git a/conf/airframes/walkera_V120D02S.xml b/conf/airframes/walkera_V120D02S.xml new file mode 100644 index 0000000000..d25f606cd2 --- /dev/null +++ b/conf/airframes/walkera_V120D02S.xml @@ -0,0 +1,248 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + +
+ + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/settings/superbitrf.xml b/conf/settings/superbitrf.xml new file mode 100644 index 0000000000..93596bdab4 --- /dev/null +++ b/conf/settings/superbitrf.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 4231d1dd90..f26ede432e 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -60,7 +60,7 @@ PRINT_CONFIG_VAR(SUPERBITRF_DRDY_PIN); /* Default forcing in DSM2 mode is false */ #ifndef SUPERBITRF_FORCE_DSM2 -#define SUPERBITRF_FORCE_DSM2 FALSE +#define SUPERBITRF_FORCE_DSM2 TRUE #endif PRINT_CONFIG_VAR(SUPERBITRF_FORCE_DSM2); @@ -434,7 +434,7 @@ void superbitrf_event(void) { } // Switch channel, sop code, data code and crc - superbitrf.channel = (superbitrf.channel + 1) % 0x62; //TODO fix define + superbitrf.channel = (superbitrf.channel + 2) % 0x4F; //TODO fix define superbitrf.crc_seed = ~superbitrf.crc_seed; pn_row = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? superbitrf.channel % 5 : (superbitrf.channel-2) % 5; @@ -483,8 +483,8 @@ void superbitrf_event(void) { cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); superbitrf.state++; - // When we don't have enough time - if(superbitrf.timeouts > 0 || superbitrf.timing2 < 10000 || superbitrf.timing1 > 10000) { + // Only send on channel 2 + if(superbitrf.crc_seed != ((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { superbitrf.state = 8; // Set the timer superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; @@ -506,10 +506,10 @@ void superbitrf_event(void) { superbitrf.packet_loss_bit = !superbitrf.packet_loss_bit; if(IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2) { tx_packet[0] = ~superbitrf.bind_mfg_id[2]; - tx_packet[1] = (~superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit; + tx_packet[1] = ((~superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit) % 0xFF; } else { tx_packet[0] = superbitrf.bind_mfg_id[2]; - tx_packet[1] = (superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit; + tx_packet[1] = ((superbitrf.bind_mfg_id[3])+1+superbitrf.packet_loss_bit) % 0xFF; } packet_size = (superbitrf.tx_insert_idx-superbitrf.tx_extract_idx+128 %128); @@ -678,7 +678,7 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui superbitrf.uplink_count++; // Check if it is a data loss packet - if(packet[1] != (~superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit) && packet[1] != (superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit)) + if(packet[1] != (~superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit)%0xFF && packet[1] != (superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit)%0xFF) superbitrf.packet_loss = TRUE; else superbitrf.packet_loss = FALSE; diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index 4312c0f300..907cbb5222 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -35,7 +35,7 @@ /* The timings in microseconds */ #define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ #define SUPERBITRF_SYNC_RECV_TIME 7000 /**< The time to wait for a sync packet on a channel in microseconds */ -#define SUPERBITRF_RECV_TIME 25000 /**< The time to wait for a transfer packet on a channel in microseconds */ +#define SUPERBITRF_RECV_TIME 22000 /**< The time to wait for a transfer packet on a channel in microseconds */ #define SUPERBITRF_DATAWAIT_TIME 100 /**< The time to wait after RC receive to send a data packet in microseconds */ #define SUPERBITRF_DATARECV_TIME 10000 /**< The time to wait for a data packet on a channel in microseconds */ From 664df087fd511cc1aef4bac0d8ca395b956b1eca Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 27 Aug 2013 20:17:17 +0200 Subject: [PATCH 172/309] [airframes] MicroMavRick --- conf/airframes/CDW/MicroMavRickLisaS.xml | 191 +++++++++++++++++++++++ 1 file changed, 191 insertions(+) create mode 100644 conf/airframes/CDW/MicroMavRickLisaS.xml diff --git a/conf/airframes/CDW/MicroMavRickLisaS.xml b/conf/airframes/CDW/MicroMavRickLisaS.xml new file mode 100644 index 0000000000..18ebcc7583 --- /dev/null +++ b/conf/airframes/CDW/MicroMavRickLisaS.xml @@ -0,0 +1,191 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + +
+ + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + +
+ +
+ + +
+ +
+ + + + + +
+ +
+ + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + +
+ +
+ + + + + + + + +
+ +
+ + + + + +
+ +
From 9a672b08692e87144c6cb976d47815020a1e08da Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 28 Aug 2013 12:54:41 +0200 Subject: [PATCH 173/309] Magneto axis correction --- conf/airframes/esden/quady_ls01pwm.xml | 35 ++++++++++++++++--- .../shared/imu_lisa_s_v0.1.makefile | 2 +- sw/airborne/subsystems/datalink/superbitrf.c | 17 ++++++++- sw/airborne/subsystems/datalink/superbitrf.h | 1 + .../subsystems/imu/imu_aspirin_2_spi.c | 6 ++++ 5 files changed, 54 insertions(+), 7 deletions(-) diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index 07c92c0557..c3b9d8fcb2 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -45,12 +45,37 @@
- -
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
@@ -179,9 +204,9 @@ - - - + + + diff --git a/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile b/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile index 536031592b..7f75e5c3a9 100644 --- a/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile +++ b/conf/firmwares/subsystems/shared/imu_lisa_s_v0.1.makefile @@ -53,7 +53,7 @@ include $(CFG_SHARED)/spi_master.makefile IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_SLAVE_IDX=SPI_SLAVE0 IMU_ASPIRIN_2_CFLAGS += -DASPIRIN_2_SPI_DEV=spi1 -IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI1 +IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI1 -DLISA_S # Slave select configuration # SLAVE0 is on PA4 (NSS) (MPU600 CS) IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE0 diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index f26ede432e..40276314d0 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -426,6 +426,19 @@ void superbitrf_event(void) { //TODO: check timeout? (Waiting for send) break; case 5: + superbitrf.state = 7; + break; + // Start receiving + cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATARECVB_TIME) % 0xFFFFFFFF; + superbitrf.state++; + break; + case 6: + // Wait for telemetry data + if (superbitrf.timer < get_sys_time_usec()) + superbitrf.state++; + break; + case 7: // When DSMX we don't need to switch if(IS_DSMX(superbitrf.protocol) && !SUPERBITRF_FORCE_DSM2) { superbitrf.state++; @@ -445,7 +458,7 @@ void superbitrf_event(void) { superbitrf.state++; break; - case 6: + case 8: // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; @@ -826,6 +839,8 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui else superbitrf.packet_loss = FALSE; + superbitrf.packet_loss = FALSE; + // When it is a data packet, parse the packet if not busy already if(!dl_msg_available && !superbitrf.packet_loss) { for(i = 2; i < superbitrf.cyrf6936.rx_count; i++) { diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index 907cbb5222..8baa147f1a 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -38,6 +38,7 @@ #define SUPERBITRF_RECV_TIME 22000 /**< The time to wait for a transfer packet on a channel in microseconds */ #define SUPERBITRF_DATAWAIT_TIME 100 /**< The time to wait after RC receive to send a data packet in microseconds */ #define SUPERBITRF_DATARECV_TIME 10000 /**< The time to wait for a data packet on a channel in microseconds */ +#define SUPERBITRF_DATARECVB_TIME 6000 /**< The time to wait for a data packet on a channel during bind in microseconds */ /* The different statuses the superbitRF can be in */ enum SuperbitRFStatus { diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c index 0fcd038a6e..207b0df6ab 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c @@ -174,10 +174,16 @@ void imu_aspirin2_event(void) -imu_aspirin2.mpu.data_accel.vect.x, imu_aspirin2.mpu.data_accel.vect.z); VECT3_ASSIGN(imu.mag_unscaled, -mag.x, -mag.y, mag.z); +#else +#ifdef LISA_S + RATES_COPY(imu.gyro_unscaled, imu_aspirin2.mpu.data_rates.rates); + VECT3_COPY(imu.accel_unscaled, imu_aspirin2.mpu.data_accel.vect); + VECT3_COPY(imu.mag_unscaled, mag); #else RATES_COPY(imu.gyro_unscaled, imu_aspirin2.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_aspirin2.mpu.data_accel.vect); VECT3_ASSIGN(imu.mag_unscaled, mag.y, -mag.x, mag.z) +#endif #endif imu_aspirin2.mpu.data_available = FALSE; imu_aspirin2.gyro_valid = TRUE; From b58bf64e7fb2cab4162d54d10b6f1ec311fb9a59 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 28 Aug 2013 12:55:55 +0200 Subject: [PATCH 174/309] Config file with airframes added --- conf/conf.xml.example | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/conf/conf.xml.example b/conf/conf.xml.example index 44f7ffad91..f51432fe66 100644 --- a/conf/conf.xml.example +++ b/conf/conf.xml.example @@ -19,16 +19,6 @@ settings=" settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/ins_neutrals.xml" gui_color="blue" /> - + Date: Wed, 28 Aug 2013 15:48:18 +0200 Subject: [PATCH 175/309] channels reversed --- conf/airframes/CDW/MicroMavRickLisaS.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/conf/airframes/CDW/MicroMavRickLisaS.xml b/conf/airframes/CDW/MicroMavRickLisaS.xml index 18ebcc7583..c183d7664c 100644 --- a/conf/airframes/CDW/MicroMavRickLisaS.xml +++ b/conf/airframes/CDW/MicroMavRickLisaS.xml @@ -39,8 +39,8 @@ - - + + From 8a9011f9007dc75898ffe5030e4c887b2b69aeb0 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 28 Aug 2013 16:04:28 +0200 Subject: [PATCH 176/309] Airframes walkera update --- conf/airframes/esden/quady_ls01pwm.xml | 6 ++++++ conf/airframes/walkera_V120D02S.xml | 20 ++++++++++---------- 2 files changed, 16 insertions(+), 10 deletions(-) diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index c3b9d8fcb2..ca1279a830 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -76,6 +76,11 @@ + + + + +
@@ -85,6 +90,7 @@
+
diff --git a/conf/airframes/walkera_V120D02S.xml b/conf/airframes/walkera_V120D02S.xml index d25f606cd2..950f93139f 100644 --- a/conf/airframes/walkera_V120D02S.xml +++ b/conf/airframes/walkera_V120D02S.xml @@ -12,9 +12,9 @@ - - - + + + @@ -34,9 +34,9 @@ - - - + + + @@ -195,10 +195,10 @@ - - - - + + + + From 97563ded23bcee916f7e7c233620ed352825c2f8 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Thu, 29 Aug 2013 14:56:02 +0200 Subject: [PATCH 177/309] [superbitrf] Cleanup --- conf/airframes/TUDelft/IMAV2013/conf.xml | 45 +++ .../IMAV2013/mavrick_lisa_s.xml} | 26 +- .../IMAV2013/quadrotor_lisa_s.xml} | 141 ++++----- .../IMAV2013}/walkera_V120D02S.xml | 53 +--- .../IMAV2013/walkera_genius_v1.xml} | 50 +--- conf/airframes/esden/quady_ls01pwm.xml | 210 ++++++------- .../quadrotor_lisa_m_2_pwm_spektrum.xml | 46 +-- conf/airframes/examples/quadrotor_lisa_s.xml | 239 +++++++++++++++ conf/conf.xml.example | 276 +++++++++--------- conf/firmwares/rotorcraft.makefile | 4 +- conf/settings/superbitrf.xml | 14 - conf/telemetry/default_rotorcraft.xml | 25 +- sw/airborne/boards/lisa_s/baro_board.h | 55 +--- 13 files changed, 651 insertions(+), 533 deletions(-) create mode 100644 conf/airframes/TUDelft/IMAV2013/conf.xml rename conf/airframes/{CDW/MicroMavRickLisaS.xml => TUDelft/IMAV2013/mavrick_lisa_s.xml} (90%) rename conf/airframes/{walkera_heli.xml.2013-08-21_140323 => TUDelft/IMAV2013/quadrotor_lisa_s.xml} (62%) rename conf/airframes/{ => TUDelft/IMAV2013}/walkera_V120D02S.xml (80%) rename conf/airframes/{walkera_heli.xml => TUDelft/IMAV2013/walkera_genius_v1.xml} (81%) create mode 100644 conf/airframes/examples/quadrotor_lisa_s.xml delete mode 100644 conf/settings/superbitrf.xml diff --git a/conf/airframes/TUDelft/IMAV2013/conf.xml b/conf/airframes/TUDelft/IMAV2013/conf.xml new file mode 100644 index 0000000000..76978844ac --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/conf.xml @@ -0,0 +1,45 @@ + + + + + + + + + diff --git a/conf/airframes/CDW/MicroMavRickLisaS.xml b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml similarity index 90% rename from conf/airframes/CDW/MicroMavRickLisaS.xml rename to conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml index c183d7664c..bc5da2d9bc 100644 --- a/conf/airframes/CDW/MicroMavRickLisaS.xml +++ b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml @@ -1,24 +1,26 @@ - + - + - - - - - - - - + + + + + + diff --git a/conf/airframes/walkera_heli.xml.2013-08-21_140323 b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml similarity index 62% rename from conf/airframes/walkera_heli.xml.2013-08-21_140323 rename to conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml index b31e3d5882..8a89ed12d7 100644 --- a/conf/airframes/walkera_heli.xml.2013-08-21_140323 +++ b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml @@ -2,21 +2,20 @@ - + - - - - - + + + + @@ -27,23 +26,29 @@ - - - - - - - - - - - + + + + + +
+ + + + + + + + + +
+
- - - + + + @@ -64,41 +69,45 @@ - - - - - - - + + + + + + + - - - - + + + +
- +
- +
- - - + + + - + + + + +
@@ -130,15 +139,15 @@ - - - + + + - - - + + + - + @@ -188,6 +197,12 @@
+
+ + + +
+ @@ -195,31 +210,33 @@ - - - - + + + + + + + + + + - - + - + - - @@ -235,15 +252,5 @@ - diff --git a/conf/airframes/walkera_V120D02S.xml b/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml similarity index 80% rename from conf/airframes/walkera_V120D02S.xml rename to conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml index 950f93139f..5df82f5f45 100644 --- a/conf/airframes/walkera_V120D02S.xml +++ b/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml @@ -1,15 +1,15 @@ - + - + @@ -64,18 +64,13 @@ - + - - - - -
@@ -85,13 +80,12 @@
- +
- @@ -99,7 +93,6 @@ -
@@ -195,8 +188,8 @@ - - + + @@ -216,33 +209,5 @@ - - - - - - - - - - - - - - - - - - diff --git a/conf/airframes/walkera_heli.xml b/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml similarity index 81% rename from conf/airframes/walkera_heli.xml rename to conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml index 3fbc382ca2..3c66aae2b2 100644 --- a/conf/airframes/walkera_heli.xml +++ b/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml @@ -1,15 +1,15 @@ - + - + @@ -91,7 +91,6 @@
- @@ -99,7 +98,6 @@ -
@@ -195,10 +193,10 @@ - - - - + + + + @@ -211,39 +209,11 @@ - + - - - - - - - - - - - - - - - - - - diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index ca1279a830..9dc6032179 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -12,25 +12,25 @@ - - - - + + + + - - - + + + - - - - + + + +
@@ -39,126 +39,91 @@ - - - + + +
+ +
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + +
- - + +
- - +
- - - + + + - - - - - +
- - - - - - - + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - + - +
@@ -166,19 +131,19 @@
- - - - + + + + - - - + + + - + - - + +
@@ -194,11 +159,11 @@
- +
- +
@@ -209,11 +174,10 @@ - - - - - + + + + @@ -221,21 +185,21 @@ - + - + - - - + + + - + @@ -39,10 +41,10 @@ - - - - + + + + @@ -59,9 +61,9 @@ - - - + + +
@@ -88,7 +90,7 @@ - +
@@ -153,22 +155,22 @@ - - - + + + - - - + + + - - - + + + - - - + + +
@@ -189,7 +191,7 @@
- + diff --git a/conf/airframes/examples/quadrotor_lisa_s.xml b/conf/airframes/examples/quadrotor_lisa_s.xml new file mode 100644 index 0000000000..a46f343030 --- /dev/null +++ b/conf/airframes/examples/quadrotor_lisa_s.xml @@ -0,0 +1,239 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + +
+ + +
+ + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ +
+ +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/conf.xml.example b/conf/conf.xml.example index f51432fe66..893aba9cec 100644 --- a/conf/conf.xml.example +++ b/conf/conf.xml.example @@ -1,14 +1,59 @@ + + + + name="BOOZ2" + ac_id="150" + airframe="airframes/examples/booz2.xml" + radio="radios/cockpitSX.xml" + telemetry="telemetry/default_rotorcraft.xml" + flight_plan="flight_plans/dummy.xml" + settings="settings/rotorcraft_basic.xml" + gui_color="white" + /> + + + + + + - - + + name="Microjet" + ac_id="5" + airframe="airframes/examples/microjet.xml" + radio="radios/cockpitMM.xml" + telemetry="telemetry/default_fixedwing.xml" + flight_plan="flight_plans/basic.xml" + settings="settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/infrared.xml" + gui_color="#6293ba" + /> + + + + - - - - - - - - - + + diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index 575c28dabb..75aeb5062e 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -194,7 +194,9 @@ else ifeq ($(BOARD), lisa_s) ap.CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE1 ap.CFLAGS += -DMS5611_SPI_DEV=spi1 ap.CFLAGS += -DMS5611_SLAVE_DEV=SPI_SLAVE1 - ap.srcs += boards/lisa_m/baro_ms5611_spi.c + ap.srcs += peripherals/ms5611.c + ap.srcs += peripherals/ms5611_spi.c + ap.srcs += subsystems/sensors/baro_ms5611_spi.c ap.CFLAGS += -DBARO_MS5611_SPI # Lia baro (no bmp onboard) diff --git a/conf/settings/superbitrf.xml b/conf/settings/superbitrf.xml deleted file mode 100644 index 93596bdab4..0000000000 --- a/conf/settings/superbitrf.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - \ No newline at end of file diff --git a/conf/telemetry/default_rotorcraft.xml b/conf/telemetry/default_rotorcraft.xml index 51a5588909..2a79fd2c04 100644 --- a/conf/telemetry/default_rotorcraft.xml +++ b/conf/telemetry/default_rotorcraft.xml @@ -6,21 +6,6 @@ - - - - - - - - - - - - - - - @@ -33,7 +18,7 @@ - + @@ -99,7 +84,13 @@ - + + + + + + + diff --git a/sw/airborne/boards/lisa_s/baro_board.h b/sw/airborne/boards/lisa_s/baro_board.h index 42014ddeee..7581ef4de3 100644 --- a/sw/airborne/boards/lisa_s/baro_board.h +++ b/sw/airborne/boards/lisa_s/baro_board.h @@ -9,59 +9,8 @@ #include "std.h" -// for right now we abuse this file for the ms5611 baro on aspirin as well -#if !BARO_MS5611_I2C && !BARO_MS5611 +extern void baro_event(void (*b_abs_handler)(void)); -#include "mcu_periph/i2c.h" - -// absolute addr -#define BMP085_ADDR 0xEE -// Over sample setting (0-3) -#define BMP085_OSS 3 - -enum LisaBaroStatus { - LBS_UNINITIALIZED, - LBS_REQUEST, - LBS_READING, - LBS_READ, - LBS_REQUEST_TEMP, - LBS_READING_TEMP, - LBS_READ_TEMP, -}; - -struct BaroBoard { - enum LisaBaroStatus status; -}; - -struct bmp085_baro_calibration { - // These values come from EEPROM on sensor - int16_t ac1; - int16_t ac2; - int16_t ac3; - uint16_t ac4; - uint16_t ac5; - uint16_t ac6; - int16_t b1; - int16_t b2; - int16_t mb; - int16_t mc; - int16_t md; - - // These values are calculated - int32_t b5; -}; - -extern struct BaroBoard baro_board; -extern struct i2c_transaction baro_trans; -extern struct bmp085_baro_calibration calibration; - -extern void baro_board_send_reset(void); -extern void baro_board_send_config(void); - -#endif // !BARO_MS5611_xx - -extern void baro_event(void (*b_abs_handler)(void), void (*b_diff_handler)(void)); - -#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler,_b_diff_handler) +#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler) #endif /* BOARDS_LISA_M_BARO_H */ From e613e79fbe9c0c387cecd161877a8c802b2967a0 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 29 Aug 2013 15:28:33 +0200 Subject: [PATCH 178/309] [tools] calibration: automatically choose noise_threshold --- sw/tools/calibration/calibrate.py | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/sw/tools/calibration/calibrate.py b/sw/tools/calibration/calibrate.py index 2fb739ff18..9aaf3940b6 100755 --- a/sw/tools/calibration/calibrate.py +++ b/sw/tools/calibration/calibrate.py @@ -20,6 +20,7 @@ # Boston, MA 02111-1307, USA. # +from __future__ import print_function import sys import os @@ -66,12 +67,12 @@ def main(): sensor_ref = 9.81 sensor_res = 10 noise_window = 20; - noise_threshold = 40; + #noise_threshold = 40; elif options.sensor == "MAG": sensor_ref = 1. sensor_res = 11 noise_window = 10; - noise_threshold = 1000; + #noise_threshold = 1000; if not filename.endswith(".data"): parser.error("Please specify a *.data log file") @@ -86,12 +87,20 @@ def main(): if options.verbose: print("found "+str(len(measurements))+" records") + # estimate the noise threshold + # find the median of measurement vector lenght + meas_median = scipy.median(scipy.array([scipy.linalg.norm(v) for v in measurements])) + # set noise threshold to be below 10% of that + noise_threshold = meas_median * 0.1 + if options.verbose: + print("Using noise threshold of", noise_threshold, "for filtering.") + # filter out noisy measurements flt_meas, flt_idx = calibration_utils.filter_meas(measurements, noise_window, noise_threshold) if options.verbose: - print("remaining "+str(len(flt_meas))+" after low pass") + print("remaining "+str(len(flt_meas))+" after filtering") if len(flt_meas) == 0: - print("Error: found zero IMU_"+options.sensor+"_RAW measurements for aircraft with id "+options.ac_id+" in log file after low pass!") + print("Error: found zero IMU_"+options.sensor+"_RAW measurements for aircraft with id "+options.ac_id+" in log file after filtering!") sys.exit(1) # get an initial min/max guess From a244d214a5ba1c6bddc99e6edd66daf33aafd509 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Thu, 29 Aug 2013 17:44:00 +0200 Subject: [PATCH 179/309] [ARDrone] LED driver fixed --- .../boards/ardrone/actuators_ardrone2_raw.c | 48 +++++++++++++++++-- .../boards/ardrone/actuators_ardrone2_raw.h | 2 + sw/airborne/boards/ardrone/baro_board.c | 2 +- sw/airborne/boards/ardrone/navdata.c | 4 +- 4 files changed, 50 insertions(+), 6 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index 353c5a5050..1989b492e7 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -123,7 +123,10 @@ void actuators_ardrone_init(void) gpio_set(107,1); //all leds green -// actuators_ardrone_set_leds(MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDGREEN); + //actuators_ardrone_set_leds(0,0,0,0); + //actuators_ardrone_set_leds(MOT_LEDRED, MOT_LEDRED, MOT_LEDRED, MOT_LEDRED); + //actuators_ardrone_set_leds(MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDGREEN); + actuators_ardrone_set_leds(MOT_LEDRED,MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDRED); } int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) { @@ -136,6 +139,13 @@ void actuators_ardrone_commit(void) actuators_ardrone_set_pwm(actuators_pwm_values[0], actuators_pwm_values[1], actuators_pwm_values[2], actuators_pwm_values[3]); } +uint8_t ardrone_error_flag = 0; + +void actuators_ardrone_error(void) +{ + ardrone_error_flag = 1; +} + /** * Write motor speed command * cmd = 001aaaaa aaaabbbb bbbbbccc ccccccdd ddddddd0 @@ -149,17 +159,49 @@ void actuators_ardrone_set_pwm(uint16_t pwm0, uint16_t pwm1, uint16_t pwm2, uint cmd[3] = ((pwm2&0x1ff)<<2) | ((pwm3&0x1ff)>>7); cmd[4] = ((pwm3&0x1ff)<<1); write(mot_fd, cmd, 5); + + if (ardrone_error_flag == 1) + { + static uint8_t blink = 0; + blink++; + if (blink == 80) + { + actuators_ardrone_set_leds(MOT_LEDRED, MOT_LEDRED, MOT_LEDRED, MOT_LEDRED); + blink = 0; + } + else if (blink == 40) + { + actuators_ardrone_set_leds(MOT_LEDOFF, MOT_LEDOFF, MOT_LEDOFF, MOT_LEDOFF); + } + else if (blink == 20) + { + //actuators_ardrone_set_leds(MOT_LEDORANGE, MOT_LEDORANGE, MOT_LEDOFF, MOT_LEDORANGE); + } + } + } /** * Write LED command * cmd = 011grgrg rgrxxxxx (this is ardrone1 format, we need ardrone2 format) */ + +/* + +led0 = RearLeft +led1 = RearRight +led2 = FrontRight +led3 = FrontLeft + +*/ + void actuators_ardrone_set_leds(uint8_t led0, uint8_t led1, uint8_t led2, uint8_t led3) { uint8_t cmd[2]; - cmd[0]=0x60 | ((led0&3)<<3) | ((led1&3)<<1) | ((led2&3)>>1); - cmd[1]=((led2&3)<<7) | ((led3&3)<<5); + + cmd[0]=0x60 | ((led0&1)<<4) | ((led1&1)<<3) | ((led2&1)<<2) | ((led3&1) <<1); + cmd[1]=((led0&2)<<3) | ((led1&2)<<2) | ((led2&2)<<1) | ((led3&2)<<0); + write(mot_fd, cmd, 2); } diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h index 2a66ba5dde..12b03089a6 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h @@ -52,6 +52,8 @@ uint16_t actuators_pwm_values[ACTUATORS_ARDRONE_NB]; extern void actuators_ardrone_commit(void); extern void actuators_ardrone_init(void); +extern void actuators_ardrone_error(void); + int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen); void actuators_ardrone_set_pwm(uint16_t pwm0, uint16_t pwm1, uint16_t pwm2, uint16_t pwm3); diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index ce0a1591a6..4320e0a3a1 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -69,7 +69,7 @@ static inline int32_t baro_apply_calibration_temp(int32_t tmp_raw) return (baro_calibration.b5 + 8) >> 4; } -void baro_periodic(void) +void baro_periodic(void) { } diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 683426faba..7d0e185dcb 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -185,7 +185,7 @@ void baro_update_logic(void) { // temp was updated temp_or_press_was_updated_last = 1; - + // This means that press must remain constant if (lastpressval != 0) { @@ -240,7 +240,7 @@ void navdata_update() // if ( navdata_checksum() == 0 ) { memcpy(navdata, port->buffer, NAVDATA_PACKET_SIZE); - + // Invert byte order so that TELEMETRY works better uint8_t tmp; uint8_t* p = (uint8_t*) &(navdata->pressure); From 271931bbfc6db1ff5bccc26b2b0a6fa91651cf8d Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Thu, 29 Aug 2013 21:05:09 +0200 Subject: [PATCH 180/309] [airframes] Gyro and Accelero sensitivity from datasheet by default, gyro neutral = automatic by filter, acc neutral and mag neutral need to be calibrated --- .../TUDelft/IMAV2013/mavrick_lisa_s.xml | 15 ------------- .../TUDelft/IMAV2013/quadrotor_lisa_s.xml | 15 ------------- .../TUDelft/IMAV2013/walkera_V120D02S.xml | 21 +++---------------- .../TUDelft/IMAV2013/walkera_genius_v1.xml | 21 +++---------------- conf/airframes/examples/quadrotor_lisa_s.xml | 15 ------------- 5 files changed, 6 insertions(+), 81 deletions(-) diff --git a/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml index bc5da2d9bc..4955b2c088 100644 --- a/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml @@ -81,25 +81,10 @@ - - - - - - - - - - - - - - - diff --git a/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml index 8a89ed12d7..69108b84fa 100644 --- a/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml @@ -50,25 +50,10 @@ - - - - - - - - - - - - - - - diff --git a/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml b/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml index 5df82f5f45..a11d9f889b 100644 --- a/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml +++ b/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml @@ -34,9 +34,9 @@ - - - + + + @@ -45,25 +45,10 @@ - - - - - - - - - - - - - - - diff --git a/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml b/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml index 3c66aae2b2..aa31e8d4ec 100644 --- a/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml +++ b/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml @@ -34,9 +34,9 @@ - - - + + + @@ -45,25 +45,10 @@ - - - - - - - - - - - - - - - diff --git a/conf/airframes/examples/quadrotor_lisa_s.xml b/conf/airframes/examples/quadrotor_lisa_s.xml index a46f343030..640ec29d44 100644 --- a/conf/airframes/examples/quadrotor_lisa_s.xml +++ b/conf/airframes/examples/quadrotor_lisa_s.xml @@ -50,25 +50,10 @@ - - - - - - - - - - - - - - - From bb3043547d6f83607c5c60aa2dc8414bcf9ad7ae Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 01:01:53 +0200 Subject: [PATCH 181/309] [rotorcraft][guidance] fixes for vertical nav --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index 2287d88252..6f2bcc950c 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -220,13 +220,16 @@ void guidance_v_run(bool_t in_flight) { run_hover_loop(in_flight); } else if (vertical_mode == VERTICAL_MODE_CLIMB) { + guidance_v_z_sp = stateGetPositionNed_i()->z; guidance_v_zd_sp = -nav_climb; gv_update_ref_from_zd_sp(guidance_v_zd_sp); - nav_flight_altitude = -guidance_v_z_sp; run_hover_loop(in_flight); } else if (vertical_mode == VERTICAL_MODE_MANUAL) { - guidance_v_z_sp = -nav_flight_altitude; // For display only + guidance_v_z_sp = stateGetPositionNed_i()->z; + guidance_v_zd_sp = stateGetSpeedNed_i()->z; + GuidanceVSetRef(guidance_v_z_sp, guidance_v_zd_sp, 0); + guidance_v_z_sum_err = 0; guidance_v_delta_t = nav_throttle; } #if NO_RC_THRUST_LIMIT From a45a9872f4ec9faaa030e8410f1466da9b11c873 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 01:43:21 +0200 Subject: [PATCH 182/309] [rotorcraft] fix takeoff-land-takeoff in nav via flightplan --- .../airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml | 2 ++ conf/flight_plans/rotorcraft_basic.xml | 4 ++++ sw/airborne/firmwares/rotorcraft/navigation.c | 7 +++++++ sw/airborne/firmwares/rotorcraft/navigation.h | 1 + 4 files changed, 14 insertions(+) diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index e9e9aa9dba..376d96d57e 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -39,6 +39,8 @@ + + diff --git a/conf/flight_plans/rotorcraft_basic.xml b/conf/flight_plans/rotorcraft_basic.xml index e9798d0de1..de897364e2 100644 --- a/conf/flight_plans/rotorcraft_basic.xml +++ b/conf/flight_plans/rotorcraft_basic.xml @@ -71,8 +71,12 @@ + + + + diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c index f78723abbf..40d86cc7a7 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.c +++ b/sw/airborne/firmwares/rotorcraft/navigation.c @@ -341,4 +341,11 @@ bool_t nav_detect_ground(void) { return TRUE; } +bool_t nav_is_in_flight(void) { + if (autopilot_in_flight) + return TRUE; + else + return FALSE; +} + void nav_home(void) {} diff --git a/sw/airborne/firmwares/rotorcraft/navigation.h b/sw/airborne/firmwares/rotorcraft/navigation.h index e992f9f311..b8df4ee553 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.h +++ b/sw/airborne/firmwares/rotorcraft/navigation.h @@ -81,6 +81,7 @@ unit_t nav_reset_alt( void ) __attribute__ ((unused)); void nav_periodic_task(void); void nav_move_waypoint(uint8_t wp_id, struct EnuCoor_i * new_pos); bool_t nav_detect_ground(void); +bool_t nav_is_in_flight(void); void nav_home(void); From 8cc90461ecabb3b42020c0f4c6505add13e3ed61 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 10:17:17 +0200 Subject: [PATCH 183/309] [modules] baro_ms5611_spi: fix update macro --- sw/airborne/modules/sensors/baro_ms5611_spi.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.h b/sw/airborne/modules/sensors/baro_ms5611_spi.h index 7bab9d92e8..70b83b2b9b 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.h +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.h @@ -50,8 +50,8 @@ extern void baro_ms5611_read(void); extern void baro_ms5611_periodic_check(void); extern void baro_ms5611_event(void); -#define BaroMs5611UpdatePressure(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; baro_ms5611.data_available = FALSE; } } +#define BaroMs5611UpdatePressure(_b, _h) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; _h(); baro_ms5611.data_available = FALSE; } } -#define BaroMs5611UpdateAlt(_b) { if (baro_ms5611.data_available) { _b = baro_ms5611_alt; baro_ms5611.data_available = FALSE; } } +#define BaroMs5611UpdateAlt(_b, _h) { if (baro_ms5611.data_available) { _b = baro_ms5611_alt; _h(); baro_ms5611.data_available = FALSE; } } #endif From 9919870bf9a953871f6fed78e6d46779059d88c4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 12:07:08 +0200 Subject: [PATCH 184/309] [datalink] only include superbitrf if actually used fixes compilation on ar_drone/omap --- sw/airborne/subsystems/datalink/downlink.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/sw/airborne/subsystems/datalink/downlink.h b/sw/airborne/subsystems/datalink/downlink.h index 50c8e562c9..851414b494 100644 --- a/sw/airborne/subsystems/datalink/downlink.h +++ b/sw/airborne/subsystems/datalink/downlink.h @@ -46,17 +46,21 @@ #endif #else /** SITL */ + #include "subsystems/datalink/udp.h" #include "subsystems/datalink/pprz_transport.h" #include "subsystems/datalink/xbee.h" #include "subsystems/datalink/w5100.h" +#if USE_SUPERBITRF #include "subsystems/datalink/superbitrf.h" +#endif #if USE_AUDIO_TELEMETRY #include "subsystems/datalink/audio_telemetry.h" #endif #ifdef USE_USB_SERIAL #include "mcu_periph/usb_serial.h" #endif + #endif /** !SITL */ #ifndef DefaultChannel From 2ccb9d4f6c1c4ddc3f8608d5e0ca688f55972144 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 12:07:58 +0200 Subject: [PATCH 185/309] [superbitrf] minor include fixes --- sw/airborne/peripherals/cyrf6936.c | 1 - sw/airborne/subsystems/datalink/superbitrf.c | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 691049baac..1b1e678a48 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -27,7 +27,6 @@ #include "cyrf6936.h" #include "mcu_periph/spi.h" #include "mcu_periph/gpio.h" -#include "mcu_periph/gpio_arch.h" #include "mcu_periph/sys_time.h" #include "subsystems/radio_control.h" diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 40276314d0..5c6d27ecfc 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -30,7 +30,7 @@ #include "paparazzi.h" #include "mcu_periph/spi.h" #include "mcu_periph/sys_time.h" -#include +#include "mcu_periph/gpio.h" /* Default SuperbitRF SPI DEV */ #ifndef SUPERBITRF_SPI_DEV From ef84f4c8df4cd49d07468b4f715e681667a3075c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 12:08:41 +0200 Subject: [PATCH 186/309] [omap] add empty gpio_arch.h --- sw/airborne/arch/omap/mcu_periph/gpio_arch.h | 49 ++++++++++++++++++++ 1 file changed, 49 insertions(+) create mode 100644 sw/airborne/arch/omap/mcu_periph/gpio_arch.h diff --git a/sw/airborne/arch/omap/mcu_periph/gpio_arch.h b/sw/airborne/arch/omap/mcu_periph/gpio_arch.h new file mode 100644 index 0000000000..795f0e18f4 --- /dev/null +++ b/sw/airborne/arch/omap/mcu_periph/gpio_arch.h @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file arch/omap/mcu_periph/gpio_arch.h + * + * GPIO helper functions for linux/omap. + * @todo implement gpio_set|clear + */ + +#ifndef GPIO_ARCH_H +#define GPIO_ARCH_H + +#include "std.h" + +/** + * Set a gpio output to high level. + */ +static inline void gpio_set(uint32_t port, uint16_t pin) { + +} + +/** + * Clear a gpio output to low level. + */ +static inline void gpio_clear(uint32_t port, uint16_t pin) { + +} + + +#endif /* GPIO_ARCH_H */ From 45c61055c3bd14595b6742d8638e78f1aae1835f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 13:10:58 +0200 Subject: [PATCH 187/309] [modules] baro_ms5611: don't send MS5611_COEFF by default to send the MS5611_COEFF message either set BARO_MS5611_SEND_COEFF to TRUE to send it every 5s or explicitly call baro_ms5611_send_coeff --- sw/airborne/modules/sensors/baro_ms5611_i2c.c | 29 +++++++++++------- sw/airborne/modules/sensors/baro_ms5611_spi.c | 30 ++++++++++++------- 2 files changed, 37 insertions(+), 22 deletions(-) diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.c b/sw/airborne/modules/sensors/baro_ms5611_i2c.c index d3b3a3d88c..e44e3044f8 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.c @@ -72,17 +72,10 @@ void baro_ms5611_periodic_check( void ) { ms5611_i2c_periodic_check(&baro_ms5611); - if (baro_ms5611.initialized) { - RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &baro_ms5611.data.c[0], - &baro_ms5611.data.c[1], - &baro_ms5611.data.c[2], - &baro_ms5611.data.c[3], - &baro_ms5611.data.c[4], - &baro_ms5611.data.c[5], - &baro_ms5611.data.c[6], - &baro_ms5611.data.c[7])); - } +#if BARO_MS5611_SEND_COEFF + // send coeff every 5s + RunOnceEvery((5*BARO_MS5611_PERIODIC_CHECK_FREQUENCY), baro_ms5611_send_coeff()); +#endif } /// trigger new measurement or initialize if needed @@ -110,3 +103,17 @@ void baro_ms5611_event( void ) { #endif } } + +void baro_ms5611_send_coeff(void) { + if (baro_ms5611.initialized) { + DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7]); + } +} diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.c b/sw/airborne/modules/sensors/baro_ms5611_spi.c index c91d713153..7da2575f41 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.c +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.c @@ -72,17 +72,11 @@ void baro_ms5611_periodic_check( void ) { ms5611_spi_periodic_check(&baro_ms5611); - if (baro_ms5611.initialized) { - RunOnceEvery((4*30), DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, - &baro_ms5611.data.c[0], - &baro_ms5611.data.c[1], - &baro_ms5611.data.c[2], - &baro_ms5611.data.c[3], - &baro_ms5611.data.c[4], - &baro_ms5611.data.c[5], - &baro_ms5611.data.c[6], - &baro_ms5611.data.c[7])); - } +#if BARO_MS5611_SEND_COEFF + // send coeff every 5s + RunOnceEvery((5*BARO_MS5611_PERIODIC_CHECK_FREQUENCY), baro_ms5611_send_coeff()); +#endif + } /// trigger new measurement or initialize if needed @@ -110,3 +104,17 @@ void baro_ms5611_event( void ) { #endif } } + +void baro_ms5611_send_coeff(void) { + if (baro_ms5611.initialized) { + DOWNLINK_SEND_MS5611_COEFF(DefaultChannel, DefaultDevice, + &baro_ms5611.data.c[0], + &baro_ms5611.data.c[1], + &baro_ms5611.data.c[2], + &baro_ms5611.data.c[3], + &baro_ms5611.data.c[4], + &baro_ms5611.data.c[5], + &baro_ms5611.data.c[6], + &baro_ms5611.data.c[7]); + } +} From 4765f35f937885b1bd0813ea008769045a042f7a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 13:15:51 +0200 Subject: [PATCH 188/309] [modules] add baro_ms5611_send_coeff declaration --- sw/airborne/modules/sensors/baro_ms5611_i2c.h | 1 + sw/airborne/modules/sensors/baro_ms5611_spi.h | 1 + 2 files changed, 2 insertions(+) diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h index f30b28debc..549b6bf731 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.h +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.h @@ -21,6 +21,7 @@ extern void baro_ms5611_init(void); extern void baro_ms5611_read(void); extern void baro_ms5611_periodic_check(void); extern void baro_ms5611_event(void); +extern void baro_ms5611_send_coeff(void); #define BaroMs5611UpdatePressure(_b, _h) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; _h(); baro_ms5611.data_available = FALSE; } } diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.h b/sw/airborne/modules/sensors/baro_ms5611_spi.h index 70b83b2b9b..7be9f9c2e5 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.h +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.h @@ -49,6 +49,7 @@ extern void baro_ms5611_init(void); extern void baro_ms5611_read(void); extern void baro_ms5611_periodic_check(void); extern void baro_ms5611_event(void); +extern void baro_ms5611_send_coeff(void); #define BaroMs5611UpdatePressure(_b, _h) { if (baro_ms5611.data_available) { _b = baro_ms5611.data.pressure; _h(); baro_ms5611.data_available = FALSE; } } From ec0592e846f99c66dc1d00b3ac6458c0ff7a55c8 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 14:29:10 +0200 Subject: [PATCH 189/309] [rotorcraft] MODULES_FREQUENCY defaults to PERIODIC_FREQUENCY --- sw/airborne/firmwares/rotorcraft/main.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 060367961d..beb36fcb31 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -83,7 +83,7 @@ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY) #ifndef MODULES_FREQUENCY -#define MODULES_FREQUENCY 512 +#define MODULES_FREQUENCY PERIODIC_FREQUENCY #endif PRINT_CONFIG_VAR(MODULES_FREQUENCY) From b1eb25e4f0abb2a4a94d433599ac84833093865c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 14:58:01 +0200 Subject: [PATCH 190/309] [dox] create dox makefile target to easily create doxygen docs --- Makefile | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 39e02ab114..b845818f72 100644 --- a/Makefile +++ b/Makefile @@ -248,6 +248,15 @@ paparazzi: chmod a+x $@ +# +# doxygen html documentation +# +dox: + $(Q)PAPARAZZI_HOME=$(PAPARAZZI_HOME) sw/tools/doxygen_gen/gen_modules_doc.py -pv + @echo "Generationg doxygen html documentation in doc/generated/html" + $(Q)( cat Doxyfile ; echo "PROJECT_NUMBER=$(./paparazzi_version)"; echo "QUIET=YES") | doxygen - + @echo "Done. Open doc/generated/html/index.html in your browser to view it." + # # Cleaning # @@ -296,7 +305,7 @@ run_tests: test: all replace_current_conf_xml run_tests restore_conf_xml -.PHONY: all print_build_version update_google_version ground_segment ground_segment.opt \ +.PHONY: all print_build_version update_google_version dox ground_segment ground_segment.opt \ subdirs $(SUBDIRS) conf ext libpprz multimon cockpit cockpit.opt tmtc tmtc.opt tools\ static sim_static lpctools commands \ clean cleanspaces ab_clean dist_clean distclean dist_clean_irreversible \ From ad8c7d636bf2e13c552ce80f5d630be7d571a3be Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 14:58:33 +0200 Subject: [PATCH 191/309] [dox][modules] update sys_mon description --- conf/modules/sys_mon.xml | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/conf/modules/sys_mon.xml b/conf/modules/sys_mon.xml index 22eccb4511..b6a7dcd923 100644 --- a/conf/modules/sys_mon.xml +++ b/conf/modules/sys_mon.xml @@ -2,7 +2,29 @@ - System monitor + + System monitor. + The sys_mon module gives you some information about the timing of the periodic tasks and a rough estimate of cpu load (averaged over 1 sec). + + The SYS_MON message contains the following information (all times are given in microseconds): + - @b periodic_time : time between two calls of the modules_periodic_task (averaged over 1s) + - @b periodic_time_min : minimum time between two calls of the modules_periodic_task() during the last second + - @b periodic_time_max : maximum time between two calls of the modules_periodic_task() during the last second + - @b periodic_cycle : time it took to execute the main periodic functions (averaged over 1s) + - @b periodic_cycle_min : minimum time it took to execute the main periodic functions during the last second + - @b periodic_cycle_max : maximum time it took to execute the main periodic functions during the last second + - @b event_number : number of times the event loop was called during the last second + - @b cpu_load : rough estimate of cpu load (averaged over 1 sec) + + + So your periodic_time should be 1/MODULES_FREQUENCY, which should be the same as 1/PERIODIC_FREQUENCY + The periodic_cycle_max should not be over the periodic_time, otherwise in at least one cycle it took longer to calculate everything and the next one was slightly delayed. + + + The sys_mon module has to run at the full main frequency! + + So either don't specify a main_freq parameter for the modules node or set your actual main frequency +
From e99410998bf2804e4089295e77174b9f6e1df54c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 15:11:14 +0200 Subject: [PATCH 192/309] [dox] fix file headers for sensors/baro_ms5611_* --- sw/airborne/subsystems/sensors/baro_ms5611_i2c.c | 2 +- sw/airborne/subsystems/sensors/baro_ms5611_spi.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c index a996cee2dc..a3c446e4bd 100644 --- a/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_i2c.c @@ -21,7 +21,7 @@ */ /** - * @file boards/lisa_m/baro_ms5611_i2c.c + * @file subsystems/sensors/baro_ms5611_i2c.c * * Driver for MS5611 baro via I2C. * diff --git a/sw/airborne/subsystems/sensors/baro_ms5611_spi.c b/sw/airborne/subsystems/sensors/baro_ms5611_spi.c index a86ab818f7..bd8603ea43 100644 --- a/sw/airborne/subsystems/sensors/baro_ms5611_spi.c +++ b/sw/airborne/subsystems/sensors/baro_ms5611_spi.c @@ -21,7 +21,7 @@ */ /** - * @file boards/lisa_m/baro_ms5611_spi.c + * @file subsystems/sensors/baro_ms5611_spi.c * * Driver for MS5611 baro on LisaM/Aspirin2.2 via SPI. * From e216c612446a3a6838ef45d6d7619c31da3ebad5 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 30 Aug 2013 16:24:37 +0200 Subject: [PATCH 193/309] [dox] fix sys_mon module description rendering --- conf/modules/sys_mon.xml | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/conf/modules/sys_mon.xml b/conf/modules/sys_mon.xml index b6a7dcd923..88964bba1c 100644 --- a/conf/modules/sys_mon.xml +++ b/conf/modules/sys_mon.xml @@ -3,27 +3,27 @@ - System monitor. - The sys_mon module gives you some information about the timing of the periodic tasks and a rough estimate of cpu load (averaged over 1 sec). +System monitor. +The sys_mon module gives you some information about the timing of the periodic tasks and a rough estimate of cpu load (averaged over 1 sec). - The SYS_MON message contains the following information (all times are given in microseconds): - - @b periodic_time : time between two calls of the modules_periodic_task (averaged over 1s) - - @b periodic_time_min : minimum time between two calls of the modules_periodic_task() during the last second - - @b periodic_time_max : maximum time between two calls of the modules_periodic_task() during the last second - - @b periodic_cycle : time it took to execute the main periodic functions (averaged over 1s) - - @b periodic_cycle_min : minimum time it took to execute the main periodic functions during the last second - - @b periodic_cycle_max : maximum time it took to execute the main periodic functions during the last second - - @b event_number : number of times the event loop was called during the last second - - @b cpu_load : rough estimate of cpu load (averaged over 1 sec) +The SYS_MON message contains the following information (all times are given in microseconds): +- @b periodic_time : time between two calls of the modules_periodic_task (averaged over 1s) +- @b periodic_time_min : minimum time between two calls of the modules_periodic_task() during the last second +- @b periodic_time_max : maximum time between two calls of the modules_periodic_task() during the last second +- @b periodic_cycle : time it took to execute the main periodic functions (averaged over 1s) +- @b periodic_cycle_min : minimum time it took to execute the main periodic functions during the last second +- @b periodic_cycle_max : maximum time it took to execute the main periodic functions during the last second +- @b event_number : number of times the event loop was called during the last second +- @b cpu_load : rough estimate of cpu load (averaged over 1 sec) - So your periodic_time should be 1/MODULES_FREQUENCY, which should be the same as 1/PERIODIC_FREQUENCY - The periodic_cycle_max should not be over the periodic_time, otherwise in at least one cycle it took longer to calculate everything and the next one was slightly delayed. +So your periodic_time should be 1/MODULES_FREQUENCY, which should be the same as 1/PERIODIC_FREQUENCY +The periodic_cycle_max should not be over the periodic_time, otherwise in at least one cycle it took longer to calculate everything and the next one was slightly delayed. - The sys_mon module has to run at the full main frequency! +The sys_mon module has to run at the full main frequency! - So either don't specify a main_freq parameter for the modules node or set your actual main frequency +So either don't specify a main_freq parameter for the modules node or set your actual main frequency
From e6ae39d9d96a019aea084eed1bcd6996ee856022 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 30 Aug 2013 12:52:31 +0200 Subject: [PATCH 194/309] [Ardrone] Takeoff without joystick is possible --- conf/airframes/ardrone2_raw.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 0b6eb33d18..d6b09dea15 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -207,9 +207,10 @@
+ - +
From 06e466face91cc3ad8e7990f68c15b38c9deec95 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 30 Aug 2013 17:41:48 +0200 Subject: [PATCH 195/309] [ArDrone][FIX] New pin numbers for motor selection --- .../boards/ardrone/actuators_ardrone2_raw.c | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index 1989b492e7..dc8037afaf 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -81,34 +81,34 @@ void actuators_ardrone_init(void) tcsetattr(mot_fd, TCSANOW, &options); //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 - gpio_set(106,-1); - gpio_set(107,0); - gpio_set(107,1); + gpio_set(176,-1); + gpio_set(175,0); + gpio_set(175,1); //all select lines inactive - gpio_set(68,1); - gpio_set(69,1); - gpio_set(70,1); - gpio_set(71,1); + gpio_set(171,1); + gpio_set(172,1); + gpio_set(173,1); + gpio_set(174,1); //configure motors uint8_t reply[256]; for(int m=0;m<4;m++) { - gpio_set(68+m,-1); + gpio_set(171+m,-1); actuators_ardrone_cmd(0xe0,reply,2); if(reply[0]!=0xe0 || reply[1]!=0x00) { printf("motor%d cmd=0x%02x reply=0x%02x\n",m+1,(int)reply[0],(int)reply[1]); } actuators_ardrone_cmd(m+1,reply,1); - gpio_set(68+m,1); + gpio_set(171+m,1); } //all select lines active - gpio_set(68,-1); - gpio_set(69,-1); - gpio_set(70,-1); - gpio_set(71,-1); + gpio_set(171,-1); + gpio_set(172,-1); + gpio_set(173,-1); + gpio_set(174,-1); //start multicast actuators_ardrone_cmd(0xa0,reply,1); @@ -118,9 +118,9 @@ void actuators_ardrone_init(void) actuators_ardrone_cmd(0xa0,reply,1); //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 - gpio_set(106,-1); - gpio_set(107,0); - gpio_set(107,1); + gpio_set(176,-1); + gpio_set(175,0); + gpio_set(175,1); //all leds green //actuators_ardrone_set_leds(0,0,0,0); From 32104f3a1668abb831f7faa86ec6bd31c9e7bcb0 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 30 Aug 2013 18:00:33 +0200 Subject: [PATCH 196/309] [ArDrone][BLDC] Read Interrupt: be able to take-off again after a motor IRQ --- .../boards/ardrone/actuators_ardrone2_raw.c | 52 +++++++++++-------- sw/airborne/boards/ardrone/gpio_ardrone.c | 12 +++++ sw/airborne/boards/ardrone/gpio_ardrone.h | 1 + 3 files changed, 44 insertions(+), 21 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index dc8037afaf..3a11e8c0b3 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -117,15 +117,12 @@ void actuators_ardrone_init(void) actuators_ardrone_cmd(0xa0,reply,1); actuators_ardrone_cmd(0xa0,reply,1); - //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 + //reset IRQ flipflop - on error 176 reads 1, this code resets 176 to 0 gpio_set(176,-1); gpio_set(175,0); gpio_set(175,1); - //all leds green - //actuators_ardrone_set_leds(0,0,0,0); - //actuators_ardrone_set_leds(MOT_LEDRED, MOT_LEDRED, MOT_LEDRED, MOT_LEDRED); - //actuators_ardrone_set_leds(MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDGREEN); + // Left Red, Right Green actuators_ardrone_set_leds(MOT_LEDRED,MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDRED); } @@ -134,13 +131,34 @@ int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) { return read(mot_fd, reply, replylen); } +#include "autopilot.h" + +void actuators_ardrone_motor_status(void); +void actuators_ardrone_motor_status(void) +{ + // If a motor IRQ lines is set + if (gpio_get(176) == 1) + { + if (autopilot_motors_on) + { + // Tell paparazzi that one motor has stalled + autopilot_set_motors_on(FALSE); + + // Toggle Flipflop reset so motors can be re-enabled + gpio_set(175,0); + gpio_set(175,1); + } + } +} + + void actuators_ardrone_commit(void) { actuators_ardrone_set_pwm(actuators_pwm_values[0], actuators_pwm_values[1], actuators_pwm_values[2], actuators_pwm_values[3]); + RunOnceEvery(100,actuators_ardrone_motor_status()); } uint8_t ardrone_error_flag = 0; - void actuators_ardrone_error(void) { ardrone_error_flag = 1; @@ -173,28 +191,20 @@ void actuators_ardrone_set_pwm(uint16_t pwm0, uint16_t pwm1, uint16_t pwm2, uint { actuators_ardrone_set_leds(MOT_LEDOFF, MOT_LEDOFF, MOT_LEDOFF, MOT_LEDOFF); } - else if (blink == 20) - { - //actuators_ardrone_set_leds(MOT_LEDORANGE, MOT_LEDORANGE, MOT_LEDOFF, MOT_LEDORANGE); - } } - } /** * Write LED command - * cmd = 011grgrg rgrxxxxx (this is ardrone1 format, we need ardrone2 format) + * cmd = 011rrrr0 000gggg0 (this is ardrone1 format, we need ardrone2 format) + * + * + * led0 = RearLeft + * led1 = RearRight + * led2 = FrontRight + * led3 = FrontLeft */ -/* - -led0 = RearLeft -led1 = RearRight -led2 = FrontRight -led3 = FrontLeft - -*/ - void actuators_ardrone_set_leds(uint8_t led0, uint8_t led1, uint8_t led2, uint8_t led3) { uint8_t cmd[2]; diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index 3a08b1c267..cd76054a79 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -37,3 +37,15 @@ int gpio_set(int nr,int val) else sprintf(cmdline,"/usr/sbin/gpio %d -d ho 0",nr); return system(cmdline); } + +#define WE_HAVE_NO_CLUE_YET + + +#ifdef WE_HAVE_NO_CLUE_YET + +int gpio_get(int nr) +{ + return 0; +} + +#endif diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.h b/sw/airborne/boards/ardrone/gpio_ardrone.h index 55563f2e09..56dee38d43 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.h +++ b/sw/airborne/boards/ardrone/gpio_ardrone.h @@ -29,5 +29,6 @@ //val=1 -> set gpio output hi //val=-1 -> set gpio as input (output hi-Z) int gpio_set(int nr,int val); +int gpio_get(int nr); #endif /* GPIO_ARDRONE_H */ From d6cc3e5820ce1d9dcbfabb02dfe1d73a4b97d480 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 30 Aug 2013 18:00:52 +0200 Subject: [PATCH 197/309] typo --- sw/airborne/firmwares/rotorcraft/autopilot.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 41c21a3343..1b52e9a449 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -106,7 +106,7 @@ void autopilot_init(void) { guidance_v_init(); stabilization_init(); - /* set startup mode, propagats through to guidance h/v */ + /* set startup mode, propagates through to guidance h/v */ autopilot_set_mode(MODE_STARTUP); } From fab4e87f7d33dad8ed294bbc3deb3bb988a8e80f Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 30 Aug 2013 18:13:26 +0200 Subject: [PATCH 198/309] [ArDrone] Working routine to read GPIO pin --- sw/airborne/boards/ardrone/gpio_ardrone.c | 93 ++++++++++++++++++++++- 1 file changed, 92 insertions(+), 1 deletion(-) diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index cd76054a79..3f8e1ce40d 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -38,7 +38,15 @@ int gpio_set(int nr,int val) return system(cmdline); } -#define WE_HAVE_NO_CLUE_YET +// Option 1: +//#define WE_HAVE_NO_CLUE_YET + +// Option 2: +#define WE_MUST_TO_USE_THE_TERRIBLE_HACK + +// Option 3: +//#define WE_KNOW_HOW_ARDRONE_IOCTL_WORKS_ON_DEV_GPIO + #ifdef WE_HAVE_NO_CLUE_YET @@ -49,3 +57,86 @@ int gpio_get(int nr) } #endif + + + + +#ifdef WE_MUST_TO_USE_THE_TERRIBLE_HACK + +FILE* ardrone_system_pipe = 0; + +int gpio_get(int nr) +{ + + if (ardrone_system_pipe == 0) + { + char cmdline[200]; + sprintf(cmdline,"/usr/sbin/gpio %d -r",nr); + ardrone_system_pipe = popen(cmdline,"r"); + if (!ardrone_system_pipe) + { + return -1; + } + } + else + { + // TODO: we now call this with a large delay expecting that all data is present + // if (!feof(pipe)) // Still busy + + char buff[128]; + char* ret = fgets(buff, 128, ardrone_system_pipe); + ret = fgets(buff, 128, ardrone_system_pipe); + pclose(ardrone_system_pipe); + ardrone_system_pipe = 0; + + if (ret == NULL) + { + return -2; + } + + int pin = ret[25] - '0'; + + printf("GPIO_GET: %d '%d' \n", nr, pin); + + return pin; + } + return -3; +} + +#endif + + + + + +#ifdef WE_KNOW_HOW_ARDRONE_IOCTL_WORKS_ON_DEV_GPIO + +#include /* File control definitions */ +#include /* Error number definitions */ +#include + + +#define GPIO_IOCTL_COUNT 0 +#define GPIO_IOCTL_GET 2 + +int gpiofp = 0; +int gpio_get(int nr) +{ + if (gpiofp == 0) + { + gpiofp = open("/dev/gpio",O_RDWR); + printf("GPIO open %d\n", gpiofp); + // printf("%s", errno() ); + } + else + { + int gpio = nr; + int ret = ioctl(gpiofp, GPIO_IOCTL_GET, &gpio); + printf("GPIO_ %d = %d %d \n",nr,gpio, ret); + } + + // We don't know yet + return 0; +} + +#endif From 32ee3bbe3a8b54f4e64f123b378564dd691bd642 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 30 Aug 2013 19:46:59 +0200 Subject: [PATCH 199/309] Line Endings --- .../subsystems/shared/radio_control_superbitrf_rc.makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile index deac945a9a..85a80e4fb0 100644 --- a/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile @@ -12,4 +12,4 @@ endif ap.srcs += peripherals/cyrf6936.c \ $(SRC_SUBSYSTEMS)/datalink/superbitrf.c\ $(SRC_SUBSYSTEMS)/radio_control.c \ - $(SRC_SUBSYSTEMS)/radio_control/superbitrf_rc.c + $(SRC_SUBSYSTEMS)/radio_control/superbitrf_rc.c From a7fb3bf7cd7c73462a63fcce80ffd8586d5189a8 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Fri, 30 Aug 2013 20:28:50 +0200 Subject: [PATCH 200/309] [ardrone2] GPIO hack removed --- .../boards/ardrone/actuators_ardrone2_raw.c | 11 +- sw/airborne/boards/ardrone/gpio_ardrone.c | 169 ++++++------------ sw/airborne/boards/ardrone/gpio_ardrone.h | 4 +- 3 files changed, 66 insertions(+), 118 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index 3a11e8c0b3..5848b71643 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -81,7 +81,7 @@ void actuators_ardrone_init(void) tcsetattr(mot_fd, TCSANOW, &options); //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 - gpio_set(176,-1); + gpio_set_input(176); gpio_set(175,0); gpio_set(175,1); @@ -105,10 +105,10 @@ void actuators_ardrone_init(void) } //all select lines active - gpio_set(171,-1); - gpio_set(172,-1); - gpio_set(173,-1); - gpio_set(174,-1); + gpio_set(171,0); + gpio_set(172,0); + gpio_set(173,0); + gpio_set(174,0); //start multicast actuators_ardrone_cmd(0xa0,reply,1); @@ -118,7 +118,6 @@ void actuators_ardrone_init(void) actuators_ardrone_cmd(0xa0,reply,1); //reset IRQ flipflop - on error 176 reads 1, this code resets 176 to 0 - gpio_set(176,-1); gpio_set(175,0); gpio_set(175,1); diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index 3f8e1ce40d..b9172c7cdf 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -22,121 +22,70 @@ * ardrone GPIO driver */ -#include -#include -#include "gpio_ardrone.h" - -//val=0 -> set gpio output lo -//val=1 -> set gpio output hi -//val=-1 -> set gpio as input (output hi-Z) -int gpio_set(int nr,int val) -{ - char cmdline[200]; - if(val<0) sprintf(cmdline,"/usr/sbin/gpio %d -d i",nr); - else if(val>0) sprintf(cmdline,"/usr/sbin/gpio %d -d ho 1",nr); - else sprintf(cmdline,"/usr/sbin/gpio %d -d ho 0",nr); - return system(cmdline); -} - -// Option 1: -//#define WE_HAVE_NO_CLUE_YET - -// Option 2: -#define WE_MUST_TO_USE_THE_TERRIBLE_HACK - -// Option 3: -//#define WE_KNOW_HOW_ARDRONE_IOCTL_WORKS_ON_DEV_GPIO - - - -#ifdef WE_HAVE_NO_CLUE_YET - -int gpio_get(int nr) -{ - return 0; -} - -#endif - - - - -#ifdef WE_MUST_TO_USE_THE_TERRIBLE_HACK - -FILE* ardrone_system_pipe = 0; - -int gpio_get(int nr) -{ - - if (ardrone_system_pipe == 0) - { - char cmdline[200]; - sprintf(cmdline,"/usr/sbin/gpio %d -r",nr); - ardrone_system_pipe = popen(cmdline,"r"); - if (!ardrone_system_pipe) - { - return -1; - } - } - else - { - // TODO: we now call this with a large delay expecting that all data is present - // if (!feof(pipe)) // Still busy - - char buff[128]; - char* ret = fgets(buff, 128, ardrone_system_pipe); - ret = fgets(buff, 128, ardrone_system_pipe); - pclose(ardrone_system_pipe); - ardrone_system_pipe = 0; - - if (ret == NULL) - { - return -2; - } - - int pin = ret[25] - '0'; - - printf("GPIO_GET: %d '%d' \n", nr, pin); - - return pin; - } - return -3; -} - -#endif - - - - - -#ifdef WE_KNOW_HOW_ARDRONE_IOCTL_WORKS_ON_DEV_GPIO - #include /* File control definitions */ #include /* Error number definitions */ #include +#include "gpio_ardrone.h" - -#define GPIO_IOCTL_COUNT 0 -#define GPIO_IOCTL_GET 2 - +#define GPIO_MAGIC 'p' +#define GPIO_DIRECTION _IOW(GPIO_MAGIC, 0, struct gpio_direction) +#define GPIO_READ _IOWR(GPIO_MAGIC, 1, struct gpio_data) +#define GPIO_WRITE _IOW(GPIO_MAGIC, 2, struct gpio_data) int gpiofp = 0; -int gpio_get(int nr) -{ - if (gpiofp == 0) - { - gpiofp = open("/dev/gpio",O_RDWR); - printf("GPIO open %d\n", gpiofp); - // printf("%s", errno() ); - } - else - { - int gpio = nr; - int ret = ioctl(gpiofp, GPIO_IOCTL_GET, &gpio); - printf("GPIO_ %d = %d %d \n",nr,gpio, ret); - } - // We don't know yet - return 0; +struct gpio_data { + int pin; + int value; +}; + +enum gpio_mode { + GPIO_INPUT = 0, //!< Pin configured for input + GPIO_OUTPUT_LOW, //!< Pin configured for output with low level + GPIO_OUTPUT_HIGH, //!< Pin configured for output with high level +}; + +struct gpio_direction { + int pin; + enum gpio_mode mode; +}; + +//val=0 -> set gpio output lo +//val=1 -> set gpio output hi +void gpio_set(int nr, int val) +{ + struct gpio_data data; + // Open the device if not open + if (gpiofp == 0) + gpiofp = open("/dev/gpio",O_RDWR); + + // Read the GPIO value + data.pin = nr; + data.value = val; + ioctl(gpiofp, GPIO_WRITE, &data); } -#endif +void gpio_set_input(int nr) +{ + struct gpio_direction dir; + // Open the device if not open + if (gpiofp == 0) + gpiofp = open("/dev/gpio",O_RDWR); + + // Read the GPIO value + dir.pin = nr; + dir.mode = GPIO_INPUT; + ioctl(gpiofp, GPIO_DIRECTION, &dir); +} + +int gpio_get(int nr) +{ + struct gpio_data data; + // Open the device if not open + if (gpiofp == 0) + gpiofp = open("/dev/gpio",O_RDWR); + + // Read the GPIO value + data.pin = nr; + ioctl(gpiofp, GPIO_READ, &data); + return data.value; +} diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.h b/sw/airborne/boards/ardrone/gpio_ardrone.h index 56dee38d43..f455d33004 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.h +++ b/sw/airborne/boards/ardrone/gpio_ardrone.h @@ -27,8 +27,8 @@ //val=0 -> set gpio output lo //val=1 -> set gpio output hi -//val=-1 -> set gpio as input (output hi-Z) -int gpio_set(int nr,int val); +void gpio_set(int nr,int val); +void gpio_set_input(int nr); int gpio_get(int nr); #endif /* GPIO_ARDRONE_H */ From 1fac821b79897c84cd436753734d5dbd0f0d5526 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sat, 31 Aug 2013 16:02:49 +0200 Subject: [PATCH 201/309] [ArDrone] GPIO rewritten to make paparazzi API more consistent --- sw/airborne/arch/omap/mcu_periph/gpio_arch.h | 11 ++-- .../boards/ardrone/actuators_ardrone2_raw.c | 48 ++++++++++------- sw/airborne/boards/ardrone/gpio_ardrone.c | 53 +++++++++++++++---- sw/airborne/boards/ardrone/gpio_ardrone.h | 34 ------------ 4 files changed, 77 insertions(+), 69 deletions(-) delete mode 100644 sw/airborne/boards/ardrone/gpio_ardrone.h diff --git a/sw/airborne/arch/omap/mcu_periph/gpio_arch.h b/sw/airborne/arch/omap/mcu_periph/gpio_arch.h index 795f0e18f4..1f7c9a9487 100644 --- a/sw/airborne/arch/omap/mcu_periph/gpio_arch.h +++ b/sw/airborne/arch/omap/mcu_periph/gpio_arch.h @@ -34,16 +34,17 @@ /** * Set a gpio output to high level. */ -static inline void gpio_set(uint32_t port, uint16_t pin) { - -} +extern void gpio_set(uint32_t port, uint16_t pin); /** * Clear a gpio output to low level. */ -static inline void gpio_clear(uint32_t port, uint16_t pin) { +extern void gpio_clear(uint32_t port, uint16_t pin); -} +/** + * Read a gpio value. + */ +uint16_t gpio_get(uint32_t gpioport, uint16_t gpios); #endif /* GPIO_ARCH_H */ diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index 5848b71643..d5fe722d09 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -30,7 +30,7 @@ #include "subsystems/actuators.h" #include "actuators_ardrone2_raw.h" -#include "gpio_ardrone.h" +#include "mcu_periph/gpio.h" #include /* Standard input/output definitions */ #include /* String function definitions */ @@ -52,6 +52,16 @@ */ int mot_fd; /**< File descriptor for the port */ +#define ARDRONE_GPIO_PORT 0 // Dummy for paparazzi compatibility + +#define ARDRONE_GPIO_PIN_MOTOR1 171 +#define ARDRONE_GPIO_PIN_MOTOR2 172 +#define ARDRONE_GPIO_PIN_MOTOR3 173 +#define ARDRONE_GPIO_PIN_MOTOR4 174 + +#define ARDRONE_GPIO_PIN_IRQ_FLIPFLOP 175 +#define ARDRONE_GPIO_PIN_IRQ_INPUT 176 + void actuators_ardrone_init(void) { //open mot port @@ -81,34 +91,34 @@ void actuators_ardrone_init(void) tcsetattr(mot_fd, TCSANOW, &options); //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 - gpio_set_input(176); - gpio_set(175,0); - gpio_set(175,1); + gpio_setup_input(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_INPUT); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); //all select lines inactive - gpio_set(171,1); - gpio_set(172,1); - gpio_set(173,1); - gpio_set(174,1); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR1); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR2); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR3); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR4); //configure motors uint8_t reply[256]; for(int m=0;m<4;m++) { - gpio_set(171+m,-1); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR1 + m); actuators_ardrone_cmd(0xe0,reply,2); if(reply[0]!=0xe0 || reply[1]!=0x00) { printf("motor%d cmd=0x%02x reply=0x%02x\n",m+1,(int)reply[0],(int)reply[1]); } actuators_ardrone_cmd(m+1,reply,1); - gpio_set(171+m,1); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR1 + m); } //all select lines active - gpio_set(171,0); - gpio_set(172,0); - gpio_set(173,0); - gpio_set(174,0); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR1); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR2); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR3); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR4); //start multicast actuators_ardrone_cmd(0xa0,reply,1); @@ -118,8 +128,8 @@ void actuators_ardrone_init(void) actuators_ardrone_cmd(0xa0,reply,1); //reset IRQ flipflop - on error 176 reads 1, this code resets 176 to 0 - gpio_set(175,0); - gpio_set(175,1); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); // Left Red, Right Green actuators_ardrone_set_leds(MOT_LEDRED,MOT_LEDGREEN, MOT_LEDGREEN, MOT_LEDRED); @@ -136,7 +146,7 @@ void actuators_ardrone_motor_status(void); void actuators_ardrone_motor_status(void) { // If a motor IRQ lines is set - if (gpio_get(176) == 1) + if (gpio_get(ARDRONE_GPIO_PORT, ARDRONE_GPIO_PIN_IRQ_INPUT) == 1) { if (autopilot_motors_on) { @@ -144,8 +154,8 @@ void actuators_ardrone_motor_status(void) autopilot_set_motors_on(FALSE); // Toggle Flipflop reset so motors can be re-enabled - gpio_set(175,0); - gpio_set(175,1); + gpio_clear(ARDRONE_GPIO_PORT, ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + gpio_set(ARDRONE_GPIO_PORT, ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); } } } diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index b9172c7cdf..9222cd27ae 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -25,7 +25,8 @@ #include /* File control definitions */ #include /* Error number definitions */ #include -#include "gpio_ardrone.h" + +#include "mcu_periph/gpio.h" #define GPIO_MAGIC 'p' #define GPIO_DIRECTION _IOW(GPIO_MAGIC, 0, struct gpio_direction) @@ -49,22 +50,36 @@ struct gpio_direction { enum gpio_mode mode; }; -//val=0 -> set gpio output lo -//val=1 -> set gpio output hi -void gpio_set(int nr, int val) + +void gpio_set(uint32_t port, uint16_t pin) { struct gpio_data data; // Open the device if not open if (gpiofp == 0) - gpiofp = open("/dev/gpio",O_RDWR); + gpiofp = open("/dev/gpio",O_RDWR); // Read the GPIO value - data.pin = nr; - data.value = val; + data.pin = pin; + data.value = 1; ioctl(gpiofp, GPIO_WRITE, &data); } -void gpio_set_input(int nr) + +void gpio_clear(uint32_t port, uint16_t pin) +{ + struct gpio_data data; + // Open the device if not open + if (gpiofp == 0) + gpiofp = open("/dev/gpio",O_RDWR); + + // Read the GPIO value + data.pin = pin; + data.value = 0; + ioctl(gpiofp, GPIO_WRITE, &data); +} + + +void gpio_setup_input(uint32_t port, uint16_t pin) { struct gpio_direction dir; // Open the device if not open @@ -72,12 +87,28 @@ void gpio_set_input(int nr) gpiofp = open("/dev/gpio",O_RDWR); // Read the GPIO value - dir.pin = nr; + dir.pin = pin; dir.mode = GPIO_INPUT; ioctl(gpiofp, GPIO_DIRECTION, &dir); } -int gpio_get(int nr) + +void gpio_setup_output(uint32_t port, uint16_t pin) +{ + struct gpio_direction dir; + // Open the device if not open + if (gpiofp == 0) + gpiofp = open("/dev/gpio",O_RDWR); + + // Read the GPIO value + dir.pin = pin; + dir.mode = GPIO_OUTPUT_HIGH; + ioctl(gpiofp, GPIO_DIRECTION, &dir); +} + + + +uint16_t gpio_get(uint32_t gpioport, uint16_t pin) { struct gpio_data data; // Open the device if not open @@ -85,7 +116,7 @@ int gpio_get(int nr) gpiofp = open("/dev/gpio",O_RDWR); // Read the GPIO value - data.pin = nr; + data.pin = pin; ioctl(gpiofp, GPIO_READ, &data); return data.value; } diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.h b/sw/airborne/boards/ardrone/gpio_ardrone.h deleted file mode 100644 index f455d33004..0000000000 --- a/sw/airborne/boards/ardrone/gpio_ardrone.h +++ /dev/null @@ -1,34 +0,0 @@ -/* - * Copyright (C) 2011 Hugo Perquin - http://blog.perquin.com - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301 USA. - */ - -/** - * @file boards/ardrone/gpio_ardrone.h - * ardrone GPIO driver - */ - -#ifndef GPIO_ARDRONE_H -#define GPIO_ARDRONE_H - -//val=0 -> set gpio output lo -//val=1 -> set gpio output hi -void gpio_set(int nr,int val); -void gpio_set_input(int nr); -int gpio_get(int nr); - -#endif /* GPIO_ARDRONE_H */ From e2961a419a4f4025f3d83f6566eaf81afaf15a42 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 31 Aug 2013 20:28:22 +0200 Subject: [PATCH 202/309] [rotorcraft] refactor guidance_h_ref and fix route_ref if both argumens for atan2 are zero not really sure what the max_ref values should be in the case where the route_ref angle can't be computed... set to max on both axes for now... see also issue #521 --- .../rotorcraft/guidance/guidance_h_ref.c | 125 ++++++++---------- 1 file changed, 53 insertions(+), 72 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c index b1db6ebcfa..31c82fcadc 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c @@ -77,9 +77,11 @@ struct Int64Vect2 gh_pos_ref; #define GH_OMEGA_2 BFP_OF_REAL((GUIDANCE_H_REF_OMEGA*GUIDANCE_H_REF_OMEGA), GH_OMEGA_2_FRAC) /** first order time constant */ -#define GH_REF_THAU_F 0.5 -#define GH_REF_INV_THAU_FRAC 16 -#define GH_REF_INV_THAU BFP_OF_REAL((1./GH_REF_THAU_F), GH_REF_INV_THAU_FRAC) +#ifndef GUIDANCE_H_REF_TAU +#define GUIDANCE_H_REF_TAU 0.5 +#endif +#define GH_REF_INV_TAU_FRAC 16 +#define GH_REF_INV_TAU BFP_OF_REAL((1./GUIDANCE_H_REF_TAU), GH_REF_INV_TAU_FRAC) static struct Int32Vect2 gh_max_speed_ref; static struct Int32Vect2 gh_max_accel_ref; @@ -88,6 +90,10 @@ static int32_t route_ref; static int32_t s_route_ref; static int32_t c_route_ref; +static void gh_saturate_ref_accel(void); +static void gh_saturate_ref_speed(void); +static void gh_compute_max_ref(struct Int32Vect2* ref_vector); + void gh_set_ref(struct Int32Vect2 pos, struct Int32Vect2 speed, struct Int32Vect2 accel) { struct Int64Vect2 new_pos; new_pos.x = ((int64_t)pos.x)<<(GH_POS_REF_FRAC - INT32_POS_FRAC); @@ -120,60 +126,14 @@ void gh_update_ref_from_pos_sp(struct Int32Vect2 pos_sp) { // sum accel VECT2_SUM(gh_accel_ref, speed, pos); - /* Compute route reference before saturation */ - float f_route_ref = atan2f(-pos_err.y, -pos_err.x); - route_ref = ANGLE_BFP_OF_REAL(f_route_ref); - /* Compute North and East route components */ - PPRZ_ITRIG_SIN(s_route_ref, route_ref); - PPRZ_ITRIG_COS(c_route_ref, route_ref); - c_route_ref = abs(c_route_ref); - s_route_ref = abs(s_route_ref); - /* Compute maximum acceleration*/ - gh_max_accel_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, c_route_ref, INT32_TRIG_FRAC); - gh_max_accel_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, s_route_ref, INT32_TRIG_FRAC); - /* Compute maximum speed*/ - gh_max_speed_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, c_route_ref, INT32_TRIG_FRAC); - gh_max_speed_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, s_route_ref, INT32_TRIG_FRAC); - /* restore gh_speed_ref range (Q14.17) */ - INT32_VECT2_LSHIFT(gh_max_speed_ref, gh_max_speed_ref, (GH_SPEED_REF_FRAC - GH_MAX_SPEED_REF_FRAC)); + /* Compute max ref accel/speed along route before saturation */ + gh_compute_max_ref(&pos_err); - /* Saturate accelerations */ - if (gh_accel_ref.x <= -gh_max_accel_ref.x) { - gh_accel_ref.x = -gh_max_accel_ref.x; - } - else if (gh_accel_ref.x >= gh_max_accel_ref.x) { - gh_accel_ref.x = gh_max_accel_ref.x; - } - if (gh_accel_ref.y <= -gh_max_accel_ref.y) { - gh_accel_ref.y = -gh_max_accel_ref.y; - } - else if (gh_accel_ref.y >= gh_max_accel_ref.y) { - gh_accel_ref.y = gh_max_accel_ref.y; - } - - /* Saturate speed and adjust acceleration accordingly */ - if (gh_speed_ref.x <= -gh_max_speed_ref.x) { - gh_speed_ref.x = -gh_max_speed_ref.x; - if (gh_accel_ref.x < 0) - gh_accel_ref.x = 0; - } - else if (gh_speed_ref.x >= gh_max_speed_ref.x) { - gh_speed_ref.x = gh_max_speed_ref.x; - if (gh_accel_ref.x > 0) - gh_accel_ref.x = 0; - } - if (gh_speed_ref.y <= -gh_max_speed_ref.y) { - gh_speed_ref.y = -gh_max_speed_ref.y; - if (gh_accel_ref.y < 0) - gh_accel_ref.y = 0; - } - else if (gh_speed_ref.y >= gh_max_speed_ref.y) { - gh_speed_ref.y = gh_max_speed_ref.y; - if (gh_accel_ref.y > 0) - gh_accel_ref.y = 0; - } + gh_saturate_ref_accel(); + gh_saturate_ref_speed(); } + void gh_update_ref_from_speed_sp(struct Int32Vect2 speed_sp) { /* WARNING: SPEED SATURATION UNTESTED */ VECT2_ADD(gh_pos_ref, gh_speed_ref); @@ -186,26 +146,45 @@ void gh_update_ref_from_speed_sp(struct Int32Vect2 speed_sp) { // convert to accel resolution INT32_VECT2_RSHIFT(speed_err, speed_err, (GH_SPEED_REF_FRAC - GH_ACCEL_REF_FRAC)); // compute accel from speed_sp - VECT2_SMUL(gh_accel_ref, speed_err, -GH_REF_INV_THAU); - INT32_VECT2_RSHIFT(gh_accel_ref, gh_accel_ref, GH_REF_INV_THAU_FRAC); + VECT2_SMUL(gh_accel_ref, speed_err, -GH_REF_INV_TAU); + INT32_VECT2_RSHIFT(gh_accel_ref, gh_accel_ref, GH_REF_INV_TAU_FRAC); + /* Compute max ref accel/speed along route before saturation */ + gh_compute_max_ref(&speed_sp); + + gh_saturate_ref_accel(); + gh_saturate_ref_speed(); +} + +static void gh_compute_max_ref(struct Int32Vect2* ref_vector) { /* Compute route reference before saturation */ - float f_route_ref = atan2f(-speed_sp.y, -speed_sp.x); - route_ref = ANGLE_BFP_OF_REAL(f_route_ref); - /* Compute North and East route components */ - PPRZ_ITRIG_SIN(s_route_ref, route_ref); - PPRZ_ITRIG_COS(c_route_ref, route_ref); - c_route_ref = abs(c_route_ref); - s_route_ref = abs(s_route_ref); - /* Compute maximum acceleration*/ - gh_max_accel_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, c_route_ref, INT32_TRIG_FRAC); - gh_max_accel_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, s_route_ref, INT32_TRIG_FRAC); - /* Compute maximum speed*/ - gh_max_speed_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, c_route_ref, INT32_TRIG_FRAC); - gh_max_speed_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, s_route_ref, INT32_TRIG_FRAC); - /* restore gh_speed_ref range (Q14.17) */ - INT32_VECT2_LSHIFT(gh_max_speed_ref, gh_max_speed_ref, (GH_SPEED_REF_FRAC - GH_MAX_SPEED_REF_FRAC)); + if (ref_vector->x == 0 && ref_vector->y == 0) { + gh_max_accel_ref.x = GH_MAX_ACCEL; + gh_max_accel_ref.y = GH_MAX_ACCEL; + gh_max_speed_ref.x = GH_MAX_SPEED; + gh_max_speed_ref.y = GH_MAX_SPEED; + } + else { + float f_route_ref = atan2f(-ref_vector->y, -ref_vector->x); + route_ref = ANGLE_BFP_OF_REAL(f_route_ref); + /* Compute North and East route components */ + PPRZ_ITRIG_SIN(s_route_ref, route_ref); + PPRZ_ITRIG_COS(c_route_ref, route_ref); + c_route_ref = abs(c_route_ref); + s_route_ref = abs(s_route_ref); + /* Compute maximum acceleration*/ + gh_max_accel_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, c_route_ref, INT32_TRIG_FRAC); + gh_max_accel_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, s_route_ref, INT32_TRIG_FRAC); + /* Compute maximum speed*/ + gh_max_speed_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, c_route_ref, INT32_TRIG_FRAC); + gh_max_speed_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, s_route_ref, INT32_TRIG_FRAC); + /* restore gh_speed_ref range (Q14.17) */ + INT32_VECT2_LSHIFT(gh_max_speed_ref, gh_max_speed_ref, (GH_SPEED_REF_FRAC - GH_MAX_SPEED_REF_FRAC)); + } +} +/** saturate reference accelerations */ +static void gh_saturate_ref_accel(void) { /* Saturate accelerations */ if (gh_accel_ref.x <= -gh_max_accel_ref.x) { gh_accel_ref.x = -gh_max_accel_ref.x; @@ -219,8 +198,10 @@ void gh_update_ref_from_speed_sp(struct Int32Vect2 speed_sp) { else if (gh_accel_ref.y >= gh_max_accel_ref.y) { gh_accel_ref.y = gh_max_accel_ref.y; } +} - /* Saturate speed and adjust acceleration accordingly */ +/** Saturate ref speed and adjust acceleration accordingly */ +static void gh_saturate_ref_speed(void) { if (gh_speed_ref.x <= -gh_max_speed_ref.x) { gh_speed_ref.x = -gh_max_speed_ref.x; if (gh_accel_ref.x < 0) From 0a8d097a994baec71fe78b949731f8b0b3644753 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sat, 31 Aug 2013 23:19:39 +0200 Subject: [PATCH 203/309] [ArDrone] Add protection to lowlevel driver that can short-circuit the board. --- sw/airborne/boards/ardrone/actuators_ardrone2_raw.c | 2 +- sw/airborne/boards/ardrone/gpio_ardrone.c | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index d5fe722d09..0131db45ba 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -52,7 +52,7 @@ */ int mot_fd; /**< File descriptor for the port */ -#define ARDRONE_GPIO_PORT 0 // Dummy for paparazzi compatibility +#define ARDRONE_GPIO_PORT 0x32524 #define ARDRONE_GPIO_PIN_MOTOR1 171 #define ARDRONE_GPIO_PIN_MOTOR2 172 diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index 9222cd27ae..9e3786722b 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -53,6 +53,7 @@ struct gpio_direction { void gpio_set(uint32_t port, uint16_t pin) { + if (port != 0x32524) return; // protect ardrone board from unauthorized use struct gpio_data data; // Open the device if not open if (gpiofp == 0) @@ -67,6 +68,7 @@ void gpio_set(uint32_t port, uint16_t pin) void gpio_clear(uint32_t port, uint16_t pin) { + if (port != 0x32524) return; // protect ardrone board from unauthorized use struct gpio_data data; // Open the device if not open if (gpiofp == 0) @@ -81,6 +83,7 @@ void gpio_clear(uint32_t port, uint16_t pin) void gpio_setup_input(uint32_t port, uint16_t pin) { + if (port != 0x32524) return; // protect ardrone board from unauthorized use struct gpio_direction dir; // Open the device if not open if (gpiofp == 0) @@ -95,6 +98,7 @@ void gpio_setup_input(uint32_t port, uint16_t pin) void gpio_setup_output(uint32_t port, uint16_t pin) { + if (port != 0x32524) return; // protect ardrone board from unauthorized use struct gpio_direction dir; // Open the device if not open if (gpiofp == 0) @@ -108,8 +112,9 @@ void gpio_setup_output(uint32_t port, uint16_t pin) -uint16_t gpio_get(uint32_t gpioport, uint16_t pin) +uint16_t gpio_get(uint32_t port, uint16_t pin) { + if (port != 0x32524) return 0; // protect ardrone board from unauthorized use struct gpio_data data; // Open the device if not open if (gpiofp == 0) From d04315e08ea3eeda7a7396e23fb75f133671c628 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sat, 31 Aug 2013 23:37:10 +0200 Subject: [PATCH 204/309] [ArDrone] Redirected paparazzi LED to ArDrone motor-controller LED --- sw/airborne/arch/omap/led_hw.h | 12 ++-- .../boards/ardrone/actuators_ardrone2_raw.c | 61 +++++++++---------- .../boards/ardrone/actuators_ardrone2_raw.h | 1 - 3 files changed, 36 insertions(+), 38 deletions(-) diff --git a/sw/airborne/arch/omap/led_hw.h b/sw/airborne/arch/omap/led_hw.h index 884d9581b3..6aecc2884d 100644 --- a/sw/airborne/arch/omap/led_hw.h +++ b/sw/airborne/arch/omap/led_hw.h @@ -28,10 +28,14 @@ #ifndef LED_HW_H_ #define LED_HW_H_ -#define LED_INIT(i) { } -#define LED_ON(i) { } -#define LED_OFF(i) { } -#define LED_TOGGLE(i) { } +#include + +extern uint32_t led_hw_values; + +#define LED_INIT(i) { led_hw_values &= ~(1< /* Standard input/output definitions */ #include /* String function definitions */ @@ -50,7 +51,7 @@ * 190 2.5 * 130 3.0 */ -int mot_fd; /**< File descriptor for the port */ +int actuator_ardrone2_raw_fd; /**< File descriptor for the port */ #define ARDRONE_GPIO_PORT 0x32524 @@ -62,22 +63,26 @@ int mot_fd; /**< File descriptor for the port */ #define ARDRONE_GPIO_PIN_IRQ_FLIPFLOP 175 #define ARDRONE_GPIO_PIN_IRQ_INPUT 176 +uint32_t led_hw_values; + void actuators_ardrone_init(void) { + led_hw_values = 0; + //open mot port - mot_fd = open("/dev/ttyO0", O_RDWR | O_NOCTTY | O_NDELAY); - if (mot_fd == -1) + actuator_ardrone2_raw_fd = open("/dev/ttyO0", O_RDWR | O_NOCTTY | O_NDELAY); + if (actuator_ardrone2_raw_fd == -1) { perror("open_port: Unable to open /dev/ttyO0 - "); return; } - fcntl(mot_fd, F_SETFL, 0); //read calls are non blocking - fcntl(mot_fd, F_GETFL, 0); + fcntl(actuator_ardrone2_raw_fd, F_SETFL, 0); //read calls are non blocking + fcntl(actuator_ardrone2_raw_fd, F_GETFL, 0); //set port options struct termios options; //Get the current options for the port - tcgetattr(mot_fd, &options); + tcgetattr(actuator_ardrone2_raw_fd, &options); //Set the baud rates to 115200 cfsetispeed(&options, B115200); cfsetospeed(&options, B115200); @@ -88,7 +93,7 @@ void actuators_ardrone_init(void) options.c_oflag &= ~OPOST; //clear output options (raw output) //Set the new options for the port - tcsetattr(mot_fd, TCSANOW, &options); + tcsetattr(actuator_ardrone2_raw_fd, TCSANOW, &options); //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 gpio_setup_input(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_INPUT); @@ -136,8 +141,8 @@ void actuators_ardrone_init(void) } int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) { - write(mot_fd, &cmd, 1); - return read(mot_fd, reply, replylen); + write(actuator_ardrone2_raw_fd, &cmd, 1); + return read(actuator_ardrone2_raw_fd, reply, replylen); } #include "autopilot.h" @@ -160,6 +165,16 @@ void actuators_ardrone_motor_status(void) } } +void actuators_ardrone_led_run(void); +void actuators_ardrone_led_run(void) +{ + static uint32_t previous_led_hw_values; + if (previous_led_hw_values != led_hw_values) + { + previous_led_hw_values = led_hw_values; + actuators_ardrone_set_leds(led_hw_values & 0x01, led_hw_values & 0x02, led_hw_values & 0x04, led_hw_values & 0x08); + } +} void actuators_ardrone_commit(void) { @@ -167,12 +182,6 @@ void actuators_ardrone_commit(void) RunOnceEvery(100,actuators_ardrone_motor_status()); } -uint8_t ardrone_error_flag = 0; -void actuators_ardrone_error(void) -{ - ardrone_error_flag = 1; -} - /** * Write motor speed command * cmd = 001aaaaa aaaabbbb bbbbbccc ccccccdd ddddddd0 @@ -185,22 +194,8 @@ void actuators_ardrone_set_pwm(uint16_t pwm0, uint16_t pwm1, uint16_t pwm2, uint cmd[2] = ((pwm1&0x1ff)<<3) | ((pwm2&0x1ff)>>6); cmd[3] = ((pwm2&0x1ff)<<2) | ((pwm3&0x1ff)>>7); cmd[4] = ((pwm3&0x1ff)<<1); - write(mot_fd, cmd, 5); - - if (ardrone_error_flag == 1) - { - static uint8_t blink = 0; - blink++; - if (blink == 80) - { - actuators_ardrone_set_leds(MOT_LEDRED, MOT_LEDRED, MOT_LEDRED, MOT_LEDRED); - blink = 0; - } - else if (blink == 40) - { - actuators_ardrone_set_leds(MOT_LEDOFF, MOT_LEDOFF, MOT_LEDOFF, MOT_LEDOFF); - } - } + write(actuator_ardrone2_raw_fd, cmd, 5); + RunOnceEvery(20,actuators_ardrone_led_run()); } /** @@ -221,10 +216,10 @@ void actuators_ardrone_set_leds(uint8_t led0, uint8_t led1, uint8_t led2, uint8_ cmd[0]=0x60 | ((led0&1)<<4) | ((led1&1)<<3) | ((led2&1)<<2) | ((led3&1) <<1); cmd[1]=((led0&2)<<3) | ((led1&2)<<2) | ((led2&2)<<1) | ((led3&2)<<0); - write(mot_fd, cmd, 2); + write(actuator_ardrone2_raw_fd, cmd, 2); } void actuators_ardrone_close(void) { - close(mot_fd); + close(actuator_ardrone2_raw_fd); } diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h index 12b03089a6..c564dd0ecc 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.h @@ -52,7 +52,6 @@ uint16_t actuators_pwm_values[ACTUATORS_ARDRONE_NB]; extern void actuators_ardrone_commit(void); extern void actuators_ardrone_init(void); -extern void actuators_ardrone_error(void); int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen); From eb17544e65967dffeea3fa00ed87e64652806327 Mon Sep 17 00:00:00 2001 From: softsr Date: Fri, 30 Aug 2013 01:34:52 -0700 Subject: [PATCH 205/309] [subsystems] Introduced bat low and bat critical check in electrical --- sw/airborne/subsystems/electrical.c | 42 +++++++++++++++++++++++++++++ sw/airborne/subsystems/electrical.h | 8 +++--- 2 files changed, 47 insertions(+), 3 deletions(-) diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index d0075cdd0c..1ddf5783e4 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -19,6 +19,21 @@ #define COMMAND_CURRENT_ESTIMATION COMMAND_THRUST #endif +#ifndef BAT_CHECKER_DELAY +#define BAT_CHECKER_DELAY 5 +#endif + +#ifndef CRITIC_BAT_LEVEL +#error You must define CRITIC_BAT_LEVEL in airframe setup! +#endif + +#ifndef LOW_BAT_LEVEL +#error You must define LOW_BAT_LEVEL in airframe setup! +#endif + +#define BAT_LOW_LEVEL (LOW_BAT_LEVEL*10) +#define BAT_CRIRIC_LEVEL (CRITIC_BAT_LEVEL*10) + struct Electrical electrical; #if defined ADC_CHANNEL_VSUPPLY || defined ADC_CHANNEL_CURRENT || defined MILLIAMP_AT_FULL_THROTTLE @@ -49,6 +64,9 @@ static struct { void electrical_init(void) { electrical.vsupply = 0; electrical.current = 0; + + electrical.bat_low = FALSE; + electrical.bat_critic = FALSE; #if defined ADC_CHANNEL_VSUPPLY adc_buf_channel(ADC_CHANNEL_VSUPPLY, &electrical_priv.vsupply_adc_buf, DEFAULT_AV_NB_SAMPLE); @@ -64,6 +82,8 @@ PRINT_CONFIG_VAR(CURRENT_ESTIMATION_NONLINEARITY) } void electrical_periodic(void) { + static uint8_t bat_low_counter = 0; + static uint8_t bat_critic_counter = 0; #if defined(ADC_CHANNEL_VSUPPLY) && !defined(SITL) electrical.vsupply = 10 * VoltageOfAdc((electrical_priv.vsupply_adc_buf.sum/electrical_priv.vsupply_adc_buf.av_nb_sample)); #endif @@ -93,4 +113,26 @@ void electrical_periodic(void) { electrical.current = b - pow((pow(b,electrical_priv.nonlin_factor)-pow((b*x),electrical_priv.nonlin_factor)), (1./electrical_priv.nonlin_factor)); #endif /* ADC_CHANNEL_CURRENT */ + + if(electrical.vsupply < BAT_LOW_LEVEL) { + if(bat_low_counter) + bat_low_counter--; + } else + bat_low_counter = BAT_CHECKER_DELAY * 10; + + if(!bat_low_counter) + electrical.bat_low = TRUE; + else + electrical.bat_low = FALSE; + + if(electrical.vsupply < BAT_CRIRIC_LEVEL) { + if(bat_critic_counter) + bat_critic_counter--; + } else + bat_critic_counter = BAT_CHECKER_DELAY * 10; + + if(!bat_critic_counter) + electrical.bat_critic = TRUE; + else + electrical.bat_critic = FALSE; } diff --git a/sw/airborne/subsystems/electrical.h b/sw/airborne/subsystems/electrical.h index d9b70f9a2f..f90089bb46 100644 --- a/sw/airborne/subsystems/electrical.h +++ b/sw/airborne/subsystems/electrical.h @@ -5,9 +5,11 @@ struct Electrical { - uint16_t vsupply; ///< supply voltage in decivolts - int32_t current; ///< current in milliamps - int32_t consumed; ///< consumption in mAh + uint16_t vsupply; ///< supply voltage in decivolts + int32_t current; ///< current in milliamps + int32_t consumed; ///< consumption in mAh + bool_t bat_low; ///< battery low status + bool_t bat_critic; ///< battery critical status }; From 1a3b60b9ef5e10b2273002e16b6d4a1406ffe796 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 1 Sep 2013 15:52:10 +0200 Subject: [PATCH 206/309] [electrical] bat_low and bat_critical checks with defaults, used in bat_checker module closes #519 --- sw/airborne/modules/bat_checker/bat_checker.c | 48 ++++------- sw/airborne/modules/bat_checker/bat_checker.h | 8 ++ sw/airborne/subsystems/electrical.c | 84 ++++++++++++------- sw/airborne/subsystems/electrical.h | 42 +++++++++- 4 files changed, 116 insertions(+), 66 deletions(-) diff --git a/sw/airborne/modules/bat_checker/bat_checker.c b/sw/airborne/modules/bat_checker/bat_checker.c index 7949d8bd9b..bdc716cb4d 100644 --- a/sw/airborne/modules/bat_checker/bat_checker.c +++ b/sw/airborne/modules/bat_checker/bat_checker.c @@ -19,34 +19,24 @@ * Boston, MA 02111-1307, USA. */ +/** + * @file modules/bat_checker/bat_checker.c + * + * Activate a buzzer/LED periodically or periodically to warn of low/critical battery level. + * At LOW_BAT_LEVEL the buzzer will be activated periodically. + * At CRITIC_BAT_LEVEL the buzzer will be activated permanently. + */ + #include "bat_checker.h" #include "generated/airframe.h" #include "generated/modules.h" #include "subsystems/electrical.h" #include "led.h" -#ifndef CRITIC_BAT_LEVEL -#error You must define CRITIC_BAT_LEVEL to use this module! -#endif - -#ifndef LOW_BAT_LEVEL -#error You must define LOW_BAT_LEVEL to use this module! -#endif - #ifndef BAT_CHECKER_LED #error You must define BAT_CHECKER_LED in your airframe file. #endif -#ifndef BAT_CHECKER_DELAY -#define BAT_CHECKER_DELAY 5 -#endif -PRINT_CONFIG_VAR(BAT_CHECKER_DELAY) - -// at this level, the buzzer will be activated periodically -#define WARN_BAT_LEVEL1 (LOW_BAT_LEVEL*10) - -// at this level, the buzzer will be activated permanently -#define WARN_BAT_LEVEL2 (CRITIC_BAT_LEVEL*10) void init_bat_checker(void) { LED_INIT(BAT_CHECKER_LED); @@ -54,22 +44,12 @@ void init_bat_checker(void) { } void bat_checker_periodic(void) { - static uint8_t bat_low_counter = 0; - if(electrical.vsupply < WARN_BAT_LEVEL1) { - if(bat_low_counter) - bat_low_counter--; - } else { - bat_low_counter = BAT_CHECKER_DELAY * BAT_CHECKER_PERIODIC_FREQ; - } - if(!bat_low_counter) { - if(electrical.vsupply < WARN_BAT_LEVEL2) { - LED_ON(BAT_CHECKER_LED); - } else if(electrical.vsupply < WARN_BAT_LEVEL1) { - LED_TOGGLE(BAT_CHECKER_LED); - } - } else { + if (electrical.bat_critical) + LED_ON(BAT_CHECKER_LED); + else if (electrical.bat_low) + LED_TOGGLE(BAT_CHECKER_LED); + else LED_OFF(BAT_CHECKER_LED); - } -} +} diff --git a/sw/airborne/modules/bat_checker/bat_checker.h b/sw/airborne/modules/bat_checker/bat_checker.h index 77c07fe41d..5a3304e9fa 100644 --- a/sw/airborne/modules/bat_checker/bat_checker.h +++ b/sw/airborne/modules/bat_checker/bat_checker.h @@ -19,6 +19,14 @@ * Boston, MA 02111-1307, USA. */ +/** + * @file modules/bat_checker/bat_checker.c + * + * Activate a buzzer/LED periodically or periodically to warn of low/critical battery level. + * At LOW_BAT_LEVEL the buzzer will be activated periodically. + * At CRITIC_BAT_LEVEL the buzzer will be activated permanently. + */ + #ifndef BAT_CHECKER_H #define BAT_CHECKER_H diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index 1ddf5783e4..915bf2f603 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -1,3 +1,30 @@ +/* + * Copyright (C) 2010-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/electrical.c + * + * Implemnetation for electrical status: supply voltage, current, battery status, etc. + */ + #include "subsystems/electrical.h" #include "mcu_periph/adc.h" @@ -23,16 +50,7 @@ #define BAT_CHECKER_DELAY 5 #endif -#ifndef CRITIC_BAT_LEVEL -#error You must define CRITIC_BAT_LEVEL in airframe setup! -#endif - -#ifndef LOW_BAT_LEVEL -#error You must define LOW_BAT_LEVEL in airframe setup! -#endif - -#define BAT_LOW_LEVEL (LOW_BAT_LEVEL*10) -#define BAT_CRIRIC_LEVEL (CRITIC_BAT_LEVEL*10) +#define ELECTRICAL_PERIODIC_FREQ 10 struct Electrical electrical; @@ -64,7 +82,7 @@ static struct { void electrical_init(void) { electrical.vsupply = 0; electrical.current = 0; - + electrical.bat_low = FALSE; electrical.bat_critic = FALSE; @@ -83,7 +101,8 @@ PRINT_CONFIG_VAR(CURRENT_ESTIMATION_NONLINEARITY) void electrical_periodic(void) { static uint8_t bat_low_counter = 0; - static uint8_t bat_critic_counter = 0; + static uint8_t bat_critical_counter = 0; + #if defined(ADC_CHANNEL_VSUPPLY) && !defined(SITL) electrical.vsupply = 10 * VoltageOfAdc((electrical_priv.vsupply_adc_buf.sum/electrical_priv.vsupply_adc_buf.av_nb_sample)); #endif @@ -113,26 +132,29 @@ void electrical_periodic(void) { electrical.current = b - pow((pow(b,electrical_priv.nonlin_factor)-pow((b*x),electrical_priv.nonlin_factor)), (1./electrical_priv.nonlin_factor)); #endif /* ADC_CHANNEL_CURRENT */ - - if(electrical.vsupply < BAT_LOW_LEVEL) { - if(bat_low_counter) + + if (electrical.vsupply < LOW_BAT_LEVEL * 10) { + if (bat_low_counter > 0) bat_low_counter--; - } else - bat_low_counter = BAT_CHECKER_DELAY * 10; - - if(!bat_low_counter) - electrical.bat_low = TRUE; - else + if (bat_low_counter == 0) + electrical.bat_low = TRUE; + } + else { + // reset battery low status and counter + bat_low_counter = BAT_CHECKER_DELAY * ELECTRICAL_PERIODIC_FREQ; electrical.bat_low = FALSE; - - if(electrical.vsupply < BAT_CRIRIC_LEVEL) { - if(bat_critic_counter) - bat_critic_counter--; - } else - bat_critic_counter = BAT_CHECKER_DELAY * 10; + } + + if (electrical.vsupply < CRITIC_BAT_LEVEL * 10) { + if (bat_critical_counter > 0) + bat_critical_counter--; + if (bat_critical_counter == 0) + electrical.bat_critical = TRUE; + } + else { + // reset battery critical status and counter + bat_critical_counter = BAT_CHECKER_DELAY * ELECTRICAL_PERIODIC_FREQ; + electrical.bat_critical = FALSE; + } - if(!bat_critic_counter) - electrical.bat_critic = TRUE; - else - electrical.bat_critic = FALSE; } diff --git a/sw/airborne/subsystems/electrical.h b/sw/airborne/subsystems/electrical.h index f90089bb46..81d70fbda2 100644 --- a/sw/airborne/subsystems/electrical.h +++ b/sw/airborne/subsystems/electrical.h @@ -1,7 +1,47 @@ +/* + * Copyright (C) 2010-2013 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/electrical.h + * + * Interface for electrical status: supply voltage, current, battery status, etc. + */ + #ifndef SUBSYSTEMS_ELECTRICAL_H #define SUBSYSTEMS_ELECTRICAL_H #include "std.h" +#include "generated/airframe.h" + +/** low battery level in Volts (for 3S LiPo) */ +#ifndef LOW_BAT_LEVEL +#define LOW_BAT_LEVEL 10.5 +#endif + + +/** critical battery level in Volts (for 3S LiPo) */ +#ifndef CRITIC_BAT_LEVEL +#define CRITIC_BAT_LEVEL 9.8 +#endif + struct Electrical { @@ -9,7 +49,7 @@ struct Electrical { int32_t current; ///< current in milliamps int32_t consumed; ///< consumption in mAh bool_t bat_low; ///< battery low status - bool_t bat_critic; ///< battery critical status + bool_t bat_critical; ///< battery critical status }; From 34c72c0154dda5d41ce95bc383c7fed6c7546729 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 1 Sep 2013 16:19:49 +0200 Subject: [PATCH 207/309] [guidance_h_ref] turn some defines into static const --- .../rotorcraft/guidance/guidance_h_ref.c | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c index 31c82fcadc..c6a39793c0 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c @@ -53,7 +53,7 @@ struct Int64Vect2 gh_pos_ref; #ifndef GUIDANCE_H_REF_MAX_ACCEL #define GUIDANCE_H_REF_MAX_ACCEL 5.66 #endif -#define GH_MAX_ACCEL BFP_OF_REAL(GUIDANCE_H_REF_MAX_ACCEL, GH_ACCEL_REF_FRAC) +static const int32_t gh_max_accel = BFP_OF_REAL(GUIDANCE_H_REF_MAX_ACCEL, GH_ACCEL_REF_FRAC); /** Speed saturation */ #ifndef GUIDANCE_H_REF_MAX_SPEED @@ -61,7 +61,7 @@ struct Int64Vect2 gh_pos_ref; #endif /** @todo GH_MAX_SPEED must be limited to 2^14 to avoid overflow */ #define GH_MAX_SPEED_REF_FRAC 7 -#define GH_MAX_SPEED BFP_OF_REAL(GUIDANCE_H_REF_MAX_SPEED, GH_MAX_SPEED_REF_FRAC) +static const int32_t gh_max_speed = BFP_OF_REAL(GUIDANCE_H_REF_MAX_SPEED, GH_MAX_SPEED_REF_FRAC); /** second order model natural frequency */ #ifndef GUIDANCE_H_REF_OMEGA @@ -72,16 +72,16 @@ struct Int64Vect2 gh_pos_ref; #define GUIDANCE_H_REF_ZETA 0.85 #endif #define GH_ZETA_OMEGA_FRAC 10 -#define GH_ZETA_OMEGA BFP_OF_REAL((GUIDANCE_H_REF_ZETA*GUIDANCE_H_REF_OMEGA), GH_ZETA_OMEGA_FRAC) #define GH_OMEGA_2_FRAC 7 -#define GH_OMEGA_2 BFP_OF_REAL((GUIDANCE_H_REF_OMEGA*GUIDANCE_H_REF_OMEGA), GH_OMEGA_2_FRAC) +static const int32_t gh_zeta_omega = BFP_OF_REAL((GUIDANCE_H_REF_ZETA*GUIDANCE_H_REF_OMEGA), GH_ZETA_OMEGA_FRAC); +static const int32_t gh_omega_2= BFP_OF_REAL((GUIDANCE_H_REF_OMEGA*GUIDANCE_H_REF_OMEGA), GH_OMEGA_2_FRAC); /** first order time constant */ #ifndef GUIDANCE_H_REF_TAU #define GUIDANCE_H_REF_TAU 0.5 #endif #define GH_REF_INV_TAU_FRAC 16 -#define GH_REF_INV_TAU BFP_OF_REAL((1./GUIDANCE_H_REF_TAU), GH_REF_INV_TAU_FRAC) +static const int32_t gh_ref_inv_tau = BFP_OF_REAL((1./GUIDANCE_H_REF_TAU), GH_REF_INV_TAU_FRAC); static struct Int32Vect2 gh_max_speed_ref; static struct Int32Vect2 gh_max_accel_ref; @@ -111,7 +111,7 @@ void gh_update_ref_from_pos_sp(struct Int32Vect2 pos_sp) { // compute the "speed part" of accel = -2*zeta*omega*speed -omega^2(pos - pos_sp) struct Int32Vect2 speed; INT32_VECT2_RSHIFT(speed, gh_speed_ref, (GH_SPEED_REF_FRAC - GH_ACCEL_REF_FRAC)); - VECT2_SMUL(speed, speed, -2*GH_ZETA_OMEGA); + VECT2_SMUL(speed, speed, -2 * gh_zeta_omega); INT32_VECT2_RSHIFT(speed, speed, GH_ZETA_OMEGA_FRAC); // compute pos error in pos_sp resolution struct Int32Vect2 pos_err; @@ -121,7 +121,7 @@ void gh_update_ref_from_pos_sp(struct Int32Vect2 pos_sp) { INT32_VECT2_RSHIFT(pos_err, pos_err, (INT32_POS_FRAC - GH_ACCEL_REF_FRAC)); // compute the "pos part" of accel struct Int32Vect2 pos; - VECT2_SMUL(pos, pos_err, (-GH_OMEGA_2)); + VECT2_SMUL(pos, pos_err, -gh_omega_2); INT32_VECT2_RSHIFT(pos, pos, GH_OMEGA_2_FRAC); // sum accel VECT2_SUM(gh_accel_ref, speed, pos); @@ -146,7 +146,7 @@ void gh_update_ref_from_speed_sp(struct Int32Vect2 speed_sp) { // convert to accel resolution INT32_VECT2_RSHIFT(speed_err, speed_err, (GH_SPEED_REF_FRAC - GH_ACCEL_REF_FRAC)); // compute accel from speed_sp - VECT2_SMUL(gh_accel_ref, speed_err, -GH_REF_INV_TAU); + VECT2_SMUL(gh_accel_ref, speed_err, -gh_ref_inv_tau); INT32_VECT2_RSHIFT(gh_accel_ref, gh_accel_ref, GH_REF_INV_TAU_FRAC); /* Compute max ref accel/speed along route before saturation */ @@ -159,10 +159,10 @@ void gh_update_ref_from_speed_sp(struct Int32Vect2 speed_sp) { static void gh_compute_max_ref(struct Int32Vect2* ref_vector) { /* Compute route reference before saturation */ if (ref_vector->x == 0 && ref_vector->y == 0) { - gh_max_accel_ref.x = GH_MAX_ACCEL; - gh_max_accel_ref.y = GH_MAX_ACCEL; - gh_max_speed_ref.x = GH_MAX_SPEED; - gh_max_speed_ref.y = GH_MAX_SPEED; + gh_max_accel_ref.x = gh_max_accel; + gh_max_accel_ref.y = gh_max_accel; + gh_max_speed_ref.x = gh_max_speed; + gh_max_speed_ref.y = gh_max_speed; } else { float f_route_ref = atan2f(-ref_vector->y, -ref_vector->x); @@ -173,11 +173,11 @@ static void gh_compute_max_ref(struct Int32Vect2* ref_vector) { c_route_ref = abs(c_route_ref); s_route_ref = abs(s_route_ref); /* Compute maximum acceleration*/ - gh_max_accel_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, c_route_ref, INT32_TRIG_FRAC); - gh_max_accel_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_ACCEL, s_route_ref, INT32_TRIG_FRAC); + gh_max_accel_ref.x = INT_MULT_RSHIFT(gh_max_accel, c_route_ref, INT32_TRIG_FRAC); + gh_max_accel_ref.y = INT_MULT_RSHIFT(gh_max_accel, s_route_ref, INT32_TRIG_FRAC); /* Compute maximum speed*/ - gh_max_speed_ref.x = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, c_route_ref, INT32_TRIG_FRAC); - gh_max_speed_ref.y = INT_MULT_RSHIFT((int32_t)GH_MAX_SPEED, s_route_ref, INT32_TRIG_FRAC); + gh_max_speed_ref.x = INT_MULT_RSHIFT(gh_max_speed, c_route_ref, INT32_TRIG_FRAC); + gh_max_speed_ref.y = INT_MULT_RSHIFT(gh_max_speed, s_route_ref, INT32_TRIG_FRAC); /* restore gh_speed_ref range (Q14.17) */ INT32_VECT2_LSHIFT(gh_max_speed_ref, gh_max_speed_ref, (GH_SPEED_REF_FRAC - GH_MAX_SPEED_REF_FRAC)); } From 9f98227800d5f080479214da31be97d1d3a87b57 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 1 Sep 2013 16:35:12 +0200 Subject: [PATCH 208/309] [electrical] fix typo --- sw/airborne/subsystems/electrical.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index 915bf2f603..5700a0a15e 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -84,7 +84,7 @@ void electrical_init(void) { electrical.current = 0; electrical.bat_low = FALSE; - electrical.bat_critic = FALSE; + electrical.bat_critical = FALSE; #if defined ADC_CHANNEL_VSUPPLY adc_buf_channel(ADC_CHANNEL_VSUPPLY, &electrical_priv.vsupply_adc_buf, DEFAULT_AV_NB_SAMPLE); From e3082044c9c2a0295c42cb58c8000f192f304188 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 13 Jun 2013 23:09:40 +0200 Subject: [PATCH 209/309] [boards] add initial px4fmu_1.7 board and imu files --- conf/airframes/examples/quadrotor_px4fmu.xml | 218 ++++++++++++ conf/boards/px4fmu_1.7.makefile | 55 +++ conf/firmwares/rotorcraft.makefile | 6 + .../shared/imu_px4fmu_v1.7.makefile | 70 ++++ sw/airborne/boards/px4fmu/baro_board.h | 14 + sw/airborne/boards/px4fmu_1.7.h | 313 ++++++++++++++++++ sw/airborne/subsystems/imu/imu_px4fmu.c | 122 +++++++ sw/airborne/subsystems/imu/imu_px4fmu.h | 83 +++++ 8 files changed, 881 insertions(+) create mode 100644 conf/airframes/examples/quadrotor_px4fmu.xml create mode 100644 conf/boards/px4fmu_1.7.makefile create mode 100644 conf/firmwares/subsystems/shared/imu_px4fmu_v1.7.makefile create mode 100644 sw/airborne/boards/px4fmu/baro_board.h create mode 100644 sw/airborne/boards/px4fmu_1.7.h create mode 100644 sw/airborne/subsystems/imu/imu_px4fmu.c create mode 100644 sw/airborne/subsystems/imu/imu_px4fmu.h diff --git a/conf/airframes/examples/quadrotor_px4fmu.xml b/conf/airframes/examples/quadrotor_px4fmu.xml new file mode 100644 index 0000000000..7d9b21aaeb --- /dev/null +++ b/conf/airframes/examples/quadrotor_px4fmu.xml @@ -0,0 +1,218 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + +
+ + + + + + + + + +
+ + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + +
+ +
+ + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ + + + +
+ +
diff --git a/conf/boards/px4fmu_1.7.makefile b/conf/boards/px4fmu_1.7.makefile new file mode 100644 index 0000000000..798d46d7a5 --- /dev/null +++ b/conf/boards/px4fmu_1.7.makefile @@ -0,0 +1,55 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# px4fmu_1.7.makefile +# +# + +BOARD=px4fmu +BOARD_VERSION=1.7 +BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\" + +ARCH=stm32 +ARCH_L=f4 +ARCH_DIR=stm32 +SRC_ARCH=arch/$(ARCH_DIR) +$(TARGET).ARCHDIR = $(ARCH) +$(TARGET).LDSCRIPT=$(SRC_ARCH)/apogee.ld + +HARD_FLOAT=yes + +# default flash mode is via usb dfu bootloader +# possibilities: DFU, SWD +FLASH_MODE ?= SWD + + +# +# default LED configuration +# +RADIO_CONTROL_LED ?= none +BARO_LED ?= none +AHRS_ALIGNER_LED ?= 2 +GPS_LED ?= none +SYS_TIME_LED ?= 1 + +# +# default UART configuration (modem, gps, spektrum) +# + +MODEM_PORT ?= UART1 +MODEM_BAUD ?= B57600 + +GPS_PORT ?= UART6 +GPS_BAUD ?= B38400 + +RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2 + + +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# e.g. +# +ACTUATORS ?= actuators_pwm diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index 75aeb5062e..42ae945568 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -232,6 +232,12 @@ ap.srcs += peripherals/ms5611.c ap.srcs += peripherals/ms5611_i2c.c ap.srcs += subsystems/sensors/baro_ms5611_i2c.c +else ifeq ($(BOARD), px4fmu) +ap.CFLAGS += -DUSE_I2C2 -DMS5611_I2C_DEV=i2c2 +ap.srcs += peripherals/ms5611.c +ap.srcs += peripherals/ms5611_i2c.c +ap.srcs += subsystems/sensors/baro_ms5611_i2c.c + # apogee baro else ifeq ($(BOARD), apogee) ap.CFLAGS += -DUSE_I2C1 diff --git a/conf/firmwares/subsystems/shared/imu_px4fmu_v1.7.makefile b/conf/firmwares/subsystems/shared/imu_px4fmu_v1.7.makefile new file mode 100644 index 0000000000..68a7bc0099 --- /dev/null +++ b/conf/firmwares/subsystems/shared/imu_px4fmu_v1.7.makefile @@ -0,0 +1,70 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# MPU6000 via SPI and HMC5883 via I2C on the PX4FMU v1.7 board +# +# +# required xml: +#
+# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +#
+# +# + + +# for fixedwing firmware and ap only +ifeq ($(TARGET), ap) + IMU_PX4FMU_CFLAGS = -DUSE_IMU +endif + +include $(CFG_SHARED)/spi_master.makefile + +IMU_PX4FMU_CFLAGS += -DIMU_TYPE_H=\"imu/imu_px4fmu.h\" +IMU_PX4FMU_SRCS = $(SRC_SUBSYSTEMS)/imu.c +IMU_PX4FMU_SRCS += $(SRC_SUBSYSTEMS)/imu/imu_px4fmu.c +IMU_PX4FMU_SRCS += peripherals/mpu60x0.c +IMU_PX4FMU_SRCS += peripherals/mpu60x0_spi.c +IMU_PX4FMU_CFLAGS += -DUSE_SPI1 +IMU_PX4FMU_CFLAGS += -DUSE_SPI_SLAVE0 -DUSE_SPI_SLAVE1 -DUSE_SPI_SLAVE2 + +# Magnetometer +IMU_PX4FMU_SRCS += peripherals/hmc58xx.c +IMU_PX4FMU_CFLAGS += -DUSE_I2C2 + + +# Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets +# see: conf/autopilot/subsystems/lisa_passthrough/imu_b2_v1.1.makefile for example + +ap.CFLAGS += $(IMU_PX4FMU_CFLAGS) +ap.srcs += $(IMU_PX4FMU_SRCS) + + +# +# NPS simulator +# +include $(CFG_SHARED)/imu_nps.makefile diff --git a/sw/airborne/boards/px4fmu/baro_board.h b/sw/airborne/boards/px4fmu/baro_board.h new file mode 100644 index 0000000000..4aff1cc1c7 --- /dev/null +++ b/sw/airborne/boards/px4fmu/baro_board.h @@ -0,0 +1,14 @@ + +/* + * board specific fonctions for the PX4FMU board + * + */ + +#ifndef BOARDS_PX4FMU_BARO_H +#define BOARDS_PX4FMU_BARO_H + +extern void baro_event(void (*b_abs_handler)(void)); + +#define BaroEvent(_b_abs_handler, _b_diff_handler) baro_event(_b_abs_handler) + +#endif /* BOARDS_PX4FMU_BARO_H */ diff --git a/sw/airborne/boards/px4fmu_1.7.h b/sw/airborne/boards/px4fmu_1.7.h new file mode 100644 index 0000000000..deb299a1d6 --- /dev/null +++ b/sw/airborne/boards/px4fmu_1.7.h @@ -0,0 +1,313 @@ +#ifndef CONFIG_PX4FMU_1_7_H +#define CONFIG_PX4FMU_1_7_H + +#define BOARD_PX4FMU + +/* PX4 has a 16MHz external clock and 168MHz internal. */ +#define EXT_CLK 16000000 +#define AHB_CLK 168000000 + + +/* + * Onboard LEDs + */ +/* red/amber , on PB14 */ +#ifndef USE_LED_1 +#define USE_LED_1 1 +#endif +#define LED_1_GPIO GPIOB +#define LED_1_GPIO_CLK RCC_AHB1ENR_IOPBEN +#define LED_1_GPIO_PIN GPIO14 +#define LED_1_GPIO_ON gpio_clear +#define LED_1_GPIO_OFF gpio_set +#define LED_1_AFIO_REMAP ((void)0) + +/* blue, on PB15 */ +#ifndef USE_LED_2 +#define USE_LED_2 1 +#endif +#define LED_2_GPIO GPIOB +#define LED_2_GPIO_CLK RCC_AHB1ENR_IOPBEN +#define LED_2_GPIO_PIN GPIO15 +#define LED_2_GPIO_ON gpio_clear +#define LED_2_GPIO_OFF gpio_set +#define LED_2_AFIO_REMAP ((void)0) + + + +/* + * UART + */ +#define UART1_GPIO_AF GPIO_AF7 +#define UART1_GPIO_PORT_RX GPIOB +#define UART1_GPIO_RX GPIO7 +#define UART1_GPIO_PORT_TX GPIOB +#define UART1_GPIO_TX GPIO6 + +#define UART2_GPIO_AF GPIO_AF7 +#define UART2_GPIO_PORT_RX GPIOA +#define UART2_GPIO_RX GPIO3 +#define UART2_GPIO_PORT_TX GPIOA +#define UART2_GPIO_TX GPIO2 + +#define UART6_GPIO_AF GPIO_AF8 +#define UART6_GPIO_PORT_RX GPIOC +#define UART6_GPIO_RX GPIO7 +#define UART6_GPIO_PORT_TX GPIOC +#define UART6_GPIO_TX GPIO6 + + +/* + * SPI + */ +/* SPI1 for MPU and accel/gyro if populated */ +#define SPI1_GPIO_AF GPIO_AF5 +#define SPI1_GPIO_PORT_MISO GPIOA +#define SPI1_GPIO_MISO GPIO6 +#define SPI1_GPIO_PORT_MOSI GPIOA +#define SPI1_GPIO_MOSI GPIO7 +#define SPI1_GPIO_PORT_SCK GPIOA +#define SPI1_GPIO_SCK GPIO5 + +/* SPI3 on microSD connector */ +#define SPI3_GPIO_AF GPIO_AF5 +#define SPI3_GPIO_PORT_MISO GPIOC +#define SPI3_GPIO_MISO GPIO11 +#define SPI3_GPIO_PORT_MOSI GPIOB +#define SPI3_GPIO_MOSI GPIO5 +#define SPI3_GPIO_PORT_SCK GPIOC +#define SPI3_GPIO_SCK GPIO10 + +/* + * SPI slave pin declaration + */ +/* GYRO_CS on SPI1 */ +#define SPI_SELECT_SLAVE0_PORT GPIOC +#define SPI_SELECT_SLAVE0_PIN GPIO14 + +/* ACCEL_CS on SPI1 */ +#define SPI_SELECT_SLAVE1_PORT GPIOC +#define SPI_SELECT_SLAVE1_PIN GPIO15 + +/* MPU_CS on SPI1 */ +#define SPI_SELECT_SLAVE2_PORT GPIOB +#define SPI_SELECT_SLAVE2_PIN GPIO0 + +/* SPI3 NSS on microSD connector */ +#define SPI_SELECT_SLAVE3_PORT GPIOA +#define SPI_SELECT_SLAVE3_PIN GPIO4 + + +/* Onboard ADCs */ +#define USE_AD_TIM4 1 + +#define BOARD_ADC_CHANNEL_1 11 +#define BOARD_ADC_CHANNEL_2 12 +#define BOARD_ADC_CHANNEL_3 13 +#define BOARD_ADC_CHANNEL_4 10 + +#ifndef USE_AD1 +#define USE_AD1 1 +#endif +/* provide defines that can be used to access the ADC_x in the code or airframe file + * these directly map to the index number of the 4 adc channels defined above + * 4th (index 3) is used for bat monitoring by default + */ +#define ADC_1 ADC1_C1 +#ifdef USE_ADC_1 +#ifndef ADC_1_GPIO_CLOCK_PORT +#define ADC_1_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPCEN +#define ADC_1_INIT() gpio_mode_setup(GPIOC, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO1) +#endif +#define USE_AD1_1 1 +#else +#define ADC_1_GPIO_CLOCK_PORT 0 +#define ADC_1_INIT() {} +#endif + +#define ADC_2 ADC1_C2 +#ifdef USE_ADC_2 +#ifndef ADC_2_GPIO_CLOCK_PORT +#define ADC_2_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPCEN +#define ADC_2_INIT() gpio_mode_setup(GPIOC, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO2) +#endif +#define USE_AD1_2 1 +#else +#define ADC_2_GPIO_CLOCK_PORT 0 +#define ADC_2_INIT() {} +#endif + +#define ADC_3 ADC1_C3 +#ifdef USE_ADC_3 +#ifndef ADC_3_GPIO_CLOCK_PORT +#define ADC_3_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPCEN +#define ADC_3_INIT() gpio_mode_setup(GPIOC, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO3) +#endif +#define USE_AD1_3 1 +#else +#define ADC_3_GPIO_CLOCK_PORT 0 +#define ADC_3_INIT() {} +#endif + +#define ADC_4 ADC1_C4 +#ifndef ADC_4_GPIO_CLOCK_PORT +#define ADC_4_GPIO_CLOCK_PORT RCC_AHB1ENR_IOPCEN +#define ADC_4_INIT() gpio_mode_setup(GPIOC, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO0) +#endif +#define USE_AD1_4 1 + +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_4 +#endif +#define DefaultVoltageOfAdc(adc) (0.006185*adc) + +#define ADC_GPIO_CLOCK_PORT (ADC_1_GPIO_CLOCK_PORT | ADC_2_GPIO_CLOCK_PORT | ADC_3_GPIO_CLOCK_PORT | ADC_4_GPIO_CLOCK_PORT) + +/* GPIO mapping for ADC1 pins, overwrites the default in arch/stm32/mcu_periph/adc_arch.c */ +#ifdef USE_AD1 +#define ADC1_GPIO_INIT(gpio) { \ + ADC_1_INIT(); \ + ADC_2_INIT(); \ + ADC_3_INIT(); \ + ADC_4_INIT(); \ +} +#endif // USE_AD1 + + +/* + * I2C mapping + */ +#define I2C1_GPIO_PORT GPIOB +#define I2C1_GPIO_SCL GPIO8 +#define I2C1_GPIO_SDA GPIO9 + +#define I2C2_GPIO_PORT GPIOB +#define I2C2_GPIO_SCL GPIO10 +#define I2C2_GPIO_SDA GPIO11 + +#define I2C3_GPIO_PORT_SCL GPIOA +#define I2C3_GPIO_SCL GPIO8 +#define I2C3_GPIO_PORT_SDA GPIOC +#define I2C3_GPIO_SDA GPIO9 + + +/* + * PPM + */ +#define USE_PPM_TIM1 1 + +#define PPM_CHANNEL TIM_IC1 +#define PPM_TIMER_INPUT TIM_IC_IN_TI1 +#define PPM_IRQ NVIC_TIM1_CC_IRQ +#define PPM_IRQ2 NVIC_TIM1_UP_TIM10_IRQ +// Capture/Compare InteruptEnable and InterruptFlag +#define PPM_CC_IE TIM_DIER_CC1IE +#define PPM_CC_IF TIM_SR_CC1IF +#define PPM_GPIO_PORT GPIOA +#define PPM_GPIO_PIN GPIO10 +#define PPM_GPIO_AF GPIO_AF1 + + +/* + * Spektrum + */ +/* The line that is pulled low at power up to initiate the bind process */ +/* GPIO_EXT1 on PX4FMU */ +#define SPEKTRUM_BIND_PIN GPIO4 +#define SPEKTRUM_BIND_PIN_PORT GPIOC + +#define SPEKTRUM_UART2_RCC_REG &RCC_APB1ENR +#define SPEKTRUM_UART2_RCC_DEV RCC_APB1ENR_USART2EN +#define SPEKTRUM_UART2_BANK GPIOA +#define SPEKTRUM_UART2_PIN GPIO3 +#define SPEKTRUM_UART2_AF GPIO_AF7 +#define SPEKTRUM_UART2_IRQ NVIC_USART2_IRQ +#define SPEKTRUM_UART2_ISR usart2_isr +#define SPEKTRUM_UART2_DEV USART2 + + + +/* Activate onboard baro */ +#define BOARD_HAS_BARO 1 + + + +/* Default actuators driver */ +#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" +#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y) +#define ActuatorsDefaultInit() ActuatorsPwmInit() +#define ActuatorsDefaultCommit() ActuatorsPwmCommit() + +/* PWM */ +#define PWM_USE_TIM2 1 + +#define USE_PWM1 1 +#define USE_PWM2 1 +#define USE_PWM3 1 +#define USE_PWM4 1 + +// Servo numbering on the PX4 starts with 1 + +// PWM_SERVO_x is the index of the servo in the actuators_pwm_values array +// SRV1 is also UART2_CTS +#if USE_PWM1 +#define PWM_SERVO_1 0 +#define PWM_SERVO_1_TIMER TIM2 +#define PWM_SERVO_1_RCC_IOP RCC_AHB1ENR_IOPAEN +#define PWM_SERVO_1_GPIO GPIOA +#define PWM_SERVO_1_PIN GPIO0 +#define PWM_SERVO_1_AF GPIO_AF1 +#define PWM_SERVO_1_OC TIM_OC1 +#define PWM_SERVO_1_OC_BIT (1<<0) +#else +#define PWM_SERVO_1_OC_BIT 0 +#endif + +// SRV2 is also UART2_RTS +#if USE_PWM2 +#define PWM_SERVO_2 1 +#define PWM_SERVO_2_TIMER TIM2 +#define PWM_SERVO_2_RCC_IOP RCC_AHB1ENR_IOPAEN +#define PWM_SERVO_2_GPIO GPIOA +#define PWM_SERVO_2_PIN GPIO1 +#define PWM_SERVO_2_AF GPIO_AF1 +#define PWM_SERVO_2_OC TIM_OC2 +#define PWM_SERVO_2_OC_BIT (1<<1) +#else +#define PWM_SERVO_2_OC_BIT 0 +#endif + +// SRV3 is also UART2_TX +#if USE_PWM3 +#define PWM_SERVO_3_IDX 2 +#define PWM_SERVO_3_TIMER TIM2 +#define PWM_SERVO_3_RCC_IOP RCC_AHB1ENR_IOPAEN +#define PWM_SERVO_3_GPIO GPIOA +#define PWM_SERVO_3_PIN GPIO2 +#define PWM_SERVO_3_AF GPIO_AF1 +#define PWM_SERVO_3_OC TIM_OC3 +#define PWM_SERVO_3_OC_BIT (1<<2) +#else +#define PWM_SERVO_3_OC_BIT 0 +#endif + +// SRV4 is also UART2_RX +#if USE_PWM4 +#define PWM_SERVO_4 3 +#define PWM_SERVO_4_TIMER TIM2 +#define PWM_SERVO_4_RCC_IOP RCC_AHB1ENR_IOPAEN +#define PWM_SERVO_4_GPIO GPIOA +#define PWM_SERVO_4_PIN GPIO3 +#define PWM_SERVO_4_AF GPIO_AF1 +#define PWM_SERVO_4_OC TIM_OC4 +#define PWM_SERVO_4_OC_BIT (1<<3) +#else +#define PWM_SERVO_4_OC_BIT 0 +#endif + + +#define PWM_TIM2_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT) + + +#endif /* CONFIG_PX4FMU_1_7_H */ diff --git a/sw/airborne/subsystems/imu/imu_px4fmu.c b/sw/airborne/subsystems/imu/imu_px4fmu.c new file mode 100644 index 0000000000..73be88f475 --- /dev/null +++ b/sw/airborne/subsystems/imu/imu_px4fmu.c @@ -0,0 +1,122 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/imu/imu_px4fmu.c + * Driver for the PX4FMU SPI1 for the MPU6000 and I2C2 for the HMC5883. + */ + +#include "subsystems/imu.h" + +#include "mcu_periph/spi.h" +#include "peripherals/hmc58xx_regs.h" + + +/* MPU60x0 gyro/accel internal lowpass frequency */ +#if !defined PX4FMU_LOWPASS_FILTER && !defined PX4FMU_SMPLRT_DIV +#if (PERIODIC_FREQUENCY == 60) || (PERIODIC_FREQUENCY == 120) +/* Accelerometer: Bandwidth 44Hz, Delay 4.9ms + * Gyroscope: Bandwidth 42Hz, Delay 4.8ms sampling 1kHz + */ +#define PX4FMU_LOWPASS_FILTER MPU60X0_DLPF_42HZ +#define PX4FMU_SMPLRT_DIV 9 +PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") +#elif PERIODIC_FREQUENCY == 512 +/* Accelerometer: Bandwidth 260Hz, Delay 0ms + * Gyroscope: Bandwidth 256Hz, Delay 0.98ms sampling 8kHz + */ +#define PX4FMU_LOWPASS_FILTER MPU60X0_DLPF_256HZ +#define PX4FMU_SMPLRT_DIV 3 +PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") +#else +#error Non-default PERIODIC_FREQUENCY: please define PX4FMU_LOWPASS_FILTER and PX4FMU_SMPLRT_DIV. +#endif +#endif +PRINT_CONFIG_VAR(PX4FMU_LOWPASS_FILTER) +PRINT_CONFIG_VAR(PX4FMU_SMPLRT_DIV) + +#ifndef PX4FMU_GYRO_RANGE +#define PX4FMU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 +#endif +PRINT_CONFIG_VAR(PX4FMU_GYRO_RANGE) + +#ifndef PX4FMU_ACCEL_RANGE +#define PX4FMU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G +#endif +PRINT_CONFIG_VAR(PX4FMU_ACCEL_RANGE) + +struct ImuPx4fmu imu_px4fmu; + +void imu_impl_init(void) +{ + imu_px4fmu.accel_valid = FALSE; + imu_px4fmu.gyro_valid = FALSE; + imu_px4fmu.mag_valid = FALSE; + + /* MPU is on spi1 and CS is SLAVE2 */ + mpu60x0_spi_init(&imu_px4fmu.mpu, &spi1, SPI_SLAVE2); + // change the default configuration + imu_px4fmu.mpu.config.smplrt_div = PX4FMU_SMPLRT_DIV; + imu_px4fmu.mpu.config.dlpf_cfg = PX4FMU_LOWPASS_FILTER; + imu_px4fmu.mpu.config.gyro_range = PX4FMU_GYRO_RANGE; + imu_px4fmu.mpu.config.accel_range = PX4FMU_ACCEL_RANGE; + + /* initialize mag on i2c2 and set default options */ + hmc58xx_init(&imu_px4fmu.hmc, &i2c2, HMC58XX_ADDR); +} + + +void imu_periodic(void) +{ + mpu60x0_spi_periodic(&imu_px4fmu.mpu); + + // Read HMC58XX at 50Hz (main loop for rotorcraft: 512Hz) + RunOnceEvery(10, hmc58xx_periodic(&imu_px4fmu.hmc)); +} + +void imu_px4fmu_event(void) +{ + mpu60x0_spi_event(&imu_px4fmu.mpu); + if (imu_px4fmu.mpu.data_available) { + RATES_ASSIGN(imu.gyro_unscaled, + imu_px4fmu.mpu.data_rates.rates.q, + imu_px4fmu.mpu.data_rates.rates.p, + -imu_px4fmu.mpu.data_rates.rates.r); + VECT3_ASSIGN(imu.accel_unscaled, + imu_px4fmu.mpu.data_accel.vect.y, + imu_px4fmu.mpu.data_accel.vect.x, + -imu_px4fmu.mpu.data_accel.vect.z); + imu_px4fmu.mpu.data_available = FALSE; + imu_px4fmu.gyro_valid = TRUE; + imu_px4fmu.accel_valid = TRUE; + } + + /* HMC58XX event task */ + hmc58xx_event(&imu_px4fmu.hmc); + if (imu_px4fmu.hmc.data_available) { + imu.mag_unscaled.x = imu_px4fmu.hmc.data.vect.y; + imu.mag_unscaled.y = imu_px4fmu.hmc.data.vect.x; + imu.mag_unscaled.z = -imu_px4fmu.hmc.data.vect.z; + imu_px4fmu.hmc.data_available = FALSE; + imu_px4fmu.mag_valid = TRUE; + } +} + diff --git a/sw/airborne/subsystems/imu/imu_px4fmu.h b/sw/airborne/subsystems/imu/imu_px4fmu.h new file mode 100644 index 0000000000..1620b9892c --- /dev/null +++ b/sw/airborne/subsystems/imu/imu_px4fmu.h @@ -0,0 +1,83 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file subsystems/imu/imu_px4fmu.h + * Driver for the PX4FMU SPI1 for the MPU6000 and I2C2 for the HMC5883. + */ + +#ifndef IMU_PX4FMU_SPI_H +#define IMU_PX4FMU_SPI_H + +#include "std.h" +#include "generated/airframe.h" +#include "subsystems/imu.h" + +#include "subsystems/imu/imu_mpu60x0_defaults.h" +#include "peripherals/mpu60x0_spi.h" +#include "peripherals/hmc58xx.h" + +#if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN +#define IMU_GYRO_P_SIGN 1 +#define IMU_GYRO_Q_SIGN 1 +#define IMU_GYRO_R_SIGN 1 +#endif +#if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN +#define IMU_ACCEL_X_SIGN 1 +#define IMU_ACCEL_Y_SIGN 1 +#define IMU_ACCEL_Z_SIGN 1 +#endif +#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN +#define IMU_MAG_X_SIGN 1 +#define IMU_MAG_Y_SIGN 1 +#define IMU_MAG_Z_SIGN 1 +#endif + +struct ImuPx4fmu { + volatile bool_t gyro_valid; + volatile bool_t accel_valid; + volatile bool_t mag_valid; + struct Mpu60x0_Spi mpu; + struct Hmc58xx hmc; +}; + +extern struct ImuPx4fmu imu_px4fmu; + +extern void imu_px4fmu_event(void); + + +static inline void ImuEvent(void (* _gyro_handler)(void), void (* _accel_handler)(void), void (* _mag_handler)(void)) { + imu_px4fmu_event(); + if (imu_px4fmu.gyro_valid) { + imu_px4fmu.gyro_valid = FALSE; + _gyro_handler(); + } + if (imu_px4fmu.accel_valid) { + imu_px4fmu.accel_valid = FALSE; + _accel_handler(); + } + if (imu_px4fmu.mag_valid) { + imu_px4fmu.mag_valid = FALSE; + _mag_handler(); + } +} + +#endif /* IMU_PX4FMU_H */ From 9489857f01be337b791ef84ee88cb74e139740b3 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 1 Sep 2013 17:00:43 +0200 Subject: [PATCH 210/309] [rotorcraft] add FAILSAFE_ON_BAT_CRITICAL set FAILSAFE_ON_BAT_CRITICAL to TRUE if you want to go into FAILSAFE mode (neutral attitude, slowly descend) if battery status is critical (vsupply voltage below CRITIC_BAT_LEVEL for a while) --- sw/airborne/firmwares/rotorcraft/main.c | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index beb36fcb31..8dfd160743 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -222,6 +222,14 @@ STATIC_INLINE void failsafe_check( void ) { autopilot_set_mode(AP_MODE_FAILSAFE); } +#if FAILSAFE_ON_BAT_CRITICAL + if (autopilot_mode != AP_MODE_KILL && + electrical.bat_critical) + { + autopilot_set_mode(AP_MODE_FAILSAFE); + } +#endif + #if USE_GPS if (autopilot_mode == AP_MODE_NAV && autopilot_motors_on && From 21df20cae8fb9a2298f102c68190d7769485a705 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 1 Sep 2013 22:59:13 +0200 Subject: [PATCH 211/309] [ArDrone] Default LEDS --- conf/boards/ardrone2_raw.makefile | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/conf/boards/ardrone2_raw.makefile b/conf/boards/ardrone2_raw.makefile index 5ab2d5f7cc..9e96052594 100644 --- a/conf/boards/ardrone2_raw.makefile +++ b/conf/boards/ardrone2_raw.makefile @@ -35,8 +35,8 @@ $(TARGET).CFLAGS +=-DARDRONE2_RAW # ----------------------------------------------------------------------- # default LED configuration -RADIO_CONTROL_LED ?= none +RADIO_CONTROL_LED ?= 4 BARO_LED ?= none -AHRS_ALIGNER_LED ?= none -GPS_LED ?= none -SYS_TIME_LED ?= none +AHRS_ALIGNER_LED ?= 2 +GPS_LED ?= 3 +SYS_TIME_LED ?= 1 From 6d33e8553dc9c621460e73cf1a885978b485dcbb Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 1 Sep 2013 23:06:07 +0200 Subject: [PATCH 212/309] [ArDrone] Extra Safety --- sw/airborne/boards/ardrone/gpio_ardrone.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index 9e3786722b..6d2202557b 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -22,6 +22,8 @@ * ardrone GPIO driver */ +#ifdef ARDRONE2_RAW + #include /* File control definitions */ #include /* Error number definitions */ #include @@ -125,3 +127,5 @@ uint16_t gpio_get(uint32_t port, uint16_t pin) ioctl(gpiofp, GPIO_READ, &data); return data.value; } + +#endif From d44b40255f4ddd06f7f9d257d02aab056965b2a5 Mon Sep 17 00:00:00 2001 From: softsr Date: Sun, 1 Sep 2013 22:45:47 -0700 Subject: [PATCH 213/309] Krooz imu fix --- sw/airborne/boards/krooz/imu_krooz.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index e120cbbea3..8d369be25a 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -180,7 +180,7 @@ void imu_krooz_event( void ) // If the HMC5883 I2C transaction has succeeded: convert the data hmc58xx_event(&imu_krooz.hmc); if (imu_krooz.hmc.data_available) { - VECT3_ASSIGN(imu.mag_unscaled, imu_krooz.hmc.data.vect.z, -imu_krooz.hmc.data.vect.x, imu_krooz.hmc.data.vect.y); + VECT3_ASSIGN(imu.mag_unscaled, imu_krooz.hmc.data.vect.y, -imu_krooz.hmc.data.vect.x, imu_krooz.hmc.data.vect.z); UpdateMedianFilterVect3Int(median_mag, imu.mag_unscaled); imu_krooz.hmc.data_available = FALSE; imu_krooz.mag_valid = TRUE; From 2782e11ad9b5f2c50416f45f4d04d795fbe90943 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 1 Sep 2013 23:12:17 +0200 Subject: [PATCH 214/309] [airframes] CDW --- conf/airframes/CDW/asctec_cdw.xml | 11 +++++++---- conf/airframes/CDW/conf.xml | 22 ++++++++++++++++++++++ conf/airframes/CDW/tricopter_cdw.xml | 4 +++- 3 files changed, 32 insertions(+), 5 deletions(-) create mode 100644 conf/airframes/CDW/conf.xml diff --git a/conf/airframes/CDW/asctec_cdw.xml b/conf/airframes/CDW/asctec_cdw.xml index 300eb6eb11..e28e7f538b 100644 --- a/conf/airframes/CDW/asctec_cdw.xml +++ b/conf/airframes/CDW/asctec_cdw.xml @@ -1,12 +1,14 @@ - + - + + + @@ -61,6 +63,7 @@ + @@ -194,7 +197,7 @@ - +
@@ -221,4 +224,4 @@
-
+
diff --git a/conf/airframes/CDW/conf.xml b/conf/airframes/CDW/conf.xml new file mode 100644 index 0000000000..c8ba362e02 --- /dev/null +++ b/conf/airframes/CDW/conf.xml @@ -0,0 +1,22 @@ + + + + diff --git a/conf/airframes/CDW/tricopter_cdw.xml b/conf/airframes/CDW/tricopter_cdw.xml index 00d9368d88..48e2192956 100644 --- a/conf/airframes/CDW/tricopter_cdw.xml +++ b/conf/airframes/CDW/tricopter_cdw.xml @@ -2,6 +2,8 @@ - + From 55e3d9d79119f81ed0b11a59487280becf13cf40 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 1 Sep 2013 17:55:14 +0100 Subject: [PATCH 215/309] Don't use failed reads. Add debugging. --- conf/airframes/ardrone2_sdk.xml | 1 + sw/airborne/boards/ardrone/at_com.c | 12 ++++-- sw/airborne/boards/ardrone/at_com.h | 2 +- sw/airborne/subsystems/ahrs/ahrs_ardrone2.c | 46 +++++++++++++++++++-- sw/airborne/subsystems/gps/gps_ardrone2.c | 8 ++++ 5 files changed, 61 insertions(+), 8 deletions(-) diff --git a/conf/airframes/ardrone2_sdk.xml b/conf/airframes/ardrone2_sdk.xml index 154b0126fb..73c21af476 100644 --- a/conf/airframes/ardrone2_sdk.xml +++ b/conf/airframes/ardrone2_sdk.xml @@ -6,6 +6,7 @@ + diff --git a/sw/airborne/boards/ardrone/at_com.c b/sw/airborne/boards/ardrone/at_com.c index b2c11e4d0b..eba448ee13 100644 --- a/sw/airborne/boards/ardrone/at_com.c +++ b/sw/airborne/boards/ardrone/at_com.c @@ -133,10 +133,14 @@ void init_at_config(void) { } //Recieve a navdata packet -void at_com_recieve_navdata(unsigned char* buffer) { - int l; - recvfrom(navdata_socket, buffer, ARDRONE_NAVDATA_BUFFER_SIZE, 0x0, - (struct sockaddr *) &from, (socklen_t *) &l); +int at_com_recieve_navdata(unsigned char* buffer) { + int l = sizeof(from); + int n; + // FIXME(ben): not clear why recvfrom() and not recv() is used. + n = recvfrom(navdata_socket, buffer, ARDRONE_NAVDATA_BUFFER_SIZE, 0x0, + (struct sockaddr *) &from, (socklen_t *) &l); + + return n; } //Send an AT command diff --git a/sw/airborne/boards/ardrone/at_com.h b/sw/airborne/boards/ardrone/at_com.h index f2b04185b2..79084315ef 100644 --- a/sw/airborne/boards/ardrone/at_com.h +++ b/sw/airborne/boards/ardrone/at_com.h @@ -202,7 +202,7 @@ typedef struct _navdata_gps_t { //External functions extern void init_at_com(void); -extern void at_com_recieve_navdata(unsigned char* buffer); +extern int at_com_recieve_navdata(unsigned char* buffer); extern void at_com_send_config(char* key, char* value); extern void at_com_send_ftrim(void); extern void at_com_send_ref(int bits); diff --git a/sw/airborne/subsystems/ahrs/ahrs_ardrone2.c b/sw/airborne/subsystems/ahrs/ahrs_ardrone2.c index afed7a6202..1e5317e937 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_ardrone2.c +++ b/sw/airborne/subsystems/ahrs/ahrs_ardrone2.c @@ -27,6 +27,11 @@ * and also sets battery level. */ +#ifdef ARDRONE2_DEBUG +# include +# include +#endif + #include "ahrs_ardrone2.h" #include "state.h" #include "math/pprz_algebra_float.h" @@ -55,15 +60,42 @@ void ahrs_align(void) { } +#ifdef ARDRONE2_DEBUG +static void dump(const void *_b, size_t s) { + const unsigned char *b = _b; + size_t n; + + for(n = 0; n < s; ++n) { + printf("%02x ", b[n]); + if (n%16 == 15) + printf("\n"); + } + if (n%16 != 0) + printf("\n"); +} +#endif + void ahrs_propagate(void) { + int l; + //Recieve the main packet - at_com_recieve_navdata(buffer); + l = at_com_recieve_navdata(buffer); navdata_t* main_packet = (navdata_t*) &buffer; +#ifdef ARDRONE2_DEBUG + if (l < 0) + printf("errno = %d\n", errno); +#endif + //When this isn't a valid packet return - if(main_packet->header != NAVDATA_HEADER) + if(l < 0 || main_packet->header != NAVDATA_HEADER) return; +#ifdef ARDRONE2_DEBUG + printf("Read %d\n", l); + dump(buffer, l); +#endif + //Set the state ahrs_impl.state = main_packet->ardrone_state; @@ -78,6 +110,9 @@ void ahrs_propagate(void) { //Read the navdata until packet is fully readed while(!full_read && navdata_option->size > 0) { +#ifdef ARDRONE2_DEBUG + printf ("tag = %d\n", navdata_option->tag); +#endif //Check the tag for the right option switch(navdata_option->tag) { case 0: //NAVDATA_DEMO @@ -112,6 +147,9 @@ void ahrs_propagate(void) { break; #ifdef USE_GPS_ARDRONE2 case 27: //NAVDATA_GPS +# ifdef ARDRONE2_DEBUG + dump(navdata_option, navdata_option->size); +# endif navdata_gps = (navdata_gps_t*) navdata_option; // Send the data to the gps parser @@ -123,7 +161,9 @@ void ahrs_propagate(void) { full_read = TRUE; break; default: - //printf("NAVDATA UNKNOWN TAG: %d %d\n", navdata_option->tag, navdata_option->size); +#ifdef ARDRONE2_DEBUG + printf("NAVDATA UNKNOWN TAG: %d %d\n", navdata_option->tag, navdata_option->size); +#endif break; } navdata_option = (navdata_option_t*) ((uint32_t)navdata_option + navdata_option->size); diff --git a/sw/airborne/subsystems/gps/gps_ardrone2.c b/sw/airborne/subsystems/gps/gps_ardrone2.c index 0326f0dd64..2feba4c765 100644 --- a/sw/airborne/subsystems/gps/gps_ardrone2.c +++ b/sw/airborne/subsystems/gps/gps_ardrone2.c @@ -26,6 +26,10 @@ * ARdrone 2 gps trough navdata for the SDK version and only works in combination with the ahrs ardrone2. */ +#ifdef ARDRONE2_DEBUG +# include +#endif + #include "subsystems/gps.h" #include "math/pprz_geodetic_double.h" @@ -37,6 +41,10 @@ void gps_impl_init( void ) { void gps_ardrone2_parse(navdata_gps_t *navdata_gps) { int i; + +#ifdef ARDRONE2_DEBUG + printf("state = %d\n", navdata_gps->gps_state); +#endif // Set the lla double struct from the navdata struct LlaCoor_d gps_lla_d; gps_lla_d.lat = RadOfDeg(navdata_gps->lat); From 29da4ede963611766ef40d7d7b2779b8a16eb1fa Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 2 Sep 2013 13:45:40 +0200 Subject: [PATCH 216/309] [rotorcraft] also call stabilization_attitude_enter if previous mode was GUIDANCE_H_MODE_KILL --- .../firmwares/rotorcraft/guidance/guidance_h.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index 1b5cdbf0b2..dc247acc1f 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -140,8 +140,9 @@ void guidance_h_mode_changed(uint8_t new_mode) { case GUIDANCE_H_MODE_FORWARD: case GUIDANCE_H_MODE_ATTITUDE: /* reset attitude stabilization if previous mode was not using it */ - if (guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT || - guidance_h_mode == GUIDANCE_H_MODE_RATE) { + if (guidance_h_mode == GUIDANCE_H_MODE_KILL || + guidance_h_mode == GUIDANCE_H_MODE_RATE || + guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) { stabilization_attitude_enter(); } break; @@ -149,8 +150,9 @@ void guidance_h_mode_changed(uint8_t new_mode) { case GUIDANCE_H_MODE_HOVER: guidance_h_hover_enter(); /* reset attitude stabilization if previous mode was not using it */ - if (guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT || - guidance_h_mode == GUIDANCE_H_MODE_RATE) { + if (guidance_h_mode == GUIDANCE_H_MODE_KILL || + guidance_h_mode == GUIDANCE_H_MODE_RATE || + guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) { stabilization_attitude_enter(); } break; @@ -158,8 +160,9 @@ void guidance_h_mode_changed(uint8_t new_mode) { case GUIDANCE_H_MODE_NAV: guidance_h_nav_enter(); /* reset attitude stabilization if previous mode was not using it */ - if (guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT || - guidance_h_mode == GUIDANCE_H_MODE_RATE) { + if (guidance_h_mode == GUIDANCE_H_MODE_KILL || + guidance_h_mode == GUIDANCE_H_MODE_RATE || + guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) { stabilization_attitude_enter(); } break; From ac31df52528b2bf9bb61d7a42625e00ffc74453d Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 2 Sep 2013 13:45:15 +0200 Subject: [PATCH 217/309] [ArDrone] SYS_LED --- conf/boards/ardrone2_raw.makefile | 10 +++++----- sw/airborne/arch/omap/mcu_periph/sys_time_arch.c | 9 +++++++++ 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/conf/boards/ardrone2_raw.makefile b/conf/boards/ardrone2_raw.makefile index 9e96052594..8fb9edacf0 100644 --- a/conf/boards/ardrone2_raw.makefile +++ b/conf/boards/ardrone2_raw.makefile @@ -35,8 +35,8 @@ $(TARGET).CFLAGS +=-DARDRONE2_RAW # ----------------------------------------------------------------------- # default LED configuration -RADIO_CONTROL_LED ?= 4 -BARO_LED ?= none -AHRS_ALIGNER_LED ?= 2 -GPS_LED ?= 3 -SYS_TIME_LED ?= 1 +RADIO_CONTROL_LED ?= 6 +BARO_LED ?= none +AHRS_ALIGNER_LED ?= 5 +GPS_LED ?= 3 +SYS_TIME_LED ?= 0 diff --git a/sw/airborne/arch/omap/mcu_periph/sys_time_arch.c b/sw/airborne/arch/omap/mcu_periph/sys_time_arch.c index 2d4c78cd04..277e1a7893 100644 --- a/sw/airborne/arch/omap/mcu_periph/sys_time_arch.c +++ b/sw/airborne/arch/omap/mcu_periph/sys_time_arch.c @@ -29,6 +29,11 @@ #include #include +#ifdef SYS_TIME_LED +#include "led.h" +#endif + + void sys_time_arch_init( void ) { sys_time.cpu_ticks_per_sec = 1e6; @@ -58,6 +63,10 @@ void sys_tick_handler( int signum ) { if (sys_time.nb_sec_rem >= sys_time.cpu_ticks_per_sec) { sys_time.nb_sec_rem -= sys_time.cpu_ticks_per_sec; sys_time.nb_sec++; +#ifdef SYS_TIME_LED + LED_TOGGLE(SYS_TIME_LED); +#endif + } for (unsigned int i=0; i Date: Mon, 2 Sep 2013 13:45:46 +0200 Subject: [PATCH 218/309] [ArDrone] Able to takeoff without joystick --- conf/airframes/ardrone2_raw.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index d6b09dea15..579ff9a31f 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -10,6 +10,7 @@ + From 2df238b28ce2421ebaeb2581f0e76cdc604b5331 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 2 Sep 2013 13:47:22 +0200 Subject: [PATCH 219/309] [ArDrone] Radio Control LED --- .../subsystems/shared/radio_control_datalink.makefile | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/conf/firmwares/subsystems/shared/radio_control_datalink.makefile b/conf/firmwares/subsystems/shared/radio_control_datalink.makefile index bb342a5c3e..6aed61a1a8 100644 --- a/conf/firmwares/subsystems/shared/radio_control_datalink.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_datalink.makefile @@ -11,9 +11,13 @@ endif ifeq ($(NORADIO), False) -ifdef (RADIO_CONTROL_DATALINK_LED) - ap.CFLAGS += -D(RADIO_CONTROL_DATALINK_LED=$((RADIO_CONTROL_DATALINK_LED) -endif + ifdef (RADIO_CONTROL_DATALINK_LED) + ap.CFLAGS += -D(RADIO_CONTROL_DATALINK_LED=$((RADIO_CONTROL_DATALINK_LED) + endif + ifneq ($(RADIO_CONTROL_LED),none) + ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) + fbw.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) + endif $(TARGET).CFLAGS += -DRADIO_CONTROL $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_H=\"radio_control/rc_datalink.h\" $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_DATALINK From 726136821488e16a6c7df5d0378cfa2a8d0c2156 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 2 Sep 2013 13:52:22 +0200 Subject: [PATCH 220/309] [ArDrone] FlipFlop reset timing slowed down --- .../boards/ardrone/actuators_ardrone2_raw.c | 76 ++++++++++++++++--- sw/airborne/boards/ardrone/gpio_ardrone.c | 4 +- 2 files changed, 68 insertions(+), 12 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index 0277cb0212..7c8cd2e8c4 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -32,6 +32,7 @@ #include "actuators_ardrone2_raw.h" #include "mcu_periph/gpio.h" #include "led_hw.h" +#include "mcu_periph/sys_time.h" #include /* Standard input/output definitions */ #include /* String function definitions */ @@ -65,6 +66,17 @@ int actuator_ardrone2_raw_fd; /**< File descriptor for the port */ uint32_t led_hw_values; +static inline void actuators_ardrone_reset_flipflop(void) +{ + gpio_setup_output(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + int32_t stop = sys_time.nb_sec + 2; + while (sys_time.nb_sec < stop); + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); +} + + + void actuators_ardrone_init(void) { led_hw_values = 0; @@ -97,10 +109,14 @@ void actuators_ardrone_init(void) //reset IRQ flipflop - on error 106 read 1, this code resets 106 to 0 gpio_setup_input(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_INPUT); - gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); - gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + actuators_ardrone_reset_flipflop(); - //all select lines inactive + + //all select lines active + gpio_setup_output(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR1); + gpio_setup_output(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR2); + gpio_setup_output(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR3); + gpio_setup_output(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR4); gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR1); gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR2); gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_MOTOR3); @@ -150,29 +166,60 @@ int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) { void actuators_ardrone_motor_status(void); void actuators_ardrone_motor_status(void) { - // If a motor IRQ lines is set + static bool_t last_motor_on = FALSE; + + // Reset Flipflop sequence + static bool_t reset_flipflop_counter = 0; + if (reset_flipflop_counter > 0) + { + reset_flipflop_counter--; + + if (reset_flipflop_counter == 10) + { + // Reset flipflop + gpio_setup_output(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + gpio_clear(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + } + else if (reset_flipflop_counter == 1) + { + // Listen to IRQ again + gpio_set(ARDRONE_GPIO_PORT,ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); + } + return; + } + + // If a motor IRQ line is set if (gpio_get(ARDRONE_GPIO_PORT, ARDRONE_GPIO_PIN_IRQ_INPUT) == 1) { if (autopilot_motors_on) { - // Tell paparazzi that one motor has stalled - autopilot_set_motors_on(FALSE); + if (last_motor_on) + { + // Tell paparazzi that one motor has stalled + autopilot_set_motors_on(FALSE); + } + else + { + // Toggle Flipflop reset so motors can be re-enabled + reset_flipflop_counter = 20; + } - // Toggle Flipflop reset so motors can be re-enabled - gpio_clear(ARDRONE_GPIO_PORT, ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); - gpio_set(ARDRONE_GPIO_PORT, ARDRONE_GPIO_PIN_IRQ_FLIPFLOP); } } + last_motor_on = autopilot_motors_on; + } +#define BIT_NUMBER(VAL,BIT) (((VAL)>>BIT)&0x03) + void actuators_ardrone_led_run(void); void actuators_ardrone_led_run(void) { - static uint32_t previous_led_hw_values; + static uint32_t previous_led_hw_values = 0x00; if (previous_led_hw_values != led_hw_values) { previous_led_hw_values = led_hw_values; - actuators_ardrone_set_leds(led_hw_values & 0x01, led_hw_values & 0x02, led_hw_values & 0x04, led_hw_values & 0x08); + actuators_ardrone_set_leds(BIT_NUMBER(led_hw_values,0), BIT_NUMBER(led_hw_values,2), BIT_NUMBER(led_hw_values,4), BIT_NUMBER(led_hw_values,6) ); } } @@ -213,6 +260,13 @@ void actuators_ardrone_set_leds(uint8_t led0, uint8_t led1, uint8_t led2, uint8_ { uint8_t cmd[2]; + led0 &= 0x03; + led1 &= 0x03; + led2 &= 0x03; + led3 &= 0x03; + + printf("LEDS: %d %d %d %d \n", led0, led1, led2, led3); + cmd[0]=0x60 | ((led0&1)<<4) | ((led1&1)<<3) | ((led2&1)<<2) | ((led3&1) <<1); cmd[1]=((led0&2)<<3) | ((led1&2)<<2) | ((led2&2)<<1) | ((led3&2)<<0); diff --git a/sw/airborne/boards/ardrone/gpio_ardrone.c b/sw/airborne/boards/ardrone/gpio_ardrone.c index 6d2202557b..363ca87686 100644 --- a/sw/airborne/boards/ardrone/gpio_ardrone.c +++ b/sw/airborne/boards/ardrone/gpio_ardrone.c @@ -100,6 +100,7 @@ void gpio_setup_input(uint32_t port, uint16_t pin) void gpio_setup_output(uint32_t port, uint16_t pin) { + /* if (port != 0x32524) return; // protect ardrone board from unauthorized use struct gpio_direction dir; // Open the device if not open @@ -108,8 +109,9 @@ void gpio_setup_output(uint32_t port, uint16_t pin) // Read the GPIO value dir.pin = pin; - dir.mode = GPIO_OUTPUT_HIGH; + dir.mode = GPIO_OUTPUT_LOW; ioctl(gpiofp, GPIO_DIRECTION, &dir); + */ } From 51aeb9bd487cdbc312d36eecc4e0e271c41ccf02 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 2 Sep 2013 16:18:47 +0200 Subject: [PATCH 221/309] [guidance_h_ref] split up and fix ref max accel/speed calculation --- .../rotorcraft/guidance/guidance_h_ref.c | 68 +++++++++++++++---- 1 file changed, 53 insertions(+), 15 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c index c6a39793c0..34b23d212c 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h_ref.c @@ -90,9 +90,12 @@ static int32_t route_ref; static int32_t s_route_ref; static int32_t c_route_ref; +static void gh_compute_route_ref(struct Int32Vect2* ref_vector); +static void gh_compute_ref_max(struct Int32Vect2* ref_vector); +static void gh_compute_ref_max_accel(struct Int32Vect2* ref_vector); +static void gh_compute_ref_max_speed(struct Int32Vect2* ref_vector); static void gh_saturate_ref_accel(void); static void gh_saturate_ref_speed(void); -static void gh_compute_max_ref(struct Int32Vect2* ref_vector); void gh_set_ref(struct Int32Vect2 pos, struct Int32Vect2 speed, struct Int32Vect2 accel) { struct Int64Vect2 new_pos; @@ -127,7 +130,7 @@ void gh_update_ref_from_pos_sp(struct Int32Vect2 pos_sp) { VECT2_SUM(gh_accel_ref, speed, pos); /* Compute max ref accel/speed along route before saturation */ - gh_compute_max_ref(&pos_err); + gh_compute_ref_max(&pos_err); gh_saturate_ref_accel(); gh_saturate_ref_speed(); @@ -150,28 +153,33 @@ void gh_update_ref_from_speed_sp(struct Int32Vect2 speed_sp) { INT32_VECT2_RSHIFT(gh_accel_ref, gh_accel_ref, GH_REF_INV_TAU_FRAC); /* Compute max ref accel/speed along route before saturation */ - gh_compute_max_ref(&speed_sp); + gh_compute_ref_max_speed(&speed_sp); + gh_compute_ref_max_accel(&speed_err); gh_saturate_ref_accel(); gh_saturate_ref_speed(); } -static void gh_compute_max_ref(struct Int32Vect2* ref_vector) { +static void gh_compute_route_ref(struct Int32Vect2* ref_vector) { + float f_route_ref = atan2f(-ref_vector->y, -ref_vector->x); + route_ref = ANGLE_BFP_OF_REAL(f_route_ref); + /* Compute North and East route components */ + PPRZ_ITRIG_SIN(s_route_ref, route_ref); + PPRZ_ITRIG_COS(c_route_ref, route_ref); + c_route_ref = abs(c_route_ref); + s_route_ref = abs(s_route_ref); +} + +static void gh_compute_ref_max(struct Int32Vect2* ref_vector) { /* Compute route reference before saturation */ if (ref_vector->x == 0 && ref_vector->y == 0) { - gh_max_accel_ref.x = gh_max_accel; - gh_max_accel_ref.y = gh_max_accel; - gh_max_speed_ref.x = gh_max_speed; - gh_max_speed_ref.y = gh_max_speed; + gh_max_accel_ref.x = 0; + gh_max_accel_ref.y = 0; + gh_max_speed_ref.x = 0; + gh_max_speed_ref.y = 0; } else { - float f_route_ref = atan2f(-ref_vector->y, -ref_vector->x); - route_ref = ANGLE_BFP_OF_REAL(f_route_ref); - /* Compute North and East route components */ - PPRZ_ITRIG_SIN(s_route_ref, route_ref); - PPRZ_ITRIG_COS(c_route_ref, route_ref); - c_route_ref = abs(c_route_ref); - s_route_ref = abs(s_route_ref); + gh_compute_route_ref(ref_vector); /* Compute maximum acceleration*/ gh_max_accel_ref.x = INT_MULT_RSHIFT(gh_max_accel, c_route_ref, INT32_TRIG_FRAC); gh_max_accel_ref.y = INT_MULT_RSHIFT(gh_max_accel, s_route_ref, INT32_TRIG_FRAC); @@ -183,6 +191,36 @@ static void gh_compute_max_ref(struct Int32Vect2* ref_vector) { } } +static void gh_compute_ref_max_accel(struct Int32Vect2* ref_vector) { + /* Compute route reference before saturation */ + if (ref_vector->x == 0 && ref_vector->y == 0) { + gh_max_accel_ref.x = 0; + gh_max_accel_ref.y = 0; + } + else { + gh_compute_route_ref(ref_vector); + /* Compute maximum acceleration*/ + gh_max_accel_ref.x = INT_MULT_RSHIFT(gh_max_accel, c_route_ref, INT32_TRIG_FRAC); + gh_max_accel_ref.y = INT_MULT_RSHIFT(gh_max_accel, s_route_ref, INT32_TRIG_FRAC); + } +} + +static void gh_compute_ref_max_speed(struct Int32Vect2* ref_vector) { + /* Compute route reference before saturation */ + if (ref_vector->x == 0 && ref_vector->y == 0) { + gh_max_speed_ref.x = 0; + gh_max_speed_ref.y = 0; + } + else { + gh_compute_route_ref(ref_vector); + /* Compute maximum speed*/ + gh_max_speed_ref.x = INT_MULT_RSHIFT(gh_max_speed, c_route_ref, INT32_TRIG_FRAC); + gh_max_speed_ref.y = INT_MULT_RSHIFT(gh_max_speed, s_route_ref, INT32_TRIG_FRAC); + /* restore gh_speed_ref range (Q14.17) */ + INT32_VECT2_LSHIFT(gh_max_speed_ref, gh_max_speed_ref, (GH_SPEED_REF_FRAC - GH_MAX_SPEED_REF_FRAC)); + } +} + /** saturate reference accelerations */ static void gh_saturate_ref_accel(void) { /* Saturate accelerations */ From ec3218cdb545e384c9b9984a2a0b36eded063558 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 2 Sep 2013 18:13:57 +0200 Subject: [PATCH 222/309] [stabilization] attitude quat: fix psi angle --- .../stabilization_attitude_quat_float.c | 15 ++++++++++++++- .../stabilization_attitude_quat_int.c | 16 +++++++++++++++- 2 files changed, 29 insertions(+), 2 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c index d6c83774b6..a5764fa859 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c @@ -162,7 +162,8 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { * onto the horizontal plane with the psi setpoint. * * angle between two vectors a and b: - * angle = atan2(norm(cross(a,b)), dot(a,b)) + * angle = atan2(norm(cross(a,b)), dot(a,b)) * sign(dot(cross(a,b), n)) + * where n is the thrust vector (i.e. both a and b lie in that plane) */ const struct FloatVect3 xaxis = {1.0, 0.0, 0.0}; const struct FloatVect3 zaxis = {0.0, 0.0, 1.0}; @@ -174,14 +175,17 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { psi_vect.x = cosf(stab_att_sp_euler.psi); psi_vect.y = sinf(stab_att_sp_euler.psi); psi_vect.z = 0.0; + // normal is the direction of the thrust vector struct FloatVect3 normal; FLOAT_QUAT_VMULT(normal, q_rp, zaxis); + // projection of desired heading onto body x-y plane // b = v - dot(v,n)*n float dot = FLOAT_VECT3_DOT_PRODUCT(psi_vect, normal); struct FloatVect3 dotn; FLOAT_VECT3_SMUL(dotn, normal, dot); + // b = v - dot(v,n)*n struct FloatVect3 b; FLOAT_VECT3_DIFF(b, psi_vect, dotn); dot = FLOAT_VECT3_DOT_PRODUCT(a, b); @@ -189,14 +193,23 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { VECT3_CROSS_PRODUCT(cross, a, b); // norm of the cross product float nc = FLOAT_VECT3_NORM(cross); + // angle = atan2(norm(cross(a,b)), dot(a,b)) float yaw2 = atan2(nc, dot) / 2.0; + // negative angle if needed + // sign(dot(cross(a,b), n) + float dot_cross_ab = FLOAT_VECT3_DOT_PRODUCT(cross, normal); + if (dot_cross_ab < 0) { + yaw2 = -yaw2; + } + /* quaternion with yaw command */ struct FloatQuat q_yaw; QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); /* final setpoint: apply roll/pitch, then yaw around resulting body z-axis */ FLOAT_QUAT_COMP(stab_att_sp_quat, q_yaw, q_rp); + FLOAT_QUAT_NORMALIZE(stab_att_sp_quat); FLOAT_QUAT_WRAP_SHORTEST(stab_att_sp_quat); } diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c index b0b5b3ae6e..f709f9f5c0 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c @@ -117,7 +117,8 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { * onto the horizontal plane with the psi setpoint. * * angle between two vectors a and b: - * angle = atan2(norm(cross(a,b)), dot(a,b)) + * angle = atan2(norm(cross(a,b)), dot(a,b)) * sign(dot(cross(a,b), n)) + * where n is the thrust vector (i.e. both a and b lie in that plane) */ const struct FloatVect3 xaxis = {1.0, 0.0, 0.0}; const struct FloatVect3 zaxis = {0.0, 0.0, 1.0}; @@ -129,23 +130,35 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { psi_vect.x = cosf(psi_sp); psi_vect.y = sinf(psi_sp); psi_vect.z = 0.0; + // normal is the direction of the thrust vector struct FloatVect3 normal; FLOAT_QUAT_VMULT(normal, q_rp, zaxis); + // projection of desired heading onto body x-y plane // b = v - dot(v,n)*n float dot = FLOAT_VECT3_DOT_PRODUCT(psi_vect, normal); struct FloatVect3 dotn; FLOAT_VECT3_SMUL(dotn, normal, dot); + // b = v - dot(v,n)*n struct FloatVect3 b; FLOAT_VECT3_DIFF(b, psi_vect, dotn); + dot = FLOAT_VECT3_DOT_PRODUCT(a, b); struct FloatVect3 cross; VECT3_CROSS_PRODUCT(cross, a, b); // norm of the cross product float nc = FLOAT_VECT3_NORM(cross); + // angle = atan2(norm(cross(a,b)), dot(a,b)) float yaw2 = atan2(nc, dot) / 2.0; + // negative angle if needed + // sign(dot(cross(a,b), n) + float dot_cross_ab = FLOAT_VECT3_DOT_PRODUCT(cross, normal); + if (dot_cross_ab < 0) { + yaw2 = -yaw2; + } + /* quaternion with yaw command */ struct FloatQuat q_yaw; QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); @@ -153,6 +166,7 @@ void stabilization_attitude_set_cmd_i(struct Int32Eulers *sp_cmd) { /* final setpoint: apply roll/pitch, then yaw around resulting body z-axis */ struct FloatQuat q_sp; FLOAT_QUAT_COMP(q_sp, q_yaw, q_rp); + FLOAT_QUAT_NORMALIZE(q_sp); FLOAT_QUAT_WRAP_SHORTEST(q_sp); /* convert to fixed point */ From 3d3adb7281af3e1d7ddf0801b703a7b26ea3a476 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 11:02:59 +0200 Subject: [PATCH 223/309] [guidance_v] pass only vertical thrust component to gv_adapt_run Improve issue #527. Get an estimate of the ctually applied thrust in the direction of the gravity vector instead of total thrust to pass to the adaptive nominal thrust estimation. Still should be improved by using the actual thrust after saturation/mixing... --- .../rotorcraft/guidance/guidance_v.c | 26 ++++++++++++------- .../rotorcraft/guidance/guidance_v.h | 2 ++ .../rotorcraft/guidance/guidance_v_adapt.c | 2 +- 3 files changed, 19 insertions(+), 11 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index 81c72e79bf..d535c76ae1 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -175,7 +175,8 @@ void guidance_v_run(bool_t in_flight) { // FIXME... SATURATIONS NOT TAKEN INTO ACCOUNT // AKA SUPERVISION and co if (in_flight) { - gv_adapt_run(stateGetAccelNed_i()->z, stabilization_cmd[COMMAND_THRUST], guidance_v_zd_ref); + int32_t vertical_thrust = stabilization_cmd[COMMAND_THRUST] / get_vertical_thrust_coeff(); + gv_adapt_run(stateGetAccelNed_i()->z, vertical_thrust, guidance_v_zd_ref); } else { /* reset estimate while not in_flight */ @@ -262,11 +263,22 @@ void guidance_v_run(bool_t in_flight) { } } +#define MAX_BANK_COEF (BFP_OF_REAL(RadOfDeg(30.),INT32_TRIG_FRAC)) + +int32_t get_vertical_thrust_coeff(void) { + int32_t cphi,ctheta,cphitheta; + struct Int32Eulers* att_euler = stateGetNedToBodyEulers_i(); + PPRZ_ITRIG_COS(cphi, att_euler->phi); + PPRZ_ITRIG_COS(ctheta, att_euler->theta); + cphitheta = (cphi * ctheta) >> INT32_TRIG_FRAC; + if (cphitheta < MAX_BANK_COEF) + cphitheta = MAX_BANK_COEF; + return cphitheta; +} + #define FF_CMD_FRAC 18 -#define MAX_BANK_COEF (BFP_OF_REAL(RadOfDeg(30.),INT32_TRIG_FRAC)) - void run_hover_loop(bool_t in_flight) { /* convert our reference to generic representation */ @@ -301,14 +313,8 @@ void run_hover_loop(bool_t in_flight) { (guidance_v_zdd_ref << (FF_CMD_FRAC - INT32_ACCEL_FRAC)); guidance_v_ff_cmd = g_m_zdd / inv_m; - int32_t cphi,ctheta,cphitheta; - struct Int32Eulers* att_euler = stateGetNedToBodyEulers_i(); - PPRZ_ITRIG_COS(cphi, att_euler->phi); - PPRZ_ITRIG_COS(ctheta, att_euler->theta); - cphitheta = (cphi * ctheta) >> INT32_TRIG_FRAC; - if (cphitheta < MAX_BANK_COEF) cphitheta = MAX_BANK_COEF; /* feed forward command */ - guidance_v_ff_cmd = (guidance_v_ff_cmd << INT32_TRIG_FRAC) / cphitheta; + guidance_v_ff_cmd = (guidance_v_ff_cmd << INT32_TRIG_FRAC) / get_vertical_thrust_coeff(); /* bound the nominal command to 0.9*MAX_PPRZ */ Bound(guidance_v_ff_cmd, 0, 8640); diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h index 4a94b4cfa8..6f66198205 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h @@ -101,6 +101,8 @@ extern void guidance_v_mode_changed(uint8_t new_mode); extern void guidance_v_notify_in_flight(bool_t in_flight); extern void guidance_v_run(bool_t in_flight); +extern int32_t get_vertical_thrust_coeff(void); + #define guidance_v_SetKi(_val) { \ guidance_v_ki = _val; \ guidance_v_z_sum_err = 0; \ diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c index 382a3cb0bb..e1cd5e4979 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v_adapt.c @@ -64,7 +64,7 @@ PRINT_CONFIG_VAR(GUIDANCE_V_ADAPT_MAX_HOVER_THROTTLE) /** Adapt noise factor. * Smaller values will make the filter to adapt faster. - * Bigger values (slower adaptation) make the filter more robust to external perturbations. + * Bigger values (slower adaptation) make the filter more robust to external pertubations. * Factor should always be >0 */ #ifndef GUIDANCE_V_ADAPT_NOISE_FACTOR From 8c71ec676d168e2a4bbfa85cab2b8fcf2054f2e4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 11:13:01 +0200 Subject: [PATCH 224/309] [guidance_v] make some functions static --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 8 ++++---- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h | 2 -- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index d535c76ae1..03db6d7317 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -102,8 +102,8 @@ int32_t guidance_v_z_sum_err; guidance_v_zdd_ref = _accel; \ } - -void run_hover_loop(bool_t in_flight); +static int32_t get_vertical_thrust_coeff(void); +static void run_hover_loop(bool_t in_flight); void guidance_v_init(void) { @@ -265,7 +265,7 @@ void guidance_v_run(bool_t in_flight) { #define MAX_BANK_COEF (BFP_OF_REAL(RadOfDeg(30.),INT32_TRIG_FRAC)) -int32_t get_vertical_thrust_coeff(void) { +static int32_t get_vertical_thrust_coeff(void) { int32_t cphi,ctheta,cphitheta; struct Int32Eulers* att_euler = stateGetNedToBodyEulers_i(); PPRZ_ITRIG_COS(cphi, att_euler->phi); @@ -279,7 +279,7 @@ int32_t get_vertical_thrust_coeff(void) { #define FF_CMD_FRAC 18 -void run_hover_loop(bool_t in_flight) { +static void run_hover_loop(bool_t in_flight) { /* convert our reference to generic representation */ int64_t tmp = gv_z_ref>>(GV_Z_REF_FRAC - INT32_POS_FRAC); diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h index 6f66198205..4a94b4cfa8 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h @@ -101,8 +101,6 @@ extern void guidance_v_mode_changed(uint8_t new_mode); extern void guidance_v_notify_in_flight(bool_t in_flight); extern void guidance_v_run(bool_t in_flight); -extern int32_t get_vertical_thrust_coeff(void); - #define guidance_v_SetKi(_val) { \ guidance_v_ki = _val; \ guidance_v_z_sum_err = 0; \ From 0a8cfabd8ab1afa27c694f69a6975fe7feee4eca Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 11:29:29 +0200 Subject: [PATCH 225/309] [guidance_v] fix vertical thrust from COMMAND_THRUST --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index 03db6d7317..c8dac9db45 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -175,7 +175,7 @@ void guidance_v_run(bool_t in_flight) { // FIXME... SATURATIONS NOT TAKEN INTO ACCOUNT // AKA SUPERVISION and co if (in_flight) { - int32_t vertical_thrust = stabilization_cmd[COMMAND_THRUST] / get_vertical_thrust_coeff(); + int32_t vertical_thrust = (stabilization_cmd[COMMAND_THRUST] * get_vertical_thrust_coeff()) >> INT32_TRIG_FRAC; gv_adapt_run(stateGetAccelNed_i()->z, vertical_thrust, guidance_v_zd_ref); } else { From 5e2647eb81eacd15bdd58aab4de2fefbfce007ab Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 15:49:26 +0200 Subject: [PATCH 226/309] [rotorcraft] AUTOPILOT_IN_FLIGHT_MIN_THRUST defaults to 500 (~5%) --- sw/airborne/firmwares/rotorcraft/autopilot.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 17d802181f..0efd589ecb 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -66,7 +66,7 @@ bool_t autopilot_detect_ground_once; /** minimum thrust for in_flight condition in pprz_t units */ #ifndef AUTOPILOT_IN_FLIGHT_MIN_THRUST -#define AUTOPILOT_IN_FLIGHT_MIN_THRUST 50 +#define AUTOPILOT_IN_FLIGHT_MIN_THRUST 500 #endif #ifndef AUTOPILOT_DISABLE_AHRS_KILL From 07a1dc6908e66f404cc21b6323be0d6291b74440 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 17:23:39 +0200 Subject: [PATCH 227/309] [rotorcraft] by default always reset attitude stab on mode change again To only reset (psi setpoint to current value, reset ref, reset integrators) the attitude stabilization if the previous mode was not using it, define NO_ATTITUDE_RESET_ON_MODE_CHANGE --- .../firmwares/rotorcraft/guidance/guidance_h.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index dc247acc1f..e94ac41b18 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -139,32 +139,35 @@ void guidance_h_mode_changed(uint8_t new_mode) { stabilization_attitude_reset_care_free_heading(); case GUIDANCE_H_MODE_FORWARD: case GUIDANCE_H_MODE_ATTITUDE: +#if NO_ATTITUDE_RESET_ON_MODE_CHANGE /* reset attitude stabilization if previous mode was not using it */ if (guidance_h_mode == GUIDANCE_H_MODE_KILL || guidance_h_mode == GUIDANCE_H_MODE_RATE || - guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) { + guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) +#endif stabilization_attitude_enter(); - } break; case GUIDANCE_H_MODE_HOVER: guidance_h_hover_enter(); +#if NO_ATTITUDE_RESET_ON_MODE_CHANGE /* reset attitude stabilization if previous mode was not using it */ if (guidance_h_mode == GUIDANCE_H_MODE_KILL || guidance_h_mode == GUIDANCE_H_MODE_RATE || - guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) { + guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) stabilization_attitude_enter(); - } +#endif break; case GUIDANCE_H_MODE_NAV: guidance_h_nav_enter(); +#if NO_ATTITUDE_RESET_ON_MODE_CHANGE /* reset attitude stabilization if previous mode was not using it */ if (guidance_h_mode == GUIDANCE_H_MODE_KILL || guidance_h_mode == GUIDANCE_H_MODE_RATE || - guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) { + guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) stabilization_attitude_enter(); - } +#endif break; default: From c5c8772458695eef0af8a21f532d3399a35d40b2 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 17:30:01 +0200 Subject: [PATCH 228/309] [rotorcraft] ups, fix wrong endif --- sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index e94ac41b18..842f3ccf21 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -155,8 +155,8 @@ void guidance_h_mode_changed(uint8_t new_mode) { if (guidance_h_mode == GUIDANCE_H_MODE_KILL || guidance_h_mode == GUIDANCE_H_MODE_RATE || guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) - stabilization_attitude_enter(); #endif + stabilization_attitude_enter(); break; case GUIDANCE_H_MODE_NAV: @@ -166,8 +166,8 @@ void guidance_h_mode_changed(uint8_t new_mode) { if (guidance_h_mode == GUIDANCE_H_MODE_KILL || guidance_h_mode == GUIDANCE_H_MODE_RATE || guidance_h_mode == GUIDANCE_H_MODE_RC_DIRECT) - stabilization_attitude_enter(); #endif + stabilization_attitude_enter(); break; default: From 6e6dd7ae8231cc0237e86bb39026e0a3b6dda15f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 17:56:05 +0200 Subject: [PATCH 229/309] [tools] calibrate.py: make automatic noise threshold an option --- sw/tools/calibration/calibrate.py | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/sw/tools/calibration/calibrate.py b/sw/tools/calibration/calibrate.py index 9aaf3940b6..c67aa7df0b 100755 --- a/sw/tools/calibration/calibrate.py +++ b/sw/tools/calibration/calibrate.py @@ -43,6 +43,9 @@ def main(): parser.add_option("-p", "--plot", help="Show resulting plots", action="store_true", dest="plot") + parser.add_option("-a", "--auto_threshold", + help="Try to automatically determine noise threshold", + action="store_true", dest="auto_threshold") parser.add_option("-v", "--verbose", action="store_true", dest="verbose") (options, args) = parser.parse_args() @@ -67,12 +70,12 @@ def main(): sensor_ref = 9.81 sensor_res = 10 noise_window = 20; - #noise_threshold = 40; + noise_threshold = 40; elif options.sensor == "MAG": sensor_ref = 1. sensor_res = 11 noise_window = 10; - #noise_threshold = 1000; + noise_threshold = 1000; if not filename.endswith(".data"): parser.error("Please specify a *.data log file") @@ -89,9 +92,10 @@ def main(): # estimate the noise threshold # find the median of measurement vector lenght - meas_median = scipy.median(scipy.array([scipy.linalg.norm(v) for v in measurements])) - # set noise threshold to be below 10% of that - noise_threshold = meas_median * 0.1 + if options.auto_threshold: + meas_median = scipy.median(scipy.array([scipy.linalg.norm(v) for v in measurements])) + # set noise threshold to be below 10% of that + noise_threshold = meas_median * 0.1 if options.verbose: print("Using noise threshold of", noise_threshold, "for filtering.") From 70454b1111f75f43cb04698401f4c7084b67535a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 20:05:39 +0200 Subject: [PATCH 230/309] [guidance_v] only compute thrust coeff once --- sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index c8dac9db45..6043afc00c 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -94,6 +94,8 @@ int32_t guidance_v_ki; int32_t guidance_v_z_sum_err; +static int32_t guidance_v_thrust_coeff; + #define GuidanceVSetRef(_pos, _speed, _accel) { \ gv_set_ref(_pos, _speed, _accel); \ @@ -174,8 +176,9 @@ void guidance_v_run(bool_t in_flight) { // FIXME... SATURATIONS NOT TAKEN INTO ACCOUNT // AKA SUPERVISION and co + guidance_v_thrust_coeff = get_vertical_thrust_coeff(); if (in_flight) { - int32_t vertical_thrust = (stabilization_cmd[COMMAND_THRUST] * get_vertical_thrust_coeff()) >> INT32_TRIG_FRAC; + int32_t vertical_thrust = (stabilization_cmd[COMMAND_THRUST] * guidance_v_thrust_coeff) >> INT32_TRIG_FRAC; gv_adapt_run(stateGetAccelNed_i()->z, vertical_thrust, guidance_v_zd_ref); } else { @@ -314,7 +317,7 @@ static void run_hover_loop(bool_t in_flight) { guidance_v_ff_cmd = g_m_zdd / inv_m; /* feed forward command */ - guidance_v_ff_cmd = (guidance_v_ff_cmd << INT32_TRIG_FRAC) / get_vertical_thrust_coeff(); + guidance_v_ff_cmd = (guidance_v_ff_cmd << INT32_TRIG_FRAC) / guidance_v_thrust_coeff; /* bound the nominal command to 0.9*MAX_PPRZ */ Bound(guidance_v_ff_cmd, 0, 8640); From 5a4b39a417907d51cf765379cefa1fd9f0c12f3b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 3 Sep 2013 22:23:33 +0200 Subject: [PATCH 231/309] [guidance_v] slightly more correct and efficient thrust_coeff calc --- .../rotorcraft/guidance/guidance_v.c | 32 +++++++++++++------ 1 file changed, 22 insertions(+), 10 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index 6043afc00c..dea28f15f7 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -266,17 +266,29 @@ void guidance_v_run(bool_t in_flight) { } } -#define MAX_BANK_COEF (BFP_OF_REAL(RadOfDeg(30.),INT32_TRIG_FRAC)) - +/// get the cosine of the angle between thrust vector and gravity vector static int32_t get_vertical_thrust_coeff(void) { - int32_t cphi,ctheta,cphitheta; - struct Int32Eulers* att_euler = stateGetNedToBodyEulers_i(); - PPRZ_ITRIG_COS(cphi, att_euler->phi); - PPRZ_ITRIG_COS(ctheta, att_euler->theta); - cphitheta = (cphi * ctheta) >> INT32_TRIG_FRAC; - if (cphitheta < MAX_BANK_COEF) - cphitheta = MAX_BANK_COEF; - return cphitheta; + static const int32_t max_bank_coef = BFP_OF_REAL(RadOfDeg(30.), INT32_TRIG_FRAC); + + struct Int32RMat* att = stateGetNedToBodyRMat_i(); + /* thrust vector: + * INT32_RMAT_VMULT(thrust_vect, att, zaxis) + * same as last colum of rmat with INT32_TRIG_FRAC + * struct Int32Vect thrust_vect = {att.m[2], att.m[5], att.m[8]}; + * + * Angle between two vectors v1 and v2: + * angle = acos(dot(v1, v2) / (norm(v1) * norm(v2))) + * since here both are already of unit length: + * angle = acos(dot(v1, v2)) + * since we we want the cosine of the angle we simply need + * thrust_coeff = dot(v1, v2) + * also can be simplified considering: v1 is zaxis with (0,0,1) + * dot(v1, v2) = v1.z * v2.z = v2.z + */ + int32_t coef = att->m[8]; + if (coef < max_bank_coef) + coef = max_bank_coef; + return coef; } From 3f27a933085f87183ce3fac37f9ab068e55087f9 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 3 Sep 2013 16:19:12 +0200 Subject: [PATCH 232/309] [superbitrf] Fixed timing --- .../fixedwing/telemetry_superbitrf.makefile | 14 ++++ .../telemetry_superbitrf.makefile | 4 +- sw/airborne/subsystems/datalink/superbitrf.c | 64 +++++++++++-------- sw/airborne/subsystems/datalink/superbitrf.h | 5 +- 4 files changed, 54 insertions(+), 33 deletions(-) create mode 100644 conf/firmwares/subsystems/fixedwing/telemetry_superbitrf.makefile rename conf/firmwares/subsystems/{shared => rotorcraft}/telemetry_superbitrf.makefile (81%) diff --git a/conf/firmwares/subsystems/fixedwing/telemetry_superbitrf.makefile b/conf/firmwares/subsystems/fixedwing/telemetry_superbitrf.makefile new file mode 100644 index 0000000000..95e0156b6c --- /dev/null +++ b/conf/firmwares/subsystems/fixedwing/telemetry_superbitrf.makefile @@ -0,0 +1,14 @@ +# +# The superbitRF module as telemetry downlink/uplink +# +# +ap.CFLAGS += -DUSE_$(MODEM_PORT) +ap.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) + +ap.CFLAGS += -DDOWNLINK -DDOWNLINK_FBW_DEVICE=SuperbitRF -DDOWNLINK_AP_DEVICE=SuperbitRF +ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=SUPERBITRF +#ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI2 -DUSE_SPI_SLAVE2 + +ap.srcs += peripherals/cyrf6936.c +ap.srcs += subsystems/datalink/downlink.c subsystems/datalink/superbitrf.c subsystems/datalink/pprz_transport.c +ap.srcs += $(SRC_FIRMWARE)/datalink.c diff --git a/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile b/conf/firmwares/subsystems/rotorcraft/telemetry_superbitrf.makefile similarity index 81% rename from conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile rename to conf/firmwares/subsystems/rotorcraft/telemetry_superbitrf.makefile index 01f59768ea..7c784cdcd2 100644 --- a/conf/firmwares/subsystems/shared/telemetry_superbitrf.makefile +++ b/conf/firmwares/subsystems/rotorcraft/telemetry_superbitrf.makefile @@ -7,10 +7,8 @@ ap.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD) ap.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=SuperbitRF ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=SUPERBITRF - -#ap.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=SuperbitRF -#ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=SUPERBITRF #ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI2 -DUSE_SPI_SLAVE2 + ap.srcs += peripherals/cyrf6936.c ap.srcs += subsystems/datalink/downlink.c subsystems/datalink/superbitrf.c subsystems/datalink/pprz_transport.c ap.srcs += $(SRC_FIRMWARE)/datalink.c $(SRC_FIRMWARE)/telemetry.c diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 5c6d27ecfc..fc8efbb801 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -476,16 +476,19 @@ void superbitrf_event(void) { /* Switch the different states */ switch (superbitrf.state) { case 0: + // Fixing timer overflow + if(superbitrf.timer_overflow && get_sys_time_usec() <= superbitrf.timer) + superbitrf.timer_overflow = FALSE; + // When there is a timeout - if (superbitrf.timer < get_sys_time_usec()) { - superbitrf.channel_idx = (IS_DSM2(superbitrf.protocol) || SUPERBITRF_FORCE_DSM2)? (superbitrf.channel_idx + 2) %2 : (superbitrf.channel_idx + 2) %23; + if(superbitrf.timer < get_sys_time_usec() && !superbitrf.timer_overflow) { superbitrf.transfer_timeouts++; superbitrf.timeouts++; superbitrf.state++; } // We really lost the communication - if(superbitrf.timeouts > 2) { + if(superbitrf.timeouts > 100) { superbitrf.state = 0; superbitrf.resync_count++; superbitrf.status = SUPERBITRF_SYNCING_A; @@ -496,22 +499,20 @@ void superbitrf_event(void) { cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_abort_receive, 2); superbitrf.state++; - // Only send on channel 2 - if(superbitrf.crc_seed != ((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { - superbitrf.state = 8; - // Set the timer - superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; - break; - } + // Set the timer + superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; + if(superbitrf.timer < get_sys_time_usec()) + superbitrf.timer_overflow = TRUE; + else + superbitrf.timer_overflow = FALSE; - // Set the timer for sending - superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATAWAIT_TIME) % 0xFFFFFFFF; + // Only send on channel 2 + if(superbitrf.crc_seed != ((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) + superbitrf.state = 8; break; case 2: - // Wait before sending - //superbitrf.state++; - if (superbitrf.timer < get_sys_time_usec()) - superbitrf.state++; + // Wait before sending (FIXME??) + superbitrf.state++; break; case 3: // Create a new packet when no packet loss @@ -549,13 +550,14 @@ void superbitrf_event(void) { // Start receiving cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); superbitrf.state++; - - // Set the timer - superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATAWAIT_TIME + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; break; case 6: + // Fixing timer overflow + if(superbitrf.timer_overflow && get_sys_time_usec() <= superbitrf.timer) + superbitrf.timer_overflow = FALSE; + // Waiting for data receive - if (superbitrf.timer < get_sys_time_usec()) + if (superbitrf.timer < get_sys_time_usec() && !superbitrf.timer_overflow) superbitrf.state++; break; case 7: @@ -584,7 +586,15 @@ void superbitrf_event(void) { break; default: // Set the timer - superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATARECV_TIME + SUPERBITRF_RECV_TIME) % 0xFFFFFFFF; + if(superbitrf.crc_seed != ((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) + superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATARECV_TIME + SUPERBITRF_RECV_TIME) % 0xFFFFFFFF; + else + superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATARECV_TIME + SUPERBITRF_RECV_SHORT_TIME) % 0xFFFFFFFF; + if(superbitrf.timer < get_sys_time_usec()) + superbitrf.timer_overflow = TRUE; + else + superbitrf.timer_overflow = FALSE; + superbitrf.state = 0; break; } @@ -791,7 +801,7 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui /* When we receive a packet during transfer */ case SUPERBITRF_TRANSFER: // Check the MFG id - if(error && !(status & CYRF_BAD_CRC)) { + if(error) { // Start receiving TODO: Fix nicely cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_start_receive, 2); break; @@ -811,10 +821,6 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui break; } - // If the CRC is wrong invert - if (error && (status & CYRF_BAD_CRC)) - superbitrf.crc_seed = ~superbitrf.crc_seed; - // Check if it is a RC packet if(packet[1] == (~superbitrf.bind_mfg_id[3]&0xFF) || packet[1] == (superbitrf.bind_mfg_id[3]&0xFF)) { superbitrf.rc_count++; @@ -824,8 +830,10 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui superbitrf.rc_frame_available = TRUE; // Calculate the timing (seperately for the channel switches) - superbitrf.timing2 = superbitrf.timing1; - superbitrf.timing1 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_TIME); + if(superbitrf.crc_seed != ((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) + superbitrf.timing2 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_TIME); + else + superbitrf.timing1 = get_sys_time_usec() - (superbitrf.timer - SUPERBITRF_RECV_SHORT_TIME); // Go to next receive superbitrf.state = 1; diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h index 8baa147f1a..e1cbb6d3bf 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.h +++ b/sw/airborne/subsystems/datalink/superbitrf.h @@ -35,8 +35,8 @@ /* The timings in microseconds */ #define SUPERBITRF_BIND_RECV_TIME 10000 /**< The time to wait for a bind packet on a channel in microseconds */ #define SUPERBITRF_SYNC_RECV_TIME 7000 /**< The time to wait for a sync packet on a channel in microseconds */ -#define SUPERBITRF_RECV_TIME 22000 /**< The time to wait for a transfer packet on a channel in microseconds */ -#define SUPERBITRF_DATAWAIT_TIME 100 /**< The time to wait after RC receive to send a data packet in microseconds */ +#define SUPERBITRF_RECV_TIME 20000 /**< The time to wait for a transfer packet on a channel in microseconds */ +#define SUPERBITRF_RECV_SHORT_TIME 6000 /**< The time to wait for a transfer packet short on a channel in microseconds */ #define SUPERBITRF_DATARECV_TIME 10000 /**< The time to wait for a data packet on a channel in microseconds */ #define SUPERBITRF_DATARECVB_TIME 6000 /**< The time to wait for a data packet on a channel during bind in microseconds */ @@ -75,6 +75,7 @@ struct SuperbitRF { volatile enum SuperbitRFStatus status; /**< The status of the superbitRF */ uint8_t state; /**< The states each status can be in */ uint32_t timer; /**< The timer in microseconds */ + bool_t timer_overflow; /**< When the timer overflows */ uint8_t timeouts; /**< The amount of timeouts */ uint32_t transfer_timeouts; /**< The amount of timeouts during transfer */ uint32_t resync_count; /**< The amount of resyncs needed during transfer */ From 15c6424d3763abe7fb6907ccc45ba92ac92b49f6 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Tue, 3 Sep 2013 16:19:12 +0200 Subject: [PATCH 233/309] [conf] update some TUDelft airframe - Fix automatic kill and tuned ChouChou - Walkera heli reference model updated --- .../TUDelft/IMAV2013/chouchou_lisa_s.xml | 223 ++++++++++++++++++ conf/airframes/TUDelft/IMAV2013/conf.xml | 85 ++++--- .../TUDelft/IMAV2013/mavrick_lisa_s.xml | 28 +-- .../TUDelft/IMAV2013/quadrotor_lisa_s.xml | 4 +- .../TUDelft/IMAV2013/walkera_genius_v1.xml | 27 +-- conf/airframes/examples/quadrotor_lisa_s.xml | 1 - 6 files changed, 296 insertions(+), 72 deletions(-) create mode 100644 conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml diff --git a/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml new file mode 100644 index 0000000000..2ff2bb94a6 --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml @@ -0,0 +1,223 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + +
+ + +
+ + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ +
+ +
+ +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/airframes/TUDelft/IMAV2013/conf.xml b/conf/airframes/TUDelft/IMAV2013/conf.xml index 76978844ac..5581e4ce28 100644 --- a/conf/airframes/TUDelft/IMAV2013/conf.xml +++ b/conf/airframes/TUDelft/IMAV2013/conf.xml @@ -1,45 +1,52 @@ - - + name="ChouChou_LisaS" + ac_id="5" + airframe="airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml" + radio="radios/cockpitSX.xml" + telemetry="telemetry/default_rotorcraft.xml" + flight_plan="flight_plans/rotorcraft_basic.xml" + settings=" settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml settings/control/stabilization_rate.xml settings/control/rotorcraft_guidance.xml" + gui_color="blue" + /> + name="MavRick_LisaS" + ac_id="1" + airframe="airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml" + radio="radios/cockpitSX.xml" + telemetry="telemetry/default_fixedwing_imu.xml" + flight_plan="flight_plans/basic.xml" + settings=" settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/ins_neutrals.xml" + gui_color="white" + /> + name="Quadrotor_LisaS" + ac_id="2" + airframe="airframes/examples/quadrotor_lisa_s.xml" + radio="radios/cockpitSX.xml" + telemetry="telemetry/default_rotorcraft.xml" + flight_plan="flight_plans/rotorcraft_basic.xml" + settings=" settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml settings/control/stabilization_rate.xml" + gui_color="blue" + /> - + name="Walkera_GeniusV1" + ac_id="4" + airframe="airframes/TUDelft/IMAV2013/walkera_genius_v1.xml" + radio="radios/cockpitSX.xml" + telemetry="telemetry/default_rotorcraft.xml" + flight_plan="flight_plans/rotorcraft_basic.xml" + settings=" settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int.xml settings/control/stabilization_rate.xml" + gui_color="orange" + /> + diff --git a/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml index 4955b2c088..7f719564ee 100644 --- a/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml @@ -23,7 +23,7 @@ - + @@ -42,8 +42,8 @@ - - + + @@ -86,17 +86,12 @@ - - - - - - - - - - - + + + + + +
@@ -107,7 +102,10 @@
- + + + +
diff --git a/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml index 69108b84fa..b73795e5aa 100644 --- a/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml @@ -22,7 +22,7 @@ - + @@ -76,7 +76,7 @@
- +
diff --git a/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml b/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml index aa31e8d4ec..4e7dda0a2e 100644 --- a/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml +++ b/conf/airframes/TUDelft/IMAV2013/walkera_genius_v1.xml @@ -41,7 +41,7 @@
- + @@ -71,7 +71,7 @@
- +
@@ -90,27 +90,25 @@ - - - + - - + + - + - - + + - + - - + + @@ -178,10 +176,9 @@ - + - diff --git a/conf/airframes/examples/quadrotor_lisa_s.xml b/conf/airframes/examples/quadrotor_lisa_s.xml index 640ec29d44..5dcc646985 100644 --- a/conf/airframes/examples/quadrotor_lisa_s.xml +++ b/conf/airframes/examples/quadrotor_lisa_s.xml @@ -196,7 +196,6 @@ - From 5a6f4cff1714fd8af5235672d48ad64c09698627 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 4 Sep 2013 21:36:02 +0200 Subject: [PATCH 234/309] [nps] add nps_bypass_ins option --- conf/settings/nps.xml | 1 + sw/airborne/firmwares/rotorcraft/main.c | 3 ++ sw/airborne/math/pprz_algebra.h | 12 ++++++++ sw/simulator/nps/nps_autopilot_rotorcraft.c | 34 +++++++++++++++++++-- sw/simulator/nps/nps_autopilot_rotorcraft.h | 2 ++ 5 files changed, 49 insertions(+), 3 deletions(-) diff --git a/conf/settings/nps.xml b/conf/settings/nps.xml index d4b2b93c89..8fb6ed6513 100644 --- a/conf/settings/nps.xml +++ b/conf/settings/nps.xml @@ -5,6 +5,7 @@ + diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 5edfa0660f..b942a084ac 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -294,6 +294,9 @@ static inline void on_gyro_event( void ) { if (nps_bypass_ahrs) sim_overwrite_ahrs(); #endif ins_propagate(); +#ifdef SITL + if (nps_bypass_ins) sim_overwrite_ins(); +#endif } #ifdef USE_VEHICLE_INTERFACE vi_notify_imu_available(); diff --git a/sw/airborne/math/pprz_algebra.h b/sw/airborne/math/pprz_algebra.h index 4bf69fc197..25439b28c5 100644 --- a/sw/airborne/math/pprz_algebra.h +++ b/sw/airborne/math/pprz_algebra.h @@ -626,6 +626,18 @@ (_ri).r = RATE_BFP_OF_REAL((_rf).r); \ } +#define POSITIONS_FLOAT_OF_BFP(_ef, _ei) { \ + (_ef).x = POS_FLOAT_OF_BFP((_ei).x); \ + (_ef).y = POS_FLOAT_OF_BFP((_ei).y); \ + (_ef).z = POS_FLOAT_OF_BFP((_ei).z); \ + } + +#define POSITIONS_BFP_OF_REAL(_ef, _ei) { \ + (_ef).x = POS_BFP_OF_REAL((_ei).x); \ + (_ef).y = POS_BFP_OF_REAL((_ei).y); \ + (_ef).z = POS_BFP_OF_REAL((_ei).z); \ + } + #define SPEEDS_FLOAT_OF_BFP(_ef, _ei) { \ (_ef).x = SPEED_FLOAT_OF_BFP((_ei).x); \ (_ef).y = SPEED_FLOAT_OF_BFP((_ei).y); \ diff --git a/sw/simulator/nps/nps_autopilot_rotorcraft.c b/sw/simulator/nps/nps_autopilot_rotorcraft.c index f87e000747..0a8cfa11c4 100644 --- a/sw/simulator/nps/nps_autopilot_rotorcraft.c +++ b/sw/simulator/nps/nps_autopilot_rotorcraft.c @@ -31,22 +31,32 @@ #include "subsystems/electrical.h" #include "mcu_periph/sys_time.h" #include "state.h" +#include "nps_fdm.h" +#include "subsystems/ahrs.h" +#include "subsystems/ins.h" +#include "math/pprz_algebra.h" #include "subsystems/actuators/motor_mixing.h" struct NpsAutopilot autopilot; bool_t nps_bypass_ahrs; +bool_t nps_bypass_ins; #ifndef NPS_BYPASS_AHRS #define NPS_BYPASS_AHRS FALSE #endif +#ifndef NPS_BYPASS_INS +#define NPS_BYPASS_INS FALSE +#endif + void nps_autopilot_init(enum NpsRadioControlType type_rc, int num_rc_script, char* rc_dev) { nps_radio_control_init(type_rc, num_rc_script, rc_dev); nps_bypass_ahrs = NPS_BYPASS_AHRS; + nps_bypass_ins = NPS_BYPASS_INS; main_init(); @@ -98,6 +108,10 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { sim_overwrite_ahrs(); } + if (nps_bypass_ins) { + sim_overwrite_ins(); + } + handle_periodic_tasks(); /* scale final motor commands to 0-1 for feeding the fdm */ @@ -107,9 +121,7 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { } -#include "nps_fdm.h" -#include "subsystems/ahrs.h" -#include "math/pprz_algebra.h" + void sim_overwrite_ahrs(void) { struct Int32Quat quat; @@ -121,3 +133,19 @@ void sim_overwrite_ahrs(void) { stateSetBodyRates_i(&rates); } + +void sim_overwrite_ins(void) { + + struct NedCoor_i ltp_pos; + POSITIONS_BFP_OF_REAL(ltp_pos, fdm.ltpprz_pos); + stateSetPositionNed_i(<p_pos); + + struct NedCoor_i ltp_speed; + SPEEDS_BFP_OF_REAL(ltp_speed, fdm.ltpprz_ecef_vel); + stateSetSpeedNed_i(<p_speed); + + struct NedCoor_i ltp_accel; + ACCELS_BFP_OF_REAL(ltp_accel, fdm.ltpprz_ecef_accel); + stateSetAccelNed_i(<p_accel); + +} diff --git a/sw/simulator/nps/nps_autopilot_rotorcraft.h b/sw/simulator/nps/nps_autopilot_rotorcraft.h index 9d04b7213c..b71ffd7eb8 100644 --- a/sw/simulator/nps/nps_autopilot_rotorcraft.h +++ b/sw/simulator/nps/nps_autopilot_rotorcraft.h @@ -5,6 +5,8 @@ extern bool_t nps_bypass_ahrs; +extern bool_t nps_bypass_ins; extern void sim_overwrite_ahrs(void); +extern void sim_overwrite_ins(void); #endif /* NPS_AUTOPILOT_ROTORCRAFT_H */ From 280f97111e3c1e77af9433bb37728818612f6dcd Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 5 Sep 2013 15:36:28 +0200 Subject: [PATCH 235/309] [conf] nps: replace INITIAL_CONDITITONS by JSBSIM_INIT --- conf/airframes/CDW/asctec_cdw.xml | 2 +- conf/airframes/CDW/tricopter_cdw.xml | 2 +- conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml | 2 +- conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml | 2 +- conf/airframes/ardrone2_raw.xml | 2 +- conf/airframes/esden/quady_ls01pwm.xml | 2 +- conf/airframes/examples/quadrotor_lisa_s.xml | 2 +- conf/airframes/examples/quadrotor_mlkf.xml | 2 +- conf/airframes/examples/quadrotor_px4fmu.xml | 2 +- conf/airframes/fraser_lisa_m_rotorcraft.xml | 2 +- 10 files changed, 10 insertions(+), 10 deletions(-) diff --git a/conf/airframes/CDW/asctec_cdw.xml b/conf/airframes/CDW/asctec_cdw.xml index e28e7f538b..830c176d2f 100644 --- a/conf/airframes/CDW/asctec_cdw.xml +++ b/conf/airframes/CDW/asctec_cdw.xml @@ -220,7 +220,7 @@
- +
diff --git a/conf/airframes/CDW/tricopter_cdw.xml b/conf/airframes/CDW/tricopter_cdw.xml index 48e2192956..86946f11f3 100644 --- a/conf/airframes/CDW/tricopter_cdw.xml +++ b/conf/airframes/CDW/tricopter_cdw.xml @@ -209,7 +209,7 @@ LiPo/LiIo-Zellen: 2-3
- +
diff --git a/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml index 2ff2bb94a6..ace2179575 100644 --- a/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml @@ -182,7 +182,7 @@
- +
diff --git a/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml index b73795e5aa..064c01ae5a 100644 --- a/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/quadrotor_lisa_s.xml @@ -184,7 +184,7 @@
- +
diff --git a/conf/airframes/ardrone2_raw.xml b/conf/airframes/ardrone2_raw.xml index 579ff9a31f..99265a1638 100644 --- a/conf/airframes/ardrone2_raw.xml +++ b/conf/airframes/ardrone2_raw.xml @@ -203,7 +203,7 @@
- +
diff --git a/conf/airframes/esden/quady_ls01pwm.xml b/conf/airframes/esden/quady_ls01pwm.xml index 9dc6032179..4a3a194c39 100644 --- a/conf/airframes/esden/quady_ls01pwm.xml +++ b/conf/airframes/esden/quady_ls01pwm.xml @@ -164,7 +164,7 @@
- +
diff --git a/conf/airframes/examples/quadrotor_lisa_s.xml b/conf/airframes/examples/quadrotor_lisa_s.xml index 5dcc646985..6cee5b9cfa 100644 --- a/conf/airframes/examples/quadrotor_lisa_s.xml +++ b/conf/airframes/examples/quadrotor_lisa_s.xml @@ -182,7 +182,7 @@
- +
diff --git a/conf/airframes/examples/quadrotor_mlkf.xml b/conf/airframes/examples/quadrotor_mlkf.xml index 781cbd771a..8778f766e9 100644 --- a/conf/airframes/examples/quadrotor_mlkf.xml +++ b/conf/airframes/examples/quadrotor_mlkf.xml @@ -207,7 +207,7 @@ - +
diff --git a/conf/airframes/examples/quadrotor_px4fmu.xml b/conf/airframes/examples/quadrotor_px4fmu.xml index 7d9b21aaeb..a67d1738fd 100644 --- a/conf/airframes/examples/quadrotor_px4fmu.xml +++ b/conf/airframes/examples/quadrotor_px4fmu.xml @@ -198,7 +198,7 @@
- +
diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index d57a70036b..7fec69072c 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -238,7 +238,7 @@
- + From 95e063f8aa4487500db06e0f794f79786e87f2c8 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 5 Sep 2013 15:52:25 +0200 Subject: [PATCH 236/309] [fixedwing] fix missing #endif --- sw/airborne/firmwares/fixedwing/main_ap.c | 1 + 1 file changed, 1 insertion(+) diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 4ea104e75f..ee1a5795a3 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -99,6 +99,7 @@ #ifndef COMMAND_YAW_TRIM #define COMMAND_YAW_TRIM 0 +#endif /* if PRINT_CONFIG is defined, print some config options */ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) From 15027d5e4d123c8e75e7b7d1434158b2836d2748 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 5 Sep 2013 15:52:50 +0200 Subject: [PATCH 237/309] [conf] fix conditional in ins_xsens makefile --- conf/firmwares/subsystems/fixedwing/ins_xsens.makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile b/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile index fca745a71c..4440f92bfd 100644 --- a/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile +++ b/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile @@ -48,7 +48,7 @@ ap.srcs += $(SRC_SUBSYSTEMS)/gps.c ## Simulator SIM_TARGETS = sim jsbsim nps -ifneq (,$(findstring $(TARGET),$(SIM_TARGETS)) +ifneq (,$(findstring $(TARGET),$(SIM_TARGETS))) $(TARGET).CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" $(TARGET).CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR From c659d7d8d649705e0910b34112c7dacc3c1941ff Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 5 Sep 2013 16:05:41 +0200 Subject: [PATCH 238/309] [nps] include common_flight_plan.h on ivy_common --- sw/simulator/nps/nps_ivy_common.c | 1 + 1 file changed, 1 insertion(+) diff --git a/sw/simulator/nps/nps_ivy_common.c b/sw/simulator/nps/nps_ivy_common.c index 90766d756e..c93bd7d4eb 100644 --- a/sw/simulator/nps/nps_ivy_common.c +++ b/sw/simulator/nps/nps_ivy_common.c @@ -10,6 +10,7 @@ #include "nps_fdm.h" #include "nps_sensors.h" #include "subsystems/ins.h" +#include "subsystems/navigation/common_flight_plan.h" #ifdef RADIO_CONTROL_TYPE_DATALINK #include "subsystems/radio_control.h" From d2e05e51f03366a59824d9f3ec9a93f5397413f7 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 5 Sep 2013 18:07:59 +0200 Subject: [PATCH 239/309] [rotorcraft] rename autopilot_detect_ground to autopilot_ground_detected --- sw/airborne/firmwares/rotorcraft/autopilot.c | 8 ++++---- sw/airborne/firmwares/rotorcraft/autopilot.h | 4 ++-- sw/airborne/firmwares/rotorcraft/navigation.c | 4 ++-- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index e49cd955b7..4a78cdfad4 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -49,7 +49,7 @@ bool_t kill_throttle; bool_t autopilot_rc; bool_t autopilot_power_switch; -bool_t autopilot_detect_ground; +bool_t autopilot_ground_detected; bool_t autopilot_detect_ground_once; #define AUTOPILOT_IN_FLIGHT_TIME 20 @@ -105,7 +105,7 @@ void autopilot_init(void) { autopilot_in_flight = FALSE; autopilot_in_flight_counter = 0; autopilot_mode_auto2 = MODE_AUTO2; - autopilot_detect_ground = FALSE; + autopilot_ground_detected = FALSE; autopilot_detect_ground_once = FALSE; autopilot_flight_time = 0; autopilot_rc = TRUE; @@ -131,9 +131,9 @@ void autopilot_periodic(void) { RunOnceEvery(NAV_PRESCALER, nav_periodic_task()); #if FAILSAFE_GROUND_DETECT INFO("Using FAILSAFE_GROUND_DETECT") - if (autopilot_mode == AP_MODE_FAILSAFE && autopilot_detect_ground) { + if (autopilot_mode == AP_MODE_FAILSAFE && autopilot_ground_detected) { autopilot_set_mode(AP_MODE_KILL); - autopilot_detect_ground = FALSE; + autopilot_ground_detected = FALSE; } #endif diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.h b/sw/airborne/firmwares/rotorcraft/autopilot.h index d970b9aba7..9203c6e43f 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot.h @@ -69,7 +69,7 @@ extern void autopilot_set_mode(uint8_t new_autopilot_mode); extern void autopilot_set_motors_on(bool_t motors_on); extern void autopilot_check_in_flight(bool_t motors_on); -extern bool_t autopilot_detect_ground; +extern bool_t autopilot_ground_detected; extern bool_t autopilot_detect_ground_once; extern uint16_t autopilot_flight_time; @@ -152,7 +152,7 @@ static inline void DetectGroundEvent(void) { struct NedCoor_f* accel = stateGetAccelNed_f(); if (accel->z < -THRESHOLD_GROUND_DETECT || accel->z > THRESHOLD_GROUND_DETECT) { - autopilot_detect_ground = TRUE; + autopilot_ground_detected = TRUE; autopilot_detect_ground_once = FALSE; } } diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c index 40d86cc7a7..2fdc841aa0 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.c +++ b/sw/airborne/firmwares/rotorcraft/navigation.c @@ -336,8 +336,8 @@ void navigation_update_wp_from_speed(uint8_t wp, struct Int16Vect3 speed_sp, int } bool_t nav_detect_ground(void) { - if (!autopilot_detect_ground) return FALSE; - autopilot_detect_ground = FALSE; + if (!autopilot_ground_detected) return FALSE; + autopilot_ground_detected = FALSE; return TRUE; } From bc3955993f3cfa51eb54b8a0f383145e5e620c6b Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Fri, 6 Sep 2013 16:47:14 +0200 Subject: [PATCH 240/309] [supervision] sort AC and session in alphabetic order --- sw/supervision/pc_aircraft.ml | 3 ++- sw/supervision/pc_control_panel.ml | 9 +++++---- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/sw/supervision/pc_aircraft.ml b/sw/supervision/pc_aircraft.ml index 1c95fd3b9d..1537747e69 100644 --- a/sw/supervision/pc_aircraft.ml +++ b/sw/supervision/pc_aircraft.ml @@ -79,7 +79,8 @@ let new_ac_id = fun () -> let parse_conf_xml = fun vbox -> let strings = ref [] in Hashtbl.iter (fun name _ac -> strings := name :: !strings) Utils.aircrafts; - Gtk_tools.combo ("" :: !strings) vbox + let ordered = List.sort String.compare ("" :: !strings) in + Gtk_tools.combo ordered vbox let editor = try Sys.getenv "EDITOR" with _ -> ( diff --git a/sw/supervision/pc_control_panel.ml b/sw/supervision/pc_control_panel.ml index a476317842..2793706092 100644 --- a/sw/supervision/pc_control_panel.ml +++ b/sw/supervision/pc_control_panel.ml @@ -195,10 +195,11 @@ let supervision = fun ?file gui log (ac_combo : Gtk_tools.combo) (target_combo : Gtk_tools.add_to_combo session_combo "Simulation"; Gtk_tools.add_to_combo session_combo "Replay"; Gtk_tools.add_to_combo session_combo Gtk_tools.combo_separator; - Hashtbl.iter - (fun name _session -> - Gtk_tools.add_to_combo session_combo name) - sessions in + let strings = ref [] in + Hashtbl.iter (fun name _session -> strings := name :: !strings) sessions; + let ordered = List.sort String.compare !strings in + List.iter (fun name -> Gtk_tools.add_to_combo session_combo name) ordered + in register_custom_sessions (); Gtk_tools.select_in_combo session_combo "Simulation"; From 28028180ea594b670f8b7ac1cb34860c0907daf6 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Fri, 6 Sep 2013 16:18:48 +0200 Subject: [PATCH 241/309] [conf] Airframe Templates: $AC_ID is auto-filled. Allows to include specific calibrations and set specific names. --- sw/tools/gen_airframe.ml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sw/tools/gen_airframe.ml b/sw/tools/gen_airframe.ml index a8d0c34221..8e066b3ec4 100644 --- a/sw/tools/gen_airframe.ml +++ b/sw/tools/gen_airframe.ml @@ -229,7 +229,7 @@ let parse_command = fun command no -> let failsafe_value = int_of_string (ExtXml.attrib command "failsafe_value") in { failsafe_value = failsafe_value; foo = 0} -let rec parse_section = fun s -> +let rec parse_section = fun ac_id s -> match Xml.tag s with "section" -> let prefix = ExtXml.attrib_or_default s "prefix" "" in @@ -281,11 +281,11 @@ let rec parse_section = fun s -> List.iter (fun d -> printf " Actuators%sInit();\\\n" d) drivers; printf "}\n\n"; | "include" -> - let filename = ExtXml.attrib s "href" in + let filename = Str.global_replace (Str.regexp "\$AC_ID") ac_id (ExtXml.attrib s "href") in let subxml = Xml.parse_file filename in printf "/* XML %s */" filename; nl (); - List.iter parse_section (Xml.children subxml) + List.iter (parse_section ac_id) (Xml.children subxml) | "makefile" -> () (** Ignoring this section *) @@ -320,7 +320,7 @@ let _ = define "AC_ID" ac_id; define "MD5SUM" (sprintf "((uint8_t*)\"%s\")" (hex_to_bin md5sum)); nl (); - List.iter parse_section (Xml.children xml); + List.iter (parse_section ac_id) (Xml.children xml); finish h_name with Xml.Error e -> fprintf stderr "%s: XML error:%s\n" xml_file (Xml.error e); exit 1 From 9b16d51afa1621ed586ae00b08bbfd091f048450 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 7 Sep 2013 20:15:57 +0200 Subject: [PATCH 242/309] [conf] fix ardrone2_sdk: all leds default to none --- conf/boards/ardrone2_sdk.makefile | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/conf/boards/ardrone2_sdk.makefile b/conf/boards/ardrone2_sdk.makefile index 46ba01c8c9..e134414b6c 100644 --- a/conf/boards/ardrone2_sdk.makefile +++ b/conf/boards/ardrone2_sdk.makefile @@ -32,3 +32,10 @@ $(TARGET).CFLAGS += -DUART1_DEV=\"/dev/ttyUSB0\" ap.CFLAGS +=-DARDRONE2_SDK # ----------------------------------------------------------------------- + +# default LED configuration +RADIO_CONTROL_LED ?= none +BARO_LED ?= none +AHRS_ALIGNER_LED ?= none +GPS_LED ?= none +SYS_TIME_LED ?= none From 874cd8ce25121139caa6682e74b9376b439bdc31 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 7 Sep 2013 20:44:33 +0200 Subject: [PATCH 243/309] [conf][subsystems] x_LED default to none so it doesn't fail if not defined in board makefile --- .../subsystems/fixedwing/ahrs_float_cmpl_quat.makefile | 1 + .../subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile | 1 + conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile | 1 + conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile | 2 ++ .../subsystems/fixedwing/ahrs_int_cmpl_euler.makefile | 1 + .../subsystems/fixedwing/ahrs_int_cmpl_quat.makefile | 1 + conf/firmwares/subsystems/fixedwing/autopilot.makefile | 1 + .../subsystems/fixedwing/gps_mediatek_diy.makefile | 1 + conf/firmwares/subsystems/fixedwing/gps_nmea.makefile | 1 + conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile | 2 ++ conf/firmwares/subsystems/fixedwing/gps_ublox.makefile | 1 + conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile | 1 + .../lisa_passthrough/radio_control_spektrum.makefile | 5 ++++- .../subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile | 1 + .../subsystems/rotorcraft/ahrs_float_mlkf.makefile | 1 + conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile | 1 + .../subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile | 5 ++--- conf/firmwares/subsystems/rotorcraft/gps_ardrone2.makefile | 1 + conf/firmwares/subsystems/rotorcraft/gps_sirf.makefile | 2 ++ conf/firmwares/subsystems/rotorcraft/gps_skytraq.makefile | 2 ++ conf/firmwares/subsystems/rotorcraft/gps_ublox.makefile | 2 ++ .../subsystems/shared/radio_control_datalink.makefile | 6 ++++-- conf/firmwares/subsystems/shared/radio_control_ppm.makefile | 1 + .../firmwares/subsystems/shared/radio_control_sbus.makefile | 5 ++++- .../subsystems/shared/radio_control_spektrum.makefile | 3 +++ .../subsystems/shared/radio_control_superbitrf_rc.makefile | 2 ++ 26 files changed, 44 insertions(+), 7 deletions(-) diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile index 3bd625f6b5..4dc3e79289 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile @@ -6,6 +6,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -DAHRS_GRAVITY_UPDATE_COORDINATED_TURN diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile index 6d82542b6c..850cd7c4e3 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile @@ -6,6 +6,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -DAHRS_GRAVITY_UPDATE_COORDINATED_TURN diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile index 6427993c02..805e38da83 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile @@ -3,6 +3,7 @@ # attitude estimation for fixedwings via dcm algorithm USE_MAGNETOMETER ?= 0 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_float_dcm.h\" AHRS_CFLAGS += -DUSE_AHRS_ALIGNER diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile index 2d0d4cee14..e7bb2544c4 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile @@ -4,6 +4,8 @@ GX3_PORT ?= UART3 GX3_BAUD ?= B921600 +AHRS_ALIGNER_LED ?= none + AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_IMU AHRS_CFLAGS += -DUSE_IMU_FLOAT diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile index 67cb44eb1f..ba7f7c884a 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile @@ -2,6 +2,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR -DUSE_AHRS_CMPL_EULER AHRS_CFLAGS += -DUSE_AHRS_ALIGNER diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile index 5bea385eaa..b81a94d6ab 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile @@ -7,6 +7,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -DAHRS_GRAVITY_UPDATE_COORDINATED_TURN diff --git a/conf/firmwares/subsystems/fixedwing/autopilot.makefile b/conf/firmwares/subsystems/fixedwing/autopilot.makefile index 90b9883deb..6c93338ac6 100644 --- a/conf/firmwares/subsystems/fixedwing/autopilot.makefile +++ b/conf/firmwares/subsystems/fixedwing/autopilot.makefile @@ -109,6 +109,7 @@ ns_srcs += $(SRC_FIRMWARE)/main.c # # LEDs # +SYS_TIME_LED ?= none ns_CFLAGS += -DUSE_LED ifneq ($(SYS_TIME_LED),none) ns_CFLAGS += -DSYS_TIME_LED=$(SYS_TIME_LED) diff --git a/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile b/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile index 931c35fed0..ffea6bd274 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_mediatek_diy.makefile @@ -2,6 +2,7 @@ # Mediatek MT3329, DIYDrones V1.4/1.6 protocol +GPS_LED ?= none ap.CFLAGS += -DUSE_GPS -DGPS_CONFIGURE -DGPS_USE_LATLONG ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) diff --git a/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile b/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile index cf03afedac..8e4cac87fe 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_nmea.makefile @@ -2,6 +2,7 @@ # NMEA GPS unit +GPS_LED ?= none ap.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) diff --git a/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile b/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile index 2e04091ffc..d0b49e7ed0 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_skytraq.makefile @@ -1,5 +1,7 @@ # Hey Emacs, this is a -*- makefile -*- +GPS_LED ?= none + ap.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) ap.CFLAGS += -DUSE_$(GPS_PORT) diff --git a/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile b/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile index 5860741b4c..4116d8cfa7 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_ublox.makefile @@ -1,6 +1,7 @@ # Hey Emacs, this is a -*- makefile -*- # UBlox LEA 5H +GPS_LED ?= none ap.CFLAGS += -DUSE_GPS -DUBX -DGPS_USE_LATLONG ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) diff --git a/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile b/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile index 0865b4f8c7..0a9622ff51 100644 --- a/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile +++ b/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile @@ -1,6 +1,7 @@ # Hey Emacs, this is a -*- makefile -*- # UBlox LEA 4P +GPS_LED ?= none ap.CFLAGS += -DUSE_GPS -DUBX ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) diff --git a/conf/firmwares/subsystems/lisa_passthrough/radio_control_spektrum.makefile b/conf/firmwares/subsystems/lisa_passthrough/radio_control_spektrum.makefile index c866fd53e3..49c54b444c 100644 --- a/conf/firmwares/subsystems/lisa_passthrough/radio_control_spektrum.makefile +++ b/conf/firmwares/subsystems/lisa_passthrough/radio_control_spektrum.makefile @@ -2,6 +2,7 @@ # Makefile for radio_control susbsytem in rotorcraft firmware # +RADIO_CONTROL_LED ?= none ifndef RADIO_CONTROL_SPEKTRUM_MODEL RADIO_CONTROL_SPEKTRUM_MODEL=\"subsystems/radio_control/spektrum_dx7se.h\" @@ -10,10 +11,12 @@ endif stm_passthrough.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_BIND_IMPL_FUNC=radio_control_spektrum_try_bind stm_passthrough.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/spektrum.h\" stm_passthrough.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_MODEL_H=$(RADIO_CONTROL_SPEKTRUM_MODEL) -stm_passthrough.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) stm_passthrough.CFLAGS += -DRADIO_CONTROL_LINK=$(RADIO_CONTROL_LINK) stm_passthrough.CFLAGS += -DUSE_$(RADIO_CONTROL_LINK) -D$(RADIO_CONTROL_LINK)_BAUD=B115200 stm_passthrough.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ $(SRC_SUBSYSTEMS)/radio_control/spektrum.c \ $(SRC_ARCH)/subsystems/radio_control/spektrum_arch.c +ifneq ($(RADIO_CONTROL_LED,none)) +stm_passthrough.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) +endif diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile index 0e0b595620..6834e76f67 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_float_cmpl_quat.makefile @@ -6,6 +6,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DAHRS_FLOAT AHRS_CFLAGS += -DUSE_AHRS_ALIGNER diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_float_mlkf.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_float_mlkf.makefile index 13049dac9f..e3ee599098 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_float_mlkf.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_float_mlkf.makefile @@ -3,6 +3,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DAHRS_FLOAT AHRS_CFLAGS += -DUSE_AHRS_ALIGNER diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile index 253b4c62a6..e12acb6c6a 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_gx3.makefile @@ -3,6 +3,7 @@ GX3_PORT ?= UART3 GX3_BAUD ?= B921600 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_IMU diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile index 2be240c0b0..1efba93150 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile @@ -3,9 +3,8 @@ # Fixed point complementary filter using euler angles for attitude estimation # -ifndef USE_MAGNETOMETER -USE_MAGNETOMETER = 1 -endif +USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS -DUSE_AHRS_CMPL_EULER AHRS_CFLAGS += -DUSE_AHRS_ALIGNER diff --git a/conf/firmwares/subsystems/rotorcraft/gps_ardrone2.makefile b/conf/firmwares/subsystems/rotorcraft/gps_ardrone2.makefile index fad4a3919f..49de927e45 100644 --- a/conf/firmwares/subsystems/rotorcraft/gps_ardrone2.makefile +++ b/conf/firmwares/subsystems/rotorcraft/gps_ardrone2.makefile @@ -2,6 +2,7 @@ # ARDrone 2 Flightrecorder GPS unit +GPS_LED ?= none ap.CFLAGS += -DUSE_GPS -DUSE_GPS_ARDRONE2 diff --git a/conf/firmwares/subsystems/rotorcraft/gps_sirf.makefile b/conf/firmwares/subsystems/rotorcraft/gps_sirf.makefile index 3cff8b7fa9..37557f098b 100644 --- a/conf/firmwares/subsystems/rotorcraft/gps_sirf.makefile +++ b/conf/firmwares/subsystems/rotorcraft/gps_sirf.makefile @@ -2,6 +2,8 @@ # Sirf GPS unit +GPS_LED ?= none + ap.CFLAGS += -DUSE_GPS ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) ap.CFLAGS += -DUSE_$(GPS_PORT) diff --git a/conf/firmwares/subsystems/rotorcraft/gps_skytraq.makefile b/conf/firmwares/subsystems/rotorcraft/gps_skytraq.makefile index 57ee37fb20..39404dd9e1 100644 --- a/conf/firmwares/subsystems/rotorcraft/gps_skytraq.makefile +++ b/conf/firmwares/subsystems/rotorcraft/gps_skytraq.makefile @@ -1,5 +1,7 @@ # Hey Emacs, this is a -*- makefile -*- +GPS_LED ?= none + ap.CFLAGS += -DUSE_GPS ap.CFLAGS += -DGPS_LINK=$(GPS_PORT) ap.CFLAGS += -DUSE_$(GPS_PORT) diff --git a/conf/firmwares/subsystems/rotorcraft/gps_ublox.makefile b/conf/firmwares/subsystems/rotorcraft/gps_ublox.makefile index c99d67ba37..0fcd453255 100644 --- a/conf/firmwares/subsystems/rotorcraft/gps_ublox.makefile +++ b/conf/firmwares/subsystems/rotorcraft/gps_ublox.makefile @@ -1,5 +1,7 @@ # Hey Emacs, this is a -*- makefile -*- +GPS_LED ?= none + ap.srcs += $(SRC_SUBSYSTEMS)/gps.c ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\" ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c diff --git a/conf/firmwares/subsystems/shared/radio_control_datalink.makefile b/conf/firmwares/subsystems/shared/radio_control_datalink.makefile index 6aed61a1a8..d24c413b5a 100644 --- a/conf/firmwares/subsystems/shared/radio_control_datalink.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_datalink.makefile @@ -9,10 +9,12 @@ ifeq ($(BOARD),classix) endif endif +RADIO_CONTROL_DATALINK_LED ?= none +RADIO_CONTROL_LED ?= none ifeq ($(NORADIO), False) - ifdef (RADIO_CONTROL_DATALINK_LED) - ap.CFLAGS += -D(RADIO_CONTROL_DATALINK_LED=$((RADIO_CONTROL_DATALINK_LED) + ifneq ($(RADIO_CONTROL_DATALINK_LED),none) + ap.CFLAGS += -DRADIO_CONTROL_DATALINK_LED=$(RADIO_CONTROL_DATALINK_LED) endif ifneq ($(RADIO_CONTROL_LED),none) ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) diff --git a/conf/firmwares/subsystems/shared/radio_control_ppm.makefile b/conf/firmwares/subsystems/shared/radio_control_ppm.makefile index f8e49d96d5..19801b6e74 100644 --- a/conf/firmwares/subsystems/shared/radio_control_ppm.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_ppm.makefile @@ -3,6 +3,7 @@ # NORADIO = False +RADIO_CONTROL_LED ?= none ifeq ($(BOARD),classix) ifeq ($(TARGET),ap) diff --git a/conf/firmwares/subsystems/shared/radio_control_sbus.makefile b/conf/firmwares/subsystems/shared/radio_control_sbus.makefile index 2e8e9ecbe1..67970f298a 100644 --- a/conf/firmwares/subsystems/shared/radio_control_sbus.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_sbus.makefile @@ -2,11 +2,14 @@ # Makefile for shared radio_control SBUS subsystem # -$(TARGET).CFLAGS += -DRADIO_CONTROL +RADIO_CONTROL_LED ?= none + ifneq ($(RADIO_CONTROL_LED),none) ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) endif +$(TARGET).CFLAGS += -DRADIO_CONTROL + # convert SBUS_PORT to upper and lower case strings: SBUS_PORT_UPPER=$(shell echo $(SBUS_PORT) | tr a-z A-Z) SBUS_PORT_LOWER=$(shell echo $(SBUS_PORT) | tr A-Z a-z) diff --git a/conf/firmwares/subsystems/shared/radio_control_spektrum.makefile b/conf/firmwares/subsystems/shared/radio_control_spektrum.makefile index 05d9d555c4..6e92d28d91 100644 --- a/conf/firmwares/subsystems/shared/radio_control_spektrum.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_spektrum.makefile @@ -1,6 +1,9 @@ # # Makefile for shared radio_control spektrum susbsytem # + +RADIO_CONTROL_LED ?= none + ifndef RADIO_CONTROL_SPEKTRUM_MODEL RADIO_CONTROL_SPEKTRUM_MODEL=\"subsystems/radio_control/spektrum_dx7se.h\" endif diff --git a/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile index 85a80e4fb0..218a7c194c 100644 --- a/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile +++ b/conf/firmwares/subsystems/shared/radio_control_superbitrf_rc.makefile @@ -2,6 +2,8 @@ # Makefile for shared radio_control superbitrf subsystem # +RADIO_CONTROL_LED ?= none + ap.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE_SUPERBITRF -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/superbitrf_rc.h\" ap.CFLAGS += -DUSE_SUPERBITRF -DUSE_SPI2 -DUSE_SPI_SLAVE2 From 0a0e89ce2e1e1380dd50a885f63792a68e49dd00 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 8 Sep 2013 14:33:58 +0200 Subject: [PATCH 244/309] [conf.xml][GUI] GUI for selecting the desired active list of airframes. --- configure.py | 213 +++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 213 insertions(+) create mode 100755 configure.py diff --git a/configure.py b/configure.py new file mode 100755 index 0000000000..03f7042200 --- /dev/null +++ b/configure.py @@ -0,0 +1,213 @@ +#!/usr/bin/env python + +from __future__ import print_function + +import pygtk +import gtk +pygtk.require('2.0') + + +import os +import datetime +from fnmatch import fnmatch +import subprocess + + +class ConfChooser: + + # General Functions + + def update_combo(self,combo,list): + combo.set_sensitive(False) + combo.get_model().clear() + for i in list: + combo.append_text(i) + combo.set_active(0) + combo.set_sensitive(True) + + def update_label(self): + r = subprocess.Popen("ls -altr ./conf/conf.xml", stdout=subprocess.PIPE,stderr=subprocess.STDOUT, shell=True).stdout.read() + r = r.strip() + self.explain.set_text("Currently set to: " + r) + + # CallBack Functions + + + def find_conf_files(self): + + list_of_conf_files = [] + + root = './conf/' + pattern = "*conf.xml*" + + for path, subdirs, files in os.walk(root): + for name in files: + if fnmatch(name, pattern): + entry = os.path.join(path, name).replace("./conf/","") + if entry != "conf.xml": + list_of_conf_files.append(entry) + + self.update_combo(self.conf_file_combo,list_of_conf_files) + + + def about(self): + gui_dialogs.about(paparazzi.home_dir) + + def launch(self, widget): + os.system("./paparazzi &"); + gtk.main_quit() + + def backupconf(self, personal=0): + timestr = datetime.datetime.now().strftime("%Y-%m-%d_%H:%M") + newname = "conf.xml." + timestr + if " -> " in self.explain.get_text(): + print("Symlink does not need backup"); + else: + os.system("cd " + self.pwd + "/conf && cp conf.xml " + newname) + print("Made a backup: " + newname) + + if personal == 1: + if os.path.exists(self.pwd + "/conf/conf.xml.personal"): + print("Backup conf.xml.personal to conf.xml.personal." + timestr) + os.system("cd " + self.pwd + "/conf && cp conf.xml.personal conf.xml.personal." + timestr) + + def delete(self, widget): + cmd = "cd " + self.pwd + "/conf && rm -f " + self.conf_file_combo.get_active_text() + # TODO: dialog: are you certain? + os.system(cmd) + self.find_conf_files() + + + def accept(self, widget): + self.backupconf() + cmd = "cd " + self.pwd + "/conf && ln -f -s " + self.conf_file_combo.get_active_text() + " conf.xml" + print(cmd) + os.system(cmd) + self.update_label() + self.find_conf_files() + + def personal(self, widget): + self.backupconf(1) + cmd = "cd " + self.pwd + "/conf && cp " + self.conf_file_combo.get_active_text() + " conf.xml.personal && ln -f -s conf.xml.personal conf.xml" + print(cmd) + os.system(cmd) + self.update_label() + self.find_conf_files() + + # Constructor Functions + + def destroy(self, widget, data=None): + gtk.main_quit() + + def __init__(self): + self.window = gtk.Window(gtk.WINDOW_TOPLEVEL) + self.window.set_title("Paparazzi Configuration Chooser") + + self.my_vbox = gtk.VBox() + + # Where Am I? + self.pwd = subprocess.Popen("pwd", stdout=subprocess.PIPE,stderr=subprocess.STDOUT, shell=True).stdout.read().strip() + + # MenuBar + mb = gtk.MenuBar() + + # File + filemenu = gtk.Menu() + + # File Title + filem = gtk.MenuItem("File") + filem.set_submenu(filemenu) + + exitm = gtk.MenuItem("Exit") + exitm.connect("activate", gtk.main_quit) + filemenu.append(exitm) + + mb.append(filem) + + # Help + helpmenu = gtk.Menu() + + # Help Title + helpm = gtk.MenuItem("Help") + helpm.set_submenu(helpmenu) + + aboutm = gtk.MenuItem("About") + aboutm.connect("activate", self.about) + helpmenu.append(aboutm) + + mb.append(helpm) + + self.my_vbox.pack_start(mb,False) + + # Combo Bar + + self.conf_label = gtk.Label("Conf:") + + self.conf_file_combo = gtk.combo_box_entry_new_text() + self.find_conf_files() +# self.firmwares_combo.connect("changed", self.parse_list_of_airframes) + self.conf_file_combo.set_size_request(600,30) + + self.confbar = gtk.HBox() + self.confbar.pack_start(self.conf_label) + self.confbar.pack_start(self.conf_file_combo) + self.my_vbox.pack_start(self.confbar, False) + + ##### Explain current config + + self.explain = gtk.Label(""); + self.update_label() + + self.exbar = gtk.HBox() + self.exbar.pack_start(self.explain) + + self.my_vbox.pack_start(self.exbar, False) + + ##### Buttons + self.btnAccept = gtk.Button("Set Selected Conf As Active") + self.btnAccept.connect("clicked", self.accept) + self.btnAccept.set_tooltip_text("Set Conf as Active") + + self.btnPersonal = gtk.Button("Create Personal Conf Based on Selected") + self.btnPersonal.connect("clicked", self.personal) + self.btnPersonal.set_tooltip_text("Create Personal Conf Based on Selected and Activate") + + self.btnDelete = gtk.Button("Delete Selected") + self.btnDelete.connect("clicked", self.delete) + self.btnDelete.set_tooltip_text("Permanently Delete") + + self.btnLaunch = gtk.Button("Launch Paparazzi") + self.btnLaunch.connect("clicked", self.launch) + self.btnLaunch.set_tooltip_text("Launch Paparazzi with current conf.xml") + + self.btnExit = gtk.Button("Exit") + self.btnExit.connect("clicked", self.destroy) + self.btnExit.set_tooltip_text("Close application") + + + self.toolbar = gtk.HBox() + self.toolbar.pack_start(self.btnAccept) + self.toolbar.pack_start(self.btnPersonal) + self.toolbar.pack_start(self.btnDelete) + self.toolbar.pack_start(self.btnLaunch) + self.toolbar.pack_start(self.btnExit) + + self.my_vbox.pack_start(self.toolbar, False) + + ##### Bottom + + self.window.add(self.my_vbox) + self.window.show_all() + self.window.set_position(gtk.WIN_POS_CENTER_ALWAYS) + self.window.connect("destroy", self.destroy) + + def main(self): + gtk.main() + +if __name__ == "__main__": + import sys + if (len(sys.argv) > 1): + airframe_file = sys.argv[1] + gui = ConfChooser() + gui.main() + From 057c842045172a4ac4f6fb4e86f3a818c4255e5d Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 05:43:37 +0100 Subject: [PATCH 245/309] navdata_port is private. --- sw/airborne/boards/ardrone/navdata.c | 12 +++++++++++- sw/airborne/boards/ardrone/navdata.h | 10 ---------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 7d0e185dcb..639663ba9f 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -36,7 +36,17 @@ #include #include "navdata.h" -int nav_fd; +typedef struct { + uint8_t isInitialized; + uint8_t isOpen; + uint16_t bytesRead; + uint32_t totalBytesRead; + uint32_t packetsRead; + uint8_t buffer[NAVDATA_BUFFER_SIZE]; +} navdata_port; + +static navdata_port* port; +static int nav_fd; int navdata_init() { diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 922bb2e46b..758f30a151 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -36,15 +36,6 @@ #define NAVDATA_BUFFER_SIZE 80 #define NAVDATA_START_BYTE 0x3a -typedef struct { - uint8_t isInitialized; - uint8_t isOpen; - uint16_t bytesRead; - uint32_t totalBytesRead; - uint32_t packetsRead; - uint8_t buffer[NAVDATA_BUFFER_SIZE]; -} navdata_port; - typedef struct { uint16_t taille; @@ -109,7 +100,6 @@ struct bmp180_baro_calibration measures_t* navdata; struct bmp180_baro_calibration baro_calibration; -navdata_port* port; uint16_t navdata_cks; uint8_t navdata_imu_available; uint8_t navdata_baro_available; From b28fae799a7588ad0c0619721551dd6d24532457 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 05:49:55 +0100 Subject: [PATCH 246/309] There's no need for |port| to be dynamically allocated. Also fixes the bug that if |nav_fd| open fails, port->isOpen and port->isInitialised are not cleared. --- sw/airborne/boards/ardrone/navdata.c | 48 +++++++++++++--------------- 1 file changed, 23 insertions(+), 25 deletions(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 639663ba9f..8c6425bb26 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -45,20 +45,18 @@ typedef struct { uint8_t buffer[NAVDATA_BUFFER_SIZE]; } navdata_port; -static navdata_port* port; +static navdata_port port; static int nav_fd; int navdata_init() { - port = malloc(sizeof(navdata_port)); - nav_fd = open("/dev/ttyO1", O_RDWR | O_NOCTTY | O_NONBLOCK); if (nav_fd == -1) { perror("navdata_init: Unable to open /dev/ttyO1 - "); return 1; } else { - port->isOpen = 1; + port.isOpen = 1; } fcntl(nav_fd, F_SETFL, 0); //read calls are non blocking @@ -93,10 +91,10 @@ int navdata_init() navdata_imu_available = 0; navdata_baro_available = 0; - port->bytesRead = 0; - port->totalBytesRead = 0; - port->packetsRead = 0; - port->isInitialized = 1; + port.bytesRead = 0; + port.totalBytesRead = 0; + port.packetsRead = 0; + port.isInitialized = 1; previousUltrasoundHeight = 0; @@ -158,7 +156,7 @@ void acquire_baro_calibration() void navdata_close() { - port->isOpen = 0; + port.isOpen = 0; close(nav_fd); } @@ -166,19 +164,19 @@ void navdata_read() { int newbytes = 0; - if (port->isInitialized != 1) + if (port.isInitialized != 1) navdata_init(); - if (port->isOpen != 1) + if (port.isOpen != 1) return; - newbytes = read(nav_fd, port->buffer+port->bytesRead, NAVDATA_BUFFER_SIZE-port->bytesRead); + newbytes = read(nav_fd, port.buffer+port.bytesRead, NAVDATA_BUFFER_SIZE-port.bytesRead); // because non-blocking read returns -1 when no bytes available if (newbytes > 0) { - port->bytesRead += newbytes; - port->totalBytesRead += newbytes; + port.bytesRead += newbytes; + port.totalBytesRead += newbytes; } } @@ -241,15 +239,15 @@ void navdata_update() navdata_read(); // while there is something interesting to do... - while (port->bytesRead >= 60) + while (port.bytesRead >= 60) { - if (port->buffer[0] == NAVDATA_START_BYTE) + if (port.buffer[0] == NAVDATA_START_BYTE) { // if checksum is OK if ( 1 ) // we dont know how to calculate the checksum // if ( navdata_checksum() == 0 ) { - memcpy(navdata, port->buffer, NAVDATA_PACKET_SIZE); + memcpy(navdata, port.buffer, NAVDATA_PACKET_SIZE); // Invert byte order so that TELEMETRY works better uint8_t tmp; @@ -266,7 +264,7 @@ void navdata_update() navdata_imu_available = 1; - port->packetsRead++; + port.packetsRead++; // printf("CCRC=%d, GCRC=%d, error=%d\n", crc, navdata->chksum, abs(crc-navdata->chksum)); //navdata_getHeight(); } @@ -276,13 +274,13 @@ void navdata_update() { // find start byte, copy all data from startbyte to buffer origin, update bytesread uint8_t * pint; - pint = memchr(port->buffer, NAVDATA_START_BYTE, port->bytesRead); + pint = memchr(port.buffer, NAVDATA_START_BYTE, port.bytesRead); if (pint != NULL) { - navdata_CropBuffer(pint - port->buffer); + navdata_CropBuffer(pint - port.buffer); } else { // if the start byte was not found, it means there is junk in the buffer - port->bytesRead = 0; + port.bytesRead = 0; } } } @@ -290,14 +288,14 @@ void navdata_update() void navdata_CropBuffer(int cropsize) { - if (port->bytesRead - cropsize < 0) { + if (port.bytesRead - cropsize < 0) { // TODO think about why the amount of bytes read minus the cropsize gets below zero - printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%p\n", port->bytesRead, cropsize, port->buffer); + printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%p\n", port.bytesRead, cropsize, port.buffer); return; } - memmove(port->buffer, port->buffer+cropsize, NAVDATA_BUFFER_SIZE-cropsize); - port->bytesRead -= cropsize; + memmove(port.buffer, port.buffer+cropsize, NAVDATA_BUFFER_SIZE-cropsize); + port.bytesRead -= cropsize; } int16_t navdata_getHeight() { From 1ba778437ee86facadcc8f8bc4053ed3dddf04dc Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 05:58:07 +0100 Subject: [PATCH 247/309] Hide more private data. --- sw/airborne/boards/ardrone/navdata.c | 4 ++++ sw/airborne/boards/ardrone/navdata.h | 4 ---- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 8c6425bb26..5b2d6bb7c2 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -36,6 +36,10 @@ #include #include "navdata.h" +#define NAVDATA_PACKET_SIZE 60 +#define NAVDATA_BUFFER_SIZE 80 +#define NAVDATA_START_BYTE 0x3a + typedef struct { uint8_t isInitialized; uint8_t isOpen; diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 758f30a151..bd29297d81 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -32,10 +32,6 @@ #include -#define NAVDATA_PACKET_SIZE 60 -#define NAVDATA_BUFFER_SIZE 80 -#define NAVDATA_START_BYTE 0x3a - typedef struct { uint16_t taille; From dfe4469e2ca8c7d1012eab12e3ee1ad70e168086 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:06:27 +0100 Subject: [PATCH 248/309] Writes can be partial, in theory at least (note, all writes are currently length 1). --- sw/airborne/boards/ardrone/navdata.c | 23 ++++++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 5b2d6bb7c2..93e3656f9a 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -52,6 +52,23 @@ typedef struct { static navdata_port port; static int nav_fd; +static void navdata_write(const uint8_t *buf, size_t count) +{ + size_t written = 0; + + while(written < count) + { + ssize_t n = write(nav_fd, buf + written, count - written); + if (n < 0) + { + perror("navdata_write: Write failed"); + // FIXME: what's sensible to do at this point? + return; + } + written += n; + } +} + int navdata_init() { nav_fd = open("/dev/ttyO1", O_RDWR | O_NOCTTY | O_NONBLOCK); @@ -82,14 +99,14 @@ int navdata_init() // stop acquisition uint8_t cmd=0x02; - write(nav_fd, &cmd, 1); + navdata_write(&cmd, 1); baro_calibrated = 0; acquire_baro_calibration(); // start acquisition cmd=0x01; - write(nav_fd, &cmd, 1); + navdata_write(&cmd, 1); navdata = malloc(sizeof(measures_t)); navdata_imu_available = 0; @@ -111,7 +128,7 @@ void acquire_baro_calibration() // start baro calibration acquisition uint8_t cmd=0x17; // send cmd 23 - write(nav_fd, &cmd, 1); + navdata_write(&cmd, 1); uint8_t calibBuffer[22]; int calib_bytes_read, calib_bytes_left, readcount; From c37b9aed4c44a30a3e45ca422aeff8994947cbe4 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:08:51 +0100 Subject: [PATCH 249/309] Read to NULL is not legal. --- sw/airborne/boards/ardrone/navdata.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 93e3656f9a..c57ba6f93c 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -124,7 +124,8 @@ int navdata_init() void acquire_baro_calibration() { - read(nav_fd, NULL, 100); // read some potential dirt + char tmp[100]; + read(nav_fd, tmp, sizeof tmp); // read some potential dirt // start baro calibration acquisition uint8_t cmd=0x17; // send cmd 23 From 1b46a385593fe1af9b4d1c460b6d8bbe1fd0f6c5 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:11:18 +0100 Subject: [PATCH 250/309] Retry blocking writes. --- sw/airborne/boards/ardrone/navdata.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index c57ba6f93c..c3b502efdf 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -34,6 +34,7 @@ #include #include #include +#include #include "navdata.h" #define NAVDATA_PACKET_SIZE 60 @@ -61,6 +62,8 @@ static void navdata_write(const uint8_t *buf, size_t count) ssize_t n = write(nav_fd, buf + written, count - written); if (n < 0) { + if (errno == EAGAIN || errno == EWOULDBLOCK) + continue; perror("navdata_write: Write failed"); // FIXME: what's sensible to do at this point? return; From 888b877f6e31b4a8059416a6c202d25b0f179975 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:13:47 +0100 Subject: [PATCH 251/309] baro_update_logic() can be static. --- sw/airborne/boards/ardrone/navdata.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index c3b502efdf..a0907a9bde 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -205,8 +205,7 @@ void navdata_read() } } -void baro_update_logic(void); -void baro_update_logic(void) +static void baro_update_logic(void) { static int32_t lastpressval = 0; static uint16_t lasttempval = 0; From aa1bf02200aafe00ef3d77fce0825b96b332c1e2 Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:14:53 +0100 Subject: [PATCH 252/309] Use constants consistently. --- sw/airborne/boards/ardrone/navdata.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index a0907a9bde..baa9332cc8 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -263,7 +263,7 @@ void navdata_update() navdata_read(); // while there is something interesting to do... - while (port.bytesRead >= 60) + while (port.bytesRead >= NAVDATA_PACKET_SIZE) { if (port.buffer[0] == NAVDATA_START_BYTE) { @@ -292,7 +292,7 @@ void navdata_update() // printf("CCRC=%d, GCRC=%d, error=%d\n", crc, navdata->chksum, abs(crc-navdata->chksum)); //navdata_getHeight(); } - navdata_CropBuffer(60); + navdata_CropBuffer(NAVDATA_PACKET_SIZE); } else { From 0726043ac0daa5a57f1fa18cf5757c429650ffdf Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:16:06 +0100 Subject: [PATCH 253/309] navdata had better be the same size as a packet. --- sw/airborne/boards/ardrone/navdata.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index baa9332cc8..69a1d66463 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -35,6 +35,7 @@ #include #include #include +#include #include "navdata.h" #define NAVDATA_PACKET_SIZE 60 @@ -271,6 +272,7 @@ void navdata_update() if ( 1 ) // we dont know how to calculate the checksum // if ( navdata_checksum() == 0 ) { + assert(sizeof navdata == NAVDATA_PACKET_SIZE); memcpy(navdata, port.buffer, NAVDATA_PACKET_SIZE); // Invert byte order so that TELEMETRY works better From 508f5ebb408c4680b51a1204750d8f272207d16e Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 06:31:14 +0100 Subject: [PATCH 254/309] |navdata| does not need to be dynamically allocated. --- sw/airborne/boards/ardrone/baro_board.c | 4 +- sw/airborne/boards/ardrone/navdata.c | 73 ++++++++++--------- sw/airborne/boards/ardrone/navdata.h | 2 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 56 +++++++------- sw/airborne/subsystems/imu/imu_ardrone2_raw.h | 6 +- 5 files changed, 71 insertions(+), 70 deletions(-) diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index 4320e0a3a1..9b05dad93a 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -77,8 +77,8 @@ void process_ardrone_baro(void) { if(baro.status == BS_RUNNING) { // first read temperature because pressure calibration depends on temperature - baro.differential = baro_apply_calibration_temp(navdata->temperature_pressure); // We store the temperature in Baro-Diff - baro.absolute = baro_apply_calibration(navdata->pressure); + baro.differential = baro_apply_calibration_temp(navdata.temperature_pressure); // We store the temperature in Baro-Diff + baro.absolute = baro_apply_calibration(navdata.pressure); } else { if (baro_calibrated == TRUE) { diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 69a1d66463..4f6b9d36c5 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -54,6 +54,8 @@ typedef struct { static navdata_port port; static int nav_fd; +measures_t navdata; + static void navdata_write(const uint8_t *buf, size_t count) { size_t written = 0; @@ -112,7 +114,6 @@ int navdata_init() cmd=0x01; navdata_write(&cmd, 1); - navdata = malloc(sizeof(measures_t)); navdata_imu_available = 0; navdata_baro_available = 0; @@ -223,7 +224,7 @@ static void baro_update_logic(void) if (lastpressval != 0) { // If pressure was updated: this is a sync error - if (lastpressval != navdata->pressure) + if (lastpressval != navdata.pressure) { // wait for temp again temp_or_press_was_updated_last = 0; @@ -241,7 +242,7 @@ static void baro_update_logic(void) if (lasttempval != 0) { // If temp was updated: this is a sync error - if (lasttempval != navdata->temperature_pressure) + if (lasttempval != navdata.temperature_pressure) { // wait for press again temp_or_press_was_updated_last = 1; @@ -252,8 +253,8 @@ static void baro_update_logic(void) navdata_baro_available = 1; } - lastpressval = navdata->pressure; - lasttempval = navdata->temperature_pressure; + lastpressval = navdata.pressure; + lasttempval = navdata.temperature_pressure; // debug // navdata->temperature_pressure = sync_errors; @@ -273,15 +274,15 @@ void navdata_update() // if ( navdata_checksum() == 0 ) { assert(sizeof navdata == NAVDATA_PACKET_SIZE); - memcpy(navdata, port.buffer, NAVDATA_PACKET_SIZE); + memcpy(&navdata, port.buffer, NAVDATA_PACKET_SIZE); // Invert byte order so that TELEMETRY works better uint8_t tmp; - uint8_t* p = (uint8_t*) &(navdata->pressure); + uint8_t* p = (uint8_t*) &(navdata.pressure); tmp = p[0]; p[0] = p[1]; p[1] = tmp; - p = (uint8_t*) &(navdata->temperature_pressure); + p = (uint8_t*) &(navdata.temperature_pressure); tmp = p[0]; p[0] = p[1]; p[1] = tmp; @@ -326,13 +327,13 @@ void navdata_CropBuffer(int cropsize) int16_t navdata_getHeight() { - if (navdata->ultrasound > 10000) { + if (navdata.ultrasound > 10000) { return previousUltrasoundHeight; } int16_t ultrasoundHeight = 0; - ultrasoundHeight = (navdata->ultrasound - 880) / 26.553; + ultrasoundHeight = (navdata.ultrasound - 880) / 26.553; previousUltrasoundHeight = ultrasoundHeight; @@ -342,32 +343,32 @@ int16_t navdata_getHeight() { // The checksum should be calculated here: we don't know the algorithm uint16_t navdata_checksum() { navdata_cks = 0; - navdata_cks += navdata->nu_trame; - navdata_cks += navdata->ax; - navdata_cks += navdata->ay; - navdata_cks += navdata->az; - navdata_cks += navdata->vx; - navdata_cks += navdata->vy; - navdata_cks += navdata->vz; - navdata_cks += navdata->temperature_acc; - navdata_cks += navdata->temperature_gyro; - navdata_cks += navdata->ultrasound; - navdata_cks += navdata->us_debut_echo; - navdata_cks += navdata->us_fin_echo; - navdata_cks += navdata->us_association_echo; - navdata_cks += navdata->us_distance_echo; - navdata_cks += navdata->us_curve_time; - navdata_cks += navdata->us_curve_value; - navdata_cks += navdata->us_curve_ref; - navdata_cks += navdata->nb_echo; - navdata_cks += navdata->sum_echo; - navdata_cks += navdata->gradient; - navdata_cks += navdata->flag_echo_ini; - navdata_cks += navdata->pressure; - navdata_cks += navdata->temperature_pressure; - navdata_cks += navdata->mx; - navdata_cks += navdata->my; - navdata_cks += navdata->mz; + navdata_cks += navdata.nu_trame; + navdata_cks += navdata.ax; + navdata_cks += navdata.ay; + navdata_cks += navdata.az; + navdata_cks += navdata.vx; + navdata_cks += navdata.vy; + navdata_cks += navdata.vz; + navdata_cks += navdata.temperature_acc; + navdata_cks += navdata.temperature_gyro; + navdata_cks += navdata.ultrasound; + navdata_cks += navdata.us_debut_echo; + navdata_cks += navdata.us_fin_echo; + navdata_cks += navdata.us_association_echo; + navdata_cks += navdata.us_distance_echo; + navdata_cks += navdata.us_curve_time; + navdata_cks += navdata.us_curve_value; + navdata_cks += navdata.us_curve_ref; + navdata_cks += navdata.nb_echo; + navdata_cks += navdata.sum_echo; + navdata_cks += navdata.gradient; + navdata_cks += navdata.flag_echo_ini; + navdata_cks += navdata.pressure; + navdata_cks += navdata.temperature_pressure; + navdata_cks += navdata.mx; + navdata_cks += navdata.my; + navdata_cks += navdata.mz; // navdata_cks += navdata->chksum; return 0; // we dont know how to calculate the checksum diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index bd29297d81..1238663049 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -94,7 +94,7 @@ struct bmp180_baro_calibration int32_t b5; }; -measures_t* navdata; +extern measures_t navdata; struct bmp180_baro_calibration baro_calibration; uint16_t navdata_cks; uint8_t navdata_imu_available; diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 4891f0a0df..5a6916b984 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -956,34 +956,34 @@ #ifdef ARDRONE2_RAW #include "navdata.h" #define PERIODIC_SEND_ARDRONE_NAVDATA(_trans, _dev) DOWNLINK_SEND_ARDRONE_NAVDATA(_trans, _dev, \ - &navdata->taille, \ - &navdata->nu_trame, \ - &navdata->ax, \ - &navdata->ay, \ - &navdata->az, \ - &navdata->vx, \ - &navdata->vy, \ - &navdata->vz, \ - &navdata->temperature_acc, \ - &navdata->temperature_gyro, \ - &navdata->ultrasound, \ - &navdata->us_debut_echo, \ - &navdata->us_fin_echo, \ - &navdata->us_association_echo, \ - &navdata->us_distance_echo, \ - &navdata->us_curve_time, \ - &navdata->us_curve_value, \ - &navdata->us_curve_ref, \ - &navdata->nb_echo, \ - &navdata->sum_echo, \ - &navdata->gradient, \ - &navdata->flag_echo_ini, \ - &navdata->pressure, \ - &navdata->temperature_pressure, \ - &navdata->mx, \ - &navdata->my, \ - &navdata->mz, \ - &navdata->chksum \ + &navdata.taille, \ + &navdata.nu_trame, \ + &navdata.ax, \ + &navdata.ay, \ + &navdata.az, \ + &navdata.vx, \ + &navdata.vy, \ + &navdata.vz, \ + &navdata.temperature_acc, \ + &navdata.temperature_gyro, \ + &navdata.ultrasound, \ + &navdata.us_debut_echo, \ + &navdata.us_fin_echo, \ + &navdata.us_association_echo, \ + &navdata.us_distance_echo, \ + &navdata.us_curve_time, \ + &navdata.us_curve_value, \ + &navdata.us_curve_ref, \ + &navdata.nb_echo, \ + &navdata.sum_echo, \ + &navdata.gradient, \ + &navdata.flag_echo_ini, \ + &navdata.pressure, \ + &navdata.temperature_pressure, \ + &navdata.mx, \ + &navdata.my, \ + &navdata.mz, \ + &navdata.chksum \ ) #else #define PERIODIC_SEND_ARDRONE_NAVDATA(_trans, _dev) {} diff --git a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h index 18b1b1bbad..cbc7c33b19 100644 --- a/sw/airborne/subsystems/imu/imu_ardrone2_raw.h +++ b/sw/airborne/subsystems/imu/imu_ardrone2_raw.h @@ -116,9 +116,9 @@ static inline void imu_ardrone2_event ( void (* _gyro_handler)(void), void (* _a //checks if the navboard has a new dataset ready if (navdata_imu_available == TRUE) { navdata_imu_available = FALSE; - RATES_ASSIGN(imu.gyro_unscaled, navdata->vx, -navdata->vy, -navdata->vz); - VECT3_ASSIGN(imu.accel_unscaled, navdata->ax, 4096-navdata->ay, 4096-navdata->az); - VECT3_ASSIGN(imu.mag_unscaled, -navdata->mx, -navdata->my, -navdata->mz); + RATES_ASSIGN(imu.gyro_unscaled, navdata.vx, -navdata.vy, -navdata.vz); + VECT3_ASSIGN(imu.accel_unscaled, navdata.ax, 4096-navdata.ay, 4096-navdata.az); + VECT3_ASSIGN(imu.mag_unscaled, -navdata.mx, -navdata.my, -navdata.mz); _gyro_handler(); _accel_handler(); From 23a92996ee3434e5166794bc2fa2e7ec19ff82ef Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 13:26:10 +0100 Subject: [PATCH 255/309] Make sure writes complete. --- .../boards/ardrone/actuators_ardrone2_raw.c | 11 ++++++++--- sw/airborne/boards/ardrone/navdata.c | 16 +++++++++++----- sw/airborne/boards/ardrone/navdata.h | 3 +++ 3 files changed, 22 insertions(+), 8 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index 7c8cd2e8c4..e3923927f4 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -33,6 +33,7 @@ #include "mcu_periph/gpio.h" #include "led_hw.h" #include "mcu_periph/sys_time.h" +#include "navdata.h" // for full_write #include /* Standard input/output definitions */ #include /* String function definitions */ @@ -157,7 +158,11 @@ void actuators_ardrone_init(void) } int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) { - write(actuator_ardrone2_raw_fd, &cmd, 1); + if (full_write(actuator_ardrone2_raw_fd, &cmd, 1) < 0) + { + perror("actuators_ardrone_cmd: write failed"); + return -1; + } return read(actuator_ardrone2_raw_fd, reply, replylen); } @@ -241,7 +246,7 @@ void actuators_ardrone_set_pwm(uint16_t pwm0, uint16_t pwm1, uint16_t pwm2, uint cmd[2] = ((pwm1&0x1ff)<<3) | ((pwm2&0x1ff)>>6); cmd[3] = ((pwm2&0x1ff)<<2) | ((pwm3&0x1ff)>>7); cmd[4] = ((pwm3&0x1ff)<<1); - write(actuator_ardrone2_raw_fd, cmd, 5); + full_write(actuator_ardrone2_raw_fd, cmd, 5); RunOnceEvery(20,actuators_ardrone_led_run()); } @@ -270,7 +275,7 @@ void actuators_ardrone_set_leds(uint8_t led0, uint8_t led1, uint8_t led2, uint8_ cmd[0]=0x60 | ((led0&1)<<4) | ((led1&1)<<3) | ((led2&1)<<2) | ((led3&1) <<1); cmd[1]=((led0&2)<<3) | ((led1&2)<<2) | ((led2&2)<<1) | ((led3&2)<<0); - write(actuator_ardrone2_raw_fd, cmd, 2); + full_write(actuator_ardrone2_raw_fd, cmd, 2); } void actuators_ardrone_close(void) diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 4f6b9d36c5..53324dfd51 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -56,23 +56,29 @@ static int nav_fd; measures_t navdata; -static void navdata_write(const uint8_t *buf, size_t count) +// FIXME(ben): there must be a better home for this +ssize_t full_write(int fd, const uint8_t *buf, size_t count) { size_t written = 0; while(written < count) { - ssize_t n = write(nav_fd, buf + written, count - written); + ssize_t n = write(fd, buf + written, count - written); if (n < 0) { if (errno == EAGAIN || errno == EWOULDBLOCK) continue; - perror("navdata_write: Write failed"); - // FIXME: what's sensible to do at this point? - return; + return n; } written += n; } + return written; +} + +static void navdata_write(const uint8_t *buf, size_t count) +{ + if (full_write(nav_fd, buf, count) < 0) + perror("navdata_write: Write failed"); } int navdata_init() diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 1238663049..2201807cac 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -31,6 +31,7 @@ #define NAVDATA_H_ #include +#include typedef struct { @@ -114,4 +115,6 @@ int16_t navdata_getHeight(void); void acquire_baro_calibration(void); +ssize_t full_write(int fd, const uint8_t *buf, size_t count); + #endif /* NAVDATA_H_ */ From 7efc5d98935228c79dde710ca2b81bafa69f06fb Mon Sep 17 00:00:00 2001 From: Ben Laurie Date: Sun, 8 Sep 2013 19:55:09 +0100 Subject: [PATCH 256/309] Add full_read(). --- .../boards/ardrone/actuators_ardrone2_raw.c | 2 +- sw/airborne/boards/ardrone/navdata.c | 37 ++++++++++++------- sw/airborne/boards/ardrone/navdata.h | 1 + 3 files changed, 26 insertions(+), 14 deletions(-) diff --git a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c index e3923927f4..b7ea3f9cae 100644 --- a/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c +++ b/sw/airborne/boards/ardrone/actuators_ardrone2_raw.c @@ -163,7 +163,7 @@ int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) { perror("actuators_ardrone_cmd: write failed"); return -1; } - return read(actuator_ardrone2_raw_fd, reply, replylen); + return full_read(actuator_ardrone2_raw_fd, reply, replylen); } #include "autopilot.h" diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 53324dfd51..1ddd68a5aa 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -56,7 +56,7 @@ static int nav_fd; measures_t navdata; -// FIXME(ben): there must be a better home for this +// FIXME(ben): there must be a better home for these ssize_t full_write(int fd, const uint8_t *buf, size_t count) { size_t written = 0; @@ -75,6 +75,25 @@ ssize_t full_write(int fd, const uint8_t *buf, size_t count) return written; } +ssize_t full_read(int fd, uint8_t *buf, size_t count) +{ + // Apologies for illiteracy, but we can't overload |read|. + size_t readed = 0; + + while(readed < count) + { + ssize_t n = read(fd, buf + readed, count - readed); + if (n < 0) + { + if (errno == EAGAIN || errno == EWOULDBLOCK) + continue; + return n; + } + readed += n; + } + return readed; +} + static void navdata_write(const uint8_t *buf, size_t count) { if (full_write(nav_fd, buf, count) < 0) @@ -143,17 +162,11 @@ void acquire_baro_calibration() navdata_write(&cmd, 1); uint8_t calibBuffer[22]; - int calib_bytes_read, calib_bytes_left, readcount; - calib_bytes_read = 0; - calib_bytes_left = 22; - readcount = 0; - while(calib_bytes_read != 22) { - readcount = read(nav_fd, calibBuffer+(22-calib_bytes_left), calib_bytes_left); - if (readcount > 0) { - calib_bytes_read += readcount; - calib_bytes_left -= readcount; - } + if (full_read(nav_fd, calibBuffer, sizeof calibBuffer) < 0) + { + perror("acquire_baro_calibration: read failed"); + return; } baro_calibration.ac1 = calibBuffer[0] << 8 | calibBuffer[1]; @@ -168,8 +181,6 @@ void acquire_baro_calibration() baro_calibration.mc = calibBuffer[18] << 8 | calibBuffer[19]; baro_calibration.md = calibBuffer[20] << 8 | calibBuffer[21]; - printf("Calibration bytes read: %d\n", calib_bytes_read); - printf("Calibration AC1: %d\n", baro_calibration.ac1); printf("Calibration AC2: %d\n", baro_calibration.ac2); printf("Calibration AC3: %d\n", baro_calibration.ac3); diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 2201807cac..dd3b36f68b 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -116,5 +116,6 @@ int16_t navdata_getHeight(void); void acquire_baro_calibration(void); ssize_t full_write(int fd, const uint8_t *buf, size_t count); +ssize_t full_read(int fd, uint8_t *buf, size_t count); #endif /* NAVDATA_H_ */ From b2e433c48279b89cd51ba18cbd8ac844f1c11c7c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 9 Sep 2013 11:40:08 +0200 Subject: [PATCH 257/309] [conf][subsystems] more robust/configurable x_I2C_DEV --- .../shared/actuators_asctec.makefile | 33 ++++++++++--- .../shared/actuators_asctec_v2.makefile | 34 ++++++++++--- .../subsystems/shared/actuators_mkk.makefile | 38 +++++++++----- .../shared/actuators_mkk_v2.makefile | 37 +++++++++----- .../shared/actuators_skiron.makefile | 35 ++++++++++--- .../shared/imu_aspirin2_i2c.makefile | 29 ++++++++--- .../shared/imu_aspirin_common.makefile | 49 +++++++++++++------ .../shared/imu_aspirin_i2c_common.makefile | 17 ++++--- .../shared/imu_drotek_10dof_v2.makefile | 15 +++--- .../subsystems/shared/imu_gl1.makefile | 15 +++--- 10 files changed, 214 insertions(+), 88 deletions(-) diff --git a/conf/firmwares/subsystems/shared/actuators_asctec.makefile b/conf/firmwares/subsystems/shared/actuators_asctec.makefile index be5d0707ff..3999cd534f 100644 --- a/conf/firmwares/subsystems/shared/actuators_asctec.makefile +++ b/conf/firmwares/subsystems/shared/actuators_asctec.makefile @@ -7,17 +7,36 @@ # $(TARGET).CFLAGS += -DACTUATORS -ap.srcs += subsystems/actuators/actuators_asctec.c +ACTUATORS_ASCTEC_SRCS = subsystems/actuators/actuators_asctec.c + + +# set default i2c device if not already configured +ifeq ($(ARCH), lpc21) +ACTUATORS_ASCTEC_I2C_DEV ?= i2c0 +else ifeq ($(ARCH), stm32) +ACTUATORS_ASCTEC_I2C_DEV ?= i2c1 +endif + +ifndef ACTUATORS_ASCTEC_I2C_DEV +$(error Error: ACTUATORS_ASCTEC_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +ACTUATORS_ASCTEC_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_ASCTEC_I2C_DEV) | tr a-z A-Z) +ACTUATORS_ASCTEC_I2C_DEV_LOWER=$(shell echo $(ACTUATORS_ASCTEC_I2C_DEV) | tr A-Z a-z) + +ACTUATORS_ASCTEC_CFLAGS += -DACTUATORS_ASCTEC_I2C_DEV=$(ACTUATORS_ASCTEC_I2C_DEV_LOWER) +ACTUATORS_ASCTEC_CFLAGS += -DUSE_$(ACTUATORS_ASCTEC_I2C_DEV_UPPER) ifeq ($(ARCH), lpc21) -ap.CFLAGS += -DACTUATORS_ASCTEC_I2C_DEV=i2c0 -ap.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 +# set default i2c timing if not already configured +ACTUATORS_ASCTEC_I2C_SCL_TIME ?= 150 +ACTUATORS_ASCTEC_CFLAGS += -D$(ACTUATORS_ASCTEC_I2C_DEV_UPPER)_SCLL=$(ACTUATORS_ASCTEC_I2C_SCL_TIME) +ACTUATORS_ASCTEC_CFLAGS += -D$(ACTUATORS_ASCTEC_I2C_DEV_UPPER)_SCLH=$(ACTUATORS_ASCTEC_I2C_SCL_TIME) endif -ifeq ($(ARCH), stm32) -ap.CFLAGS += -DACTUATORS_ASCTEC_I2C_DEV=i2c1 -ap.CFLAGS += -DUSE_I2C1 -endif +ap.CFLAGS += $(ACTUATORS_ASCTEC_CFLAGS) +ap.srcs += $(ACTUATORS_ASCTEC_SRCS) # Simulator diff --git a/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile b/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile index c2f8807796..9fb199d237 100644 --- a/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile +++ b/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile @@ -7,17 +7,37 @@ # $(TARGET).CFLAGS += -DACTUATORS -ap.srcs += subsystems/actuators/actuators_asctec_v2.c +ACTUATORS_ASCTEC_SRCS = subsystems/actuators/actuators_asctec_v2.c + + +# set default i2c device if not already configured +ifeq ($(ARCH), lpc21) +ACTUATORS_ASCTEC_V2_I2C_DEV ?= i2c0 +else ifeq ($(ARCH), stm32) +ACTUATORS_ASCTEC_V2_I2C_DEV ?= i2c1 +endif + +ifndef ACTUATORS_ASCTEC_V2_I2C_DEV +$(error Error: ACTUATORS_ASCTEC_V2_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +ACTUATORS_ASCTEC_V2_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_ASCTEC_V2_I2C_DEV) | tr a-z A-Z) +ACTUATORS_ASCTEC_V2_I2C_DEV_LOWER=$(shell echo $(ACTUATORS_ASCTEC_V2_I2C_DEV) | tr A-Z a-z) + +ACTUATORS_ASCTEC_V2_CFLAGS += -DACTUATORS_ASCTEC_V2_I2C_DEV=$(ACTUATORS_ASCTEC_V2_I2C_DEV_LOWER) +ACTUATORS_ASCTEC_V2_CFLAGS += -DUSE_$(ACTUATORS_ASCTEC_V2_I2C_DEV_UPPER) ifeq ($(ARCH), lpc21) -ap.CFLAGS += -DACTUATORS_ASCTEC_V2_I2C_DEV=i2c0 -ap.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 +# set default i2c timing if not already configured +ACTUATORS_ASCTEC_V2_I2C_SCL_TIME ?= 150 +ACTUATORS_ASCTEC_V2_CFLAGS += -D$(ACTUATORS_ASCTEC_V2_I2C_DEV_UPPER)_SCLL=$(ACTUATORS_ASCTEC_V2_I2C_SCL_TIME) +ACTUATORS_ASCTEC_V2_CFLAGS += -D$(ACTUATORS_ASCTEC_V2_I2C_DEV_UPPER)_SCLH=$(ACTUATORS_ASCTEC_V2_I2C_SCL_TIME) endif -ifeq ($(ARCH), stm32) -ap.CFLAGS += -DACTUATORS_ASCTEC_V2_I2C_DEV=i2c1 -ap.CFLAGS += -DUSE_I2C1 -endif +ap.CFLAGS += $(ACTUATORS_ASCTEC_V2_CFLAGS) +ap.srcs += $(ACTUATORS_ASCTEC_V2_SRCS) + # Simulator diff --git a/conf/firmwares/subsystems/shared/actuators_mkk.makefile b/conf/firmwares/subsystems/shared/actuators_mkk.makefile index e602f595fa..bc95bc3e89 100644 --- a/conf/firmwares/subsystems/shared/actuators_mkk.makefile +++ b/conf/firmwares/subsystems/shared/actuators_mkk.makefile @@ -22,23 +22,37 @@ # max command = 255 $(TARGET).CFLAGS += -DACTUATORS -ap.srcs += subsystems/actuators/actuators_mkk.c + +ACTUATORS_MKK_SRCS = subsystems/actuators/actuators_mkk.c + ifeq ($(ARCH), lpc21) - -# set default i2c timing if not already configured -ifeq ($(MKK_I2C_SCL_TIME), ) -MKK_I2C_SCL_TIME=150 -endif - -ap.CFLAGS += -DACTUATORS_MKK_I2C_DEV=i2c0 -ap.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=$(MKK_I2C_SCL_TIME) -DI2C0_SCLH=$(MKK_I2C_SCL_TIME) - +ACTUATORS_MKK_I2C_DEV ?= i2c0 else ifeq ($(ARCH), stm32) -ap.CFLAGS += -DACTUATORS_MKK_I2C_DEV=i2c1 -ap.CFLAGS += -DUSE_I2C1 +ACTUATORS_MKK_I2C_DEV ?= i2c1 endif +ifndef ACTUATORS_MKK_I2C_DEV +$(error Error: ACTUATORS_MKK_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +ACTUATORS_MKK_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_MKK_I2C_DEV) | tr a-z A-Z) +ACTUATORS_MKK_I2C_DEV_LOWER=$(shell echo $(ACTUATORS_MKK_I2C_DEV) | tr A-Z a-z) + +ACTUATORS_MKK_CFLAGS += -DACTUATORS_MKK_I2C_DEV=$(ACTUATORS_MKK_I2C_DEV_LOWER) +ACTUATORS_MKK_CFLAGS += -DUSE_$(ACTUATORS_MKK_I2C_DEV_UPPER) + +ifeq ($(ARCH), lpc21) +# set default i2c timing if not already configured +ACTUATORS_MKK_I2C_SCL_TIME ?= 150 +ACTUATORS_MKK_CFLAGS += -D$(ACTUATORS_MKK_I2C_DEV_UPPER)_SCLL=$(ACTUATORS_MKK_I2C_SCL_TIME) +ACTUATORS_MKK_CFLAGS += -D$(ACTUATORS_MKK_I2C_DEV_UPPER)_SCLH=$(ACTUATORS_MKK_I2C_SCL_TIME) +endif + +ap.CFLAGS += $(ACTUATORS_MKK_CFLAGS) +ap.srcs += $(ACTUATORS_MKK_SRCS) + # Simulator nps.srcs += subsystems/actuators/actuators_mkk.c nps.CFLAGS += -DUSE_I2C0 -DACTUATORS_MKK_I2C_DEV=i2c0 diff --git a/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile b/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile index 4246e1b90a..f07b44b114 100644 --- a/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile +++ b/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile @@ -22,23 +22,36 @@ # max command = 2047 $(TARGET).CFLAGS += -DACTUATORS -ap.srcs += subsystems/actuators/actuators_mkk_v2.c +ACTUATORS_MKK_V2_SRCS = subsystems/actuators/actuators_mkk_v2.c + ifeq ($(ARCH), lpc21) - -# set default i2c timing if not already configured -ifeq ($(MKK_V2_I2C_SCL_TIME), ) -MKK_V2_I2C2_SCL_TIME=150 -endif - -ap.CFLAGS += -DACTUATORS_MKK_V2_I2C_DEV=i2c0 -ap.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=$(MKK_V2_I2C_SCL_TIME) -DI2C0_SCLH=$(MKK_V2_I2C_SCL_TIME) - +ACTUATORS_MKK_V2_I2C_DEV ?= i2c0 else ifeq ($(ARCH), stm32) -ap.CFLAGS += -DACTUATORS_MKK_V2_I2C_DEV=i2c1 -ap.CFLAGS += -DUSE_I2C1 +ACTUATORS_MKK_V2_I2C_DEV ?= i2c1 endif +ifndef ACTUATORS_MKK_V2_I2C_DEV +$(error Error: ACTUATORS_MKK_V2_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +ACTUATORS_MKK_V2_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_MKK_V2_I2C_DEV) | tr a-z A-Z) +ACTUATORS_MKK_V2_I2C_DEV_LOWER=$(shell echo $(ACTUATORS_MKK_V2_I2C_DEV) | tr A-Z a-z) + +ACTUATORS_MKK_V2_CFLAGS += -DACTUATORS_MKK_V2_I2C_DEV=$(ACTUATORS_MKK_V2_I2C_DEV_LOWER) +ACTUATORS_MKK_V2_CFLAGS += -DUSE_$(ACTUATORS_MKK_V2_I2C_DEV_UPPER) + +ifeq ($(ARCH), lpc21) +# set default i2c timing if not already configured +ACTUATORS_MKK_V2_I2C_SCL_TIME ?= 150 +ACTUATORS_MKK_V2_CFLAGS += -D$(ACTUATORS_MKK_V2_I2C_DEV_UPPER)_SCLL=$(ACTUATORS_MKK_V2_I2C_SCL_TIME) +ACTUATORS_MKK_V2_CFLAGS += -D$(ACTUATORS_MKK_V2_I2C_DEV_UPPER)_SCLH=$(ACTUATORS_MKK_V2_I2C_SCL_TIME) +endif + +ap.CFLAGS += $(ACTUATORS_MKK_V2_CFLAGS) +ap.srcs += $(ACTUATORS_MKK_V2_SRCS) + # Simulator: nps.srcs += subsystems/actuators/actuators_mkk_v2.c nps.CFLAGS += -DUSE_I2C0 -DACTUATORS_MKK_V2_I2C_DEV=i2c0 diff --git a/conf/firmwares/subsystems/shared/actuators_skiron.makefile b/conf/firmwares/subsystems/shared/actuators_skiron.makefile index 5296056e43..f52b46c57d 100644 --- a/conf/firmwares/subsystems/shared/actuators_skiron.makefile +++ b/conf/firmwares/subsystems/shared/actuators_skiron.makefile @@ -17,20 +17,39 @@ # command_laws section to map motor_mixing commands to servos # -# set default i2c timing if not already configured -ifeq ($(SKIRON_I2C_SCL_TIME), ) -SKIRON_I2C_SCL_TIME=150 +$(TARGET).CFLAGS += -DACTUATORS +ACTUATORS_SKIRON_SRCS = subsystems/actuators/actuators_skiron.c + +# set default i2c device if not already configured +ifeq ($(ARCH), lpc21) +ACTUATORS_SKIRON_I2C_DEV ?= i2c0 +else ifeq ($(ARCH), stm32) +ACTUATORS_SKIRON_I2C_DEV ?= i2c1 endif -$(TARGET).CFLAGS += -DACTUATORS -ap.srcs += subsystems/actuators/actuators_skiron.c +ifndef ACTUATORS_SKIRON_I2C_DEV +$(error Error: ACTUATORS_SKIRON_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +ACTUATORS_SKIRON_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_SKIRON_I2C_DEV) | tr a-z A-Z) +ACTUATORS_SKIRON_I2C_DEV_LOWER=$(shell echo $(ACTUATORS_SKIRON_I2C_DEV) | tr A-Z a-z) + +ACTUATORS_SKIRON_CFLAGS += -DACTUATORS_SKIRON_I2C_DEV=$(ACTUATORS_SKIRON_I2C_DEV_LOWER) +ACTUATORS_SKIRON_CFLAGS += -DUSE_$(ACTUATORS_SKIRON_I2C_DEV_UPPER) ifeq ($(ARCH), lpc21) -ap.CFLAGS += -DACTUATORS_SKIRON_I2C_DEV=i2c0 -ap.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=$(SKIRON_I2C_SCL_TIME) -DI2C0_SCLH=$(SKIRON_I2C_SCL_TIME) +# set default i2c timing if not already configured +ACTUATORS_SKIRON_I2C_SCL_TIME ?= 150 +ACTUATORS_SKIRON_CFLAGS += -D$(ACTUATORS_SKIRON_I2C_DEV_UPPER)_SCLL=$(ACTUATORS_SKIRON_I2C_SCL_TIME) +ACTUATORS_SKIRON_CFLAGS += -D$(ACTUATORS_SKIRON_I2C_DEV_UPPER)_SCLH=$(ACTUATORS_SKIRON_I2C_SCL_TIME) endif +ap.CFLAGS += $(ACTUATORS_SKIRON_CFLAGS) +ap.srcs += $(ACTUATORS_SKIRON_SRCS) + + # Simulator nps.srcs += subsystems/actuators/actuators_skiron.c -nps.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=$(SKIRON_I2C_SCL_TIME) -DI2C0_SCLH=$(SKIRON_I2C_SCL_TIME) -DACTUATORS_SKIRON_I2C_DEV=i2c0 +nps.CFLAGS += -DUSE_I2C0 -DACTUATORS_SKIRON_I2C_DEV=i2c0 diff --git a/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile b/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile index e2cc60d604..d57d03f9cf 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile @@ -7,14 +7,29 @@ IMU_ASPIRIN2_SRCS = $(SRC_SUBSYSTEMS)/imu.c \ $(SRC_MODULES)/sensors/imu_aspirin2.c -IMU_ASPIRIN2_CFLAGS += -DUSE_I2C -ifeq ($(ARCH), stm32) - IMU_ASPIRIN2_CFLAGS += -DUSE_I2C2 - IMU_ASPIRIN2_CFLAGS += -DPPZUAVIMU_I2C_DEV=i2c2 -else ifeq ($(ARCH), lpc21) - IMU_ASPIRIN2_CFLAGS += -DUSE_I2C0 - IMU_ASPIRIN2_CFLAGS += -DPPZUAVIMU_I2C_DEV=i2c0 +# set default i2c bus +ifeq ($(ARCH), lpc21) +IMU_ASPIRIN2_I2C_DEV ?= i2c0 +else ifeq ($(ARCH), stm32) +IMU_ASPIRIN2_I2C_DEV ?= i2c2 endif +ifndef IMU_ASPIRIN2_I2C_DEV +$(error Error: IMU_ASPIRIN2_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +IMU_ASPIRIN2_I2C_DEV_UPPER=$(shell echo $(IMU_ASPIRIN2_I2C_DEV) | tr a-z A-Z) +IMU_ASPIRIN2_I2C_DEV_LOWER=$(shell echo $(IMU_ASPIRIN2_I2C_DEV) | tr A-Z a-z) + +IMU_ASPIRIN2_CFLAGS += -DIMU_ASPIRIN2_I2C_DEV=$(IMU_ASPIRIN2_I2C_DEV_LOWER) +IMU_ASPIRIN2_CFLAGS += -DUSE_$(IMU_ASPIRIN2_I2C_DEV_UPPER) + ap.CFLAGS += $(IMU_ASPIRIN2_CFLAGS) ap.srcs += $(IMU_ASPIRIN2_SRCS) + + +# +# NPS simulator +# +include $(CFG_SHARED)/imu_nps.makefile diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile index a19bb4a2b8..3385d78261 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile @@ -44,29 +44,46 @@ IMU_ASPIRIN_SRCS += peripherals/itg3200.c #IMU_ASPIRIN_SRCS += peripherals/hmc5843.c $(SRC_ARCH)/peripherals/hmc5843_arch.c IMU_ASPIRIN_SRCS += peripherals/hmc58xx.c + +# set default i2c bus ifeq ($(ARCH), lpc21) -IMU_ASPIRIN_CFLAGS += -DUSE_SPI_SLAVE0 -IMU_ASPIRIN_CFLAGS += -DASPIRIN_SPI_SLAVE_IDX=SPI_SLAVE0 -IMU_ASPIRIN_CFLAGS += -DASPIRIN_SPI_DEV=spi1 -IMU_ASPIRIN_CFLAGS += -DUSE_SPI1 -ifndef ASPIRIN_I2C_DEV -ASPIRIN_I2C_DEV=i2c0 -endif +ASPIRIN_I2C_DEV ?= i2c0 else ifeq ($(ARCH), stm32) -IMU_ASPIRIN_CFLAGS += -DUSE_SPI2 +ASPIRIN_I2C_DEV ?= i2c2 +endif + +ifndef ASPIRIN_I2C_DEV +$(error Error: ASPIRIN_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case +ASPIRIN_I2C_DEV_UPPER=$(shell echo $(ASPIRIN_I2C_DEV) | tr a-z A-Z) +ASPIRIN_I2C_DEV_LOWER=$(shell echo $(ASPIRIN_I2C_DEV) | tr A-Z a-z) + +IMU_ASPIRIN_CFLAGS += -DASPIRIN_I2C_DEV=$(ASPIRIN_I2C_DEV_LOWER) +IMU_ASPIRIN_CFLAGS += -DUSE_$(ASPIRIN_I2C_DEV_UPPER) + + +# set default SPI device and slave index +ifeq ($(ARCH), lpc21) +ASPIRIN_SPI_DEV ?= spi1 +ASPIRIN_SPI_SLAVE_IDX ?= SPI_SLAVE0 +else ifeq ($(ARCH), stm32) +ASPIRIN_SPI_DEV ?= spi2 # Slave select configuration # SLAVE2 is on PB12 (NSS) (ADXL345 CS) -IMU_ASPIRIN_CFLAGS += -DUSE_SPI_SLAVE2 -ifndef ASPIRIN_I2C_DEV -ASPIRIN_I2C_DEV=i2c2 -endif +ASPIRIN_SPI_SLAVE_IDX ?= SPI_SLAVE2 endif -# convert i2cx to upper case -ASPIRIN_I2C_DEV_UPPER=$(shell echo $(ASPIRIN_I2C_DEV) | tr a-z A-Z) +# convert spix to upper/lower case +ASPIRIN_SPI_DEV_UPPER=$(shell echo $(ASPIRIN_SPI_DEV) | tr a-z A-Z) +ASPIRIN_SPI_DEV_LOWER=$(shell echo $(ASPIRIN_SPI_DEV) | tr A-Z a-z) + +IMU_ASPIRIN_CFLAGS += -DASPIRIN_SPI_DEV=$(ASPIRIN_SPI_DEV_LOWER) +IMU_ASPIRIN_CFLAGS += -DUSE_$(ASPIRIN_SPI_DEV_UPPER) +IMU_ASPIRIN_CFLAGS += -DASPIRIN_SPI_SLAVE_IDX=$(ASPIRIN_SPI_SLAVE_IDX) +IMU_ASPIRIN_CFLAGS += -DUSE_$(ASPIRIN_SPI_SLAVE_IDX) -IMU_ASPIRIN_CFLAGS += -DASPIRIN_I2C_DEV=$(ASPIRIN_I2C_DEV) -IMU_ASPIRIN_CFLAGS += -DUSE_$(ASPIRIN_I2C_DEV_UPPER) # # NPS simulator diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile index 064ceb3d03..9d45a288c4 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile @@ -38,19 +38,24 @@ IMU_ASPIRIN_SRCS += peripherals/itg3200.c # Magnetometer IMU_ASPIRIN_SRCS += peripherals/hmc58xx.c + # set default i2c bus -ifndef ASPIRIN_I2C_DEV ifeq ($(ARCH), lpc21) -ASPIRIN_I2C_DEV=i2c0 +ASPIRIN_I2C_DEV ?= i2c0 else ifeq ($(ARCH), stm32) -ASPIRIN_I2C_DEV=i2c2 -endif +ASPIRIN_I2C_DEV ?= i2c2 endif -# convert i2cx to upper case +ifndef ASPIRIN_I2C_DEV +$(error Error: ASPIRIN_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case ASPIRIN_I2C_DEV_UPPER=$(shell echo $(ASPIRIN_I2C_DEV) | tr a-z A-Z) +ASPIRIN_I2C_DEV_LOWER=$(shell echo $(ASPIRIN_I2C_DEV) | tr A-Z a-z) -IMU_ASPIRIN_CFLAGS += -DASPIRIN_I2C_DEV=$(ASPIRIN_I2C_DEV) +IMU_ASPIRIN_CFLAGS += -DASPIRIN_I2C_DEV=$(ASPIRIN_I2C_DEV_LOWER) IMU_ASPIRIN_CFLAGS += -DUSE_$(ASPIRIN_I2C_DEV_UPPER) + include $(CFG_SHARED)/imu_nps.makefile diff --git a/conf/firmwares/subsystems/shared/imu_drotek_10dof_v2.makefile b/conf/firmwares/subsystems/shared/imu_drotek_10dof_v2.makefile index b41ec9b741..17c50f6ba2 100644 --- a/conf/firmwares/subsystems/shared/imu_drotek_10dof_v2.makefile +++ b/conf/firmwares/subsystems/shared/imu_drotek_10dof_v2.makefile @@ -53,18 +53,21 @@ IMU_DROTEK_2_SRCS += peripherals/hmc58xx.c # set default i2c bus -ifndef DROTEK_2_I2C_DEV ifeq ($(ARCH), lpc21) -DROTEK_2_I2C_DEV=i2c0 +DROTEK_2_I2C_DEV ?= i2c0 else ifeq ($(ARCH), stm32) -DROTEK_2_I2C_DEV=i2c2 -endif +DROTEK_2_I2C_DEV ?= i2c2 endif -# convert i2cx to upper case +ifndef DROTEK_2_I2C_DEV +$(error Error: DROTEK_2_I2C_DEV not configured!) +endif + +# convert i2cx to upper/lower case DROTEK_2_I2C_DEV_UPPER=$(shell echo $(DROTEK_2_I2C_DEV) | tr a-z A-Z) +DROTEK_2_I2C_DEV_LOWER=$(shell echo $(DROTEK_2_I2C_DEV) | tr A-Z a-z) -IMU_DROTEK_2_CFLAGS += -DDROTEK_2_I2C_DEV=$(DROTEK_2_I2C_DEV) +IMU_DROTEK_2_CFLAGS += -DDROTEK_2_I2C_DEV=$(DROTEK_2_I2C_DEV_LOWER) IMU_DROTEK_2_CFLAGS += -DUSE_$(DROTEK_2_I2C_DEV_UPPER) diff --git a/conf/firmwares/subsystems/shared/imu_gl1.makefile b/conf/firmwares/subsystems/shared/imu_gl1.makefile index 041f92f684..18107c5c9f 100644 --- a/conf/firmwares/subsystems/shared/imu_gl1.makefile +++ b/conf/firmwares/subsystems/shared/imu_gl1.makefile @@ -23,19 +23,20 @@ IMU_GL1_SRCS += peripherals/l3g4200.c IMU_GL1_SRCS += peripherals/hmc58xx.c ifeq ($(ARCH), lpc21) -ifndef GL1_I2C_DEV -GL1_I2C_DEV=i2c0 -endif +GL1_I2C_DEV ?= i2c0 else ifeq ($(ARCH), stm32) +GL1_I2C_DEV ?= i2c2 +endif + ifndef GL1_I2C_DEV -GL1_I2C_DEV=i2c2 -endif +$(error Error: GL1_I2C_DEV not configured!) endif -# convert i2cx to upper case +# convert i2cx to upper/lower case GL1_I2C_DEV_UPPER=$(shell echo $(GL1_I2C_DEV) | tr a-z A-Z) +GL1_I2C_DEV_LOWER=$(shell echo $(GL1_I2C_DEV) | tr A-Z a-z) -IMU_GL1_CFLAGS += -DGL1_I2C_DEV=$(GL1_I2C_DEV) +IMU_GL1_CFLAGS += -DGL1_I2C_DEV=$(GL1_I2C_DEV_LOWER) IMU_GL1_CFLAGS += -DUSE_$(GL1_I2C_DEV_UPPER) # Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets From e2e66c909edaaf77ac18d8d7140f285637076c83 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 9 Sep 2013 15:24:31 +0200 Subject: [PATCH 258/309] [messages] Vision Update --- conf/messages.xml | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index 0704620416..1e38778f87 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -629,8 +629,14 @@ - - + + + + + + + + From b0997d4a4838320a86f48f45d2457b5327a86816 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 9 Sep 2013 15:42:30 +0200 Subject: [PATCH 259/309] remove paparazzi-omap package from README --- README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/README.md b/README.md index 8400e0d98a..86ced4a95d 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,6 @@ Debian users can use http://paparazzi.enac.fr/debian - **paparazzi-dev** is the meta-package that depends on everything needed to compile and run the ground segment and the simulator. - **paparazzi-arm-multilib** ARM cross-compiling toolchain for LPC21 and STM32 based boards. -- **paparazzi-omap** toolchain for the optional Gumstix Overo module available on lisa/L. - **paparazzi-jsbsim** is needed for using JSBSim as flight dynamic model for the simulator. @@ -66,4 +65,4 @@ Uploading of the embedded software Flight ------ -1. From the Paparazzi Center, select the flight session and ... do the same than in simulation ! \ No newline at end of file +1. From the Paparazzi Center, select the flight session and ... do the same than in simulation ! From db924c7902efff133657a7c942cea23e0f35302b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 9 Sep 2013 15:34:20 +0200 Subject: [PATCH 260/309] [conf][subsystem] only error if devices not configured for ap target --- .../subsystems/shared/actuators_asctec.makefile | 2 ++ .../shared/actuators_asctec_v2.makefile | 2 ++ .../subsystems/shared/actuators_mkk.makefile | 2 ++ .../subsystems/shared/actuators_mkk_v2.makefile | 2 ++ .../subsystems/shared/actuators_skiron.makefile | 2 ++ .../subsystems/shared/imu_aspirin2_i2c.makefile | 2 ++ .../shared/imu_aspirin_common.makefile | 11 +++++++++++ .../shared/imu_aspirin_i2c_common.makefile | 2 ++ .../shared/imu_aspirin_v2_common.makefile | 17 +++++++++-------- 9 files changed, 34 insertions(+), 8 deletions(-) diff --git a/conf/firmwares/subsystems/shared/actuators_asctec.makefile b/conf/firmwares/subsystems/shared/actuators_asctec.makefile index 3999cd534f..5551d61262 100644 --- a/conf/firmwares/subsystems/shared/actuators_asctec.makefile +++ b/conf/firmwares/subsystems/shared/actuators_asctec.makefile @@ -17,9 +17,11 @@ else ifeq ($(ARCH), stm32) ACTUATORS_ASCTEC_I2C_DEV ?= i2c1 endif +ifeq ($(TARGET), ap) ifndef ACTUATORS_ASCTEC_I2C_DEV $(error Error: ACTUATORS_ASCTEC_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ACTUATORS_ASCTEC_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_ASCTEC_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile b/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile index 9fb199d237..94bdf097cd 100644 --- a/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile +++ b/conf/firmwares/subsystems/shared/actuators_asctec_v2.makefile @@ -17,9 +17,11 @@ else ifeq ($(ARCH), stm32) ACTUATORS_ASCTEC_V2_I2C_DEV ?= i2c1 endif +ifeq ($(TARGET), ap) ifndef ACTUATORS_ASCTEC_V2_I2C_DEV $(error Error: ACTUATORS_ASCTEC_V2_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ACTUATORS_ASCTEC_V2_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_ASCTEC_V2_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/actuators_mkk.makefile b/conf/firmwares/subsystems/shared/actuators_mkk.makefile index bc95bc3e89..fa235d2a82 100644 --- a/conf/firmwares/subsystems/shared/actuators_mkk.makefile +++ b/conf/firmwares/subsystems/shared/actuators_mkk.makefile @@ -32,9 +32,11 @@ else ifeq ($(ARCH), stm32) ACTUATORS_MKK_I2C_DEV ?= i2c1 endif +ifeq ($(TARGET), ap) ifndef ACTUATORS_MKK_I2C_DEV $(error Error: ACTUATORS_MKK_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ACTUATORS_MKK_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_MKK_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile b/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile index f07b44b114..1b539a61ea 100644 --- a/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile +++ b/conf/firmwares/subsystems/shared/actuators_mkk_v2.makefile @@ -31,9 +31,11 @@ else ifeq ($(ARCH), stm32) ACTUATORS_MKK_V2_I2C_DEV ?= i2c1 endif +ifeq ($(TARGET), ap) ifndef ACTUATORS_MKK_V2_I2C_DEV $(error Error: ACTUATORS_MKK_V2_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ACTUATORS_MKK_V2_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_MKK_V2_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/actuators_skiron.makefile b/conf/firmwares/subsystems/shared/actuators_skiron.makefile index f52b46c57d..00ff9d3574 100644 --- a/conf/firmwares/subsystems/shared/actuators_skiron.makefile +++ b/conf/firmwares/subsystems/shared/actuators_skiron.makefile @@ -27,9 +27,11 @@ else ifeq ($(ARCH), stm32) ACTUATORS_SKIRON_I2C_DEV ?= i2c1 endif +ifeq ($(TARGET), ap) ifndef ACTUATORS_SKIRON_I2C_DEV $(error Error: ACTUATORS_SKIRON_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ACTUATORS_SKIRON_I2C_DEV_UPPER=$(shell echo $(ACTUATORS_SKIRON_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile b/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile index d57d03f9cf..968a6c9823 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin2_i2c.makefile @@ -14,9 +14,11 @@ else ifeq ($(ARCH), stm32) IMU_ASPIRIN2_I2C_DEV ?= i2c2 endif +ifeq ($(TARGET), ap) ifndef IMU_ASPIRIN2_I2C_DEV $(error Error: IMU_ASPIRIN2_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case IMU_ASPIRIN2_I2C_DEV_UPPER=$(shell echo $(IMU_ASPIRIN2_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile index 3385d78261..673096f75c 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_common.makefile @@ -52,9 +52,11 @@ else ifeq ($(ARCH), stm32) ASPIRIN_I2C_DEV ?= i2c2 endif +ifeq ($(TARGET), ap) ifndef ASPIRIN_I2C_DEV $(error Error: ASPIRIN_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ASPIRIN_I2C_DEV_UPPER=$(shell echo $(ASPIRIN_I2C_DEV) | tr a-z A-Z) @@ -75,6 +77,15 @@ ASPIRIN_SPI_DEV ?= spi2 ASPIRIN_SPI_SLAVE_IDX ?= SPI_SLAVE2 endif +ifeq ($(TARGET), ap) +ifndef ASPIRIN_SPI_DEV +$(error Error: ASPIRIN_SPI_DEV not configured!) +endif +ifndef ASPIRIN_SPI_SLAVE_IDX +$(error Error: ASPIRIN_SPI_SLAVE_IDX not configured!) +endif +endif + # convert spix to upper/lower case ASPIRIN_SPI_DEV_UPPER=$(shell echo $(ASPIRIN_SPI_DEV) | tr a-z A-Z) ASPIRIN_SPI_DEV_LOWER=$(shell echo $(ASPIRIN_SPI_DEV) | tr A-Z a-z) diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile index 9d45a288c4..b5b4618a57 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_i2c_common.makefile @@ -46,9 +46,11 @@ else ifeq ($(ARCH), stm32) ASPIRIN_I2C_DEV ?= i2c2 endif +ifeq ($(TARGET), ap) ifndef ASPIRIN_I2C_DEV $(error Error: ASPIRIN_I2C_DEV not configured!) endif +endif # convert i2cx to upper/lower case ASPIRIN_I2C_DEV_UPPER=$(shell echo $(ASPIRIN_I2C_DEV) | tr a-z A-Z) diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile index a85f2e5e1f..f8b3560ed5 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_v2_common.makefile @@ -54,20 +54,21 @@ include $(CFG_SHARED)/spi_master.makefile # SPI device and slave select defaults # ifeq ($(ARCH), lpc21) -ifndef ASPIRIN_2_SPI_DEV -ASPIRIN_2_SPI_DEV = spi1 -endif -ifndef ASPIRIN_2_SPI_SLAVE_IDX -ASPIRIN_2_SPI_SLAVE_IDX = SPI_SLAVE0 -endif +ASPIRIN_2_SPI_DEV ?= spi1 +ASPIRIN_2_SPI_SLAVE_IDX ?= SPI_SLAVE0 else ifeq ($(ARCH), stm32) # Slave select configuration # SLAVE2 is on PB12 (NSS) (MPU600 CS) +ASPIRIN_2_SPI_DEV ?= spi2 +ASPIRIN_2_SPI_SLAVE_IDX ?= SPI_SLAVE2 +endif + +ifeq ($(TARGET), ap) ifndef ASPIRIN_2_SPI_DEV -ASPIRIN_2_SPI_DEV = spi2 +$(error Error: ASPIRIN_2_SPI_DEV not configured!) endif ifndef ASPIRIN_2_SPI_SLAVE_IDX -ASPIRIN_2_SPI_SLAVE_IDX = SPI_SLAVE2 +$(error Error: ASPIRIN_2_SPI_SLAVE_IDX not configured!) endif endif From dd3571ac9b82b787c0edbc8099582562238719aa Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 9 Sep 2013 23:39:24 +0200 Subject: [PATCH 261/309] [electrical] print bat level --- sw/airborne/subsystems/electrical.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index 5700a0a15e..e7103e8075 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -52,6 +52,9 @@ #define ELECTRICAL_PERIODIC_FREQ 10 +PRINT_CONFIG_VAR(LOW_BAT_LEVEL) +PRINT_CONFIG_VAR(CRITIC_BAT_LEVEL) + struct Electrical electrical; #if defined ADC_CHANNEL_VSUPPLY || defined ADC_CHANNEL_CURRENT || defined MILLIAMP_AT_FULL_THROTTLE From 64f1c9fac4f3abfd27e35a03cd8555efecf95ebc Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 10 Sep 2013 10:34:13 +0200 Subject: [PATCH 262/309] [conf] fix JS_MODE_AXIS to JS_AXIS_MODE --- conf/airframes/examples/MentorEnergy.xml | 2 +- conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml | 2 +- conf/airframes/examples/quadrotor_mlkf.xml | 2 +- conf/airframes/fraser_lisa_m_rotorcraft.xml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/conf/airframes/examples/MentorEnergy.xml b/conf/airframes/examples/MentorEnergy.xml index f282305020..80dd244402 100644 --- a/conf/airframes/examples/MentorEnergy.xml +++ b/conf/airframes/examples/MentorEnergy.xml @@ -260,7 +260,7 @@ - +
diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index ea03629dd7..d2b0a0ab4d 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -205,7 +205,7 @@ - +
diff --git a/conf/airframes/examples/quadrotor_mlkf.xml b/conf/airframes/examples/quadrotor_mlkf.xml index 8778f766e9..781cbd771a 100644 --- a/conf/airframes/examples/quadrotor_mlkf.xml +++ b/conf/airframes/examples/quadrotor_mlkf.xml @@ -207,7 +207,7 @@ - +
diff --git a/conf/airframes/fraser_lisa_m_rotorcraft.xml b/conf/airframes/fraser_lisa_m_rotorcraft.xml index 7fec69072c..a347658ee8 100644 --- a/conf/airframes/fraser_lisa_m_rotorcraft.xml +++ b/conf/airframes/fraser_lisa_m_rotorcraft.xml @@ -241,7 +241,7 @@ - +
From 577b68d38df815db07fbbe095b7577220447b75b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 9 Sep 2013 18:15:12 +0200 Subject: [PATCH 263/309] [state] fix local/global coordinate validity checks --- sw/airborne/state.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/state.h b/sw/airborne/state.h index 9818c0fafd..cb5d101555 100644 --- a/sw/airborne/state.h +++ b/sw/airborne/state.h @@ -487,12 +487,12 @@ extern void stateCalcPositionLla_f(void); /// Test if local coordinates are valid. static inline bool_t stateIsLocalCoordinateValid(void) { - return ((state.ned_initialized_i || state.utm_initialized_f) && (state.pos_status & ~(POS_LOCAL_COORD))); + return ((state.ned_initialized_i || state.utm_initialized_f) && (state.pos_status & (POS_LOCAL_COORD))); } /// Test if global coordinates are valid. static inline bool_t stateIsGlobalCoordinateValid(void) { - return ((state.pos_status & ~(POS_GLOBAL_COORD)) || stateIsLocalCoordinateValid()); + return ((state.pos_status & (POS_GLOBAL_COORD)) || stateIsLocalCoordinateValid()); } /************************ Set functions ****************************/ From 5d78d95cf63e624a375e54835130ba10de4c5cc9 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 10 Sep 2013 15:53:04 +0200 Subject: [PATCH 264/309] [ArDrone] Broadcast IP (win compatible) --- sw/airborne/subsystems/datalink/udp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/datalink/udp.c b/sw/airborne/subsystems/datalink/udp.c index 9d9a717490..88ab870c1d 100644 --- a/sw/airborne/subsystems/datalink/udp.c +++ b/sw/airborne/subsystems/datalink/udp.c @@ -26,7 +26,7 @@ //Check if variables are set and else define them #ifndef LINK_HOST -#define LINK_HOST "192.168.1.0" +#define LINK_HOST "192.168.1.255" #endif #ifndef LINK_PORT #define LINK_PORT 4242 From 604b5e15c58808dce0879a45f42257dd6a0ef875 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Thu, 5 Sep 2013 13:58:35 +0200 Subject: [PATCH 265/309] [conf] TUDelft airframes --- conf/airframes/examples/quadrotor_lisa_s.xml | 33 ++++++++++---------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/conf/airframes/examples/quadrotor_lisa_s.xml b/conf/airframes/examples/quadrotor_lisa_s.xml index 6cee5b9cfa..877026c43b 100644 --- a/conf/airframes/examples/quadrotor_lisa_s.xml +++ b/conf/airframes/examples/quadrotor_lisa_s.xml @@ -55,12 +55,12 @@ - - - - - - + + + + + + @@ -76,7 +76,10 @@
- + + + +
@@ -99,27 +102,25 @@ - - - + - + - + - + - + - - + + From c488f35d298d740b8718cd63306a52ec1cc1720e Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 11 Sep 2013 10:01:41 +0200 Subject: [PATCH 266/309] [ardrone] Auto startup and configure paparazzi Added the possibility to auto startup paparazzi sdk or raw version. Automaticly configures the drone with the airframe file. --- conf/Makefile.omap | 35 ++-- conf/boards/ardrone2_raw.makefile | 8 +- conf/boards/ardrone2_sdk.makefile | 6 + sw/airborne/boards/ardrone/electrical_raw.c | 5 +- sw/ext/ardrone2_drivers/check_update.sh | 96 ++++++++++ sw/ext/ardrone2_drivers/wifi_setup.sh | 201 ++++++++++++++++++++ 6 files changed, 336 insertions(+), 15 deletions(-) create mode 100755 sw/ext/ardrone2_drivers/check_update.sh create mode 100755 sw/ext/ardrone2_drivers/wifi_setup.sh diff --git a/conf/Makefile.omap b/conf/Makefile.omap index f53a726bc0..e567d0c314 100644 --- a/conf/Makefile.omap +++ b/conf/Makefile.omap @@ -78,34 +78,45 @@ elf: $(OBJDIR)/$(TARGET).elf # Program the device and start it. load upload program: $(OBJDIR)/$(TARGET).elf -# If it is not the SDK version, then kill program.elf -ifneq ($(BOARD_TYPE), sdk) - -echo "killall -9 program.elf" | telnet $(HOST) -endif - # Kill the application -echo "killall -9 $(TARGET).elf" | telnet $(HOST) - # Upload the modules and start the application + # Make the target dir and edit the config -{ \ - echo "mkdir -p $(TARGET_DIR)"; \ + echo "mkdir -p $(TARGET_DIR)"; \ + echo "if grep -q \"start_paparazzi *= \" /data/config.ini; then sed -i 's/\(start_paparazzi *= *\).*/\\\1$(ARDRONE2_START_PAPARAZZI)/g' /data/config.ini; else echo \"start_paparazzi = $(ARDRONE2_START_PAPARAZZI)\" >> /data/config.ini; fi"; \ + echo "if grep -q \"wifi_mode *= \" /data/config.ini; then sed -i 's/\(wifi_mode *= *\).*/\\\1$(ARDRONE2_WIFI_MODE)/g' /data/config.ini; else echo \"wifi_mode = $(ARDRONE2_WIFI_MODE)\" >> /data/config.ini; fi"; \ + echo "if grep -q \"ssid_single_player *= \" /data/config.ini; then sed -i 's/\(ssid_single_player *= *\).*/\\\1$(ARDRONE2_SSID)/g' /data/config.ini; else echo \"ssid_single_player = $(ARDRONE2_SSID)\" >> /data/config.ini; fi"; \ + echo "if grep -q \"static_ip_address_base *= \" /data/config.ini; then sed -i 's/\(static_ip_address_base *= *\).*/\\\1$(ARDRONE2_IP_ADDRESS_BASE)/g' /data/config.ini; else echo \"static_ip_address_base = $(ARDRONE2_IP_ADDRESS_BASE)\" >> /data/config.ini; fi"; \ + echo "if grep -q \"static_ip_address_probe *= \" /data/config.ini; then sed -i 's/\(static_ip_address_probe *= *\).*/\\\1$(ARDRONE2_IP_ADDRESS_PROBE)/g' /data/config.ini; else echo \"static_ip_address_probe = $(ARDRONE2_IP_ADDRESS_PROBE)\" >> /data/config.ini; fi"; \ } | telnet $(HOST) # Upload the drivers and new application { \ echo "binary"; \ echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/cdc-acm.ko /$(SUB_DIR)/cdc-acm.ko"; \ + echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/check_update.sh check_update.sh"; \ + echo "put $(PAPARAZZI_SRC)/sw/ext/ardrone2_drivers/wifi_setup.sh wifi_setup.sh"; \ echo "put $(OBJDIR)/$(TARGET).elf /$(SUB_DIR)/$(TARGET).elf"; \ echo "quit"; \ } | ftp -n $(HOST) # Upload the modules and start the application - -{ \ - echo "cd $(TARGET_DIR)"; \ - echo "insmod cdc-acm.ko"; \ - echo "chmod 777 $(TARGET).elf"; \ - echo "./$(TARGET).elf > /dev/null 2>&1 &"; \ + -{ \ + echo "mv /data/video/check_update.sh /bin/"; \ + echo "mv /data/video/wifi_setup.sh /bin/"; \ + echo "chmod 777 /bin/check_update.sh" \ + echo "chmod 777 /bin/wifi_setup.sh" \ + echo "insmod $(TARGET_DIR)/cdc-acm.ko"; \ + echo "chmod 777 $(TARGET_DIR)/$(TARGET).elf"; \ + echo "$(TARGET_DIR)/$(TARGET).elf > /dev/null 2>&1 &"; \ } | telnet $(HOST) + +ifeq ($(ARDRONE2_REBOOT),1) + -{ \ + echo "reboot"; \ + } | telnet $(HOST) +endif # Link: create ELF output file from object files. diff --git a/conf/boards/ardrone2_raw.makefile b/conf/boards/ardrone2_raw.makefile index 8fb9edacf0..b97997b11b 100644 --- a/conf/boards/ardrone2_raw.makefile +++ b/conf/boards/ardrone2_raw.makefile @@ -15,11 +15,17 @@ $(TARGET).ARCHDIR = $(ARCH) # ----------------------------------------------------------------------- USER=foobar -HOST=192.168.1.1 +HOST?=192.168.1.1 SUB_DIR=raw FTP_DIR=/data/video TARGET_DIR=$(FTP_DIR)/$(SUB_DIR) # ----------------------------------------------------------------------- +ARDRONE2_START_PAPARAZZI ?= 0 +ARDRONE2_WIFI_MODE ?= 0 +ARDRONE2_SSID ?= ardrone2_paparazzi +ARDRONE2_IP_ADDRESS_BASE ?= 192.168.1. +ARDRONE2_IP_ADDRESS_PROBE ?= 1 +# ----------------------------------------------------------------------- # The GPS sensor is connected trough USB so we have to define the device GPS_PORT ?= UART1 diff --git a/conf/boards/ardrone2_sdk.makefile b/conf/boards/ardrone2_sdk.makefile index e134414b6c..6ee6311af1 100644 --- a/conf/boards/ardrone2_sdk.makefile +++ b/conf/boards/ardrone2_sdk.makefile @@ -20,6 +20,12 @@ SUB_DIR=sdk FTP_DIR=/data/video TARGET_DIR=$(FTP_DIR)/$(SUB_DIR) # ----------------------------------------------------------------------- +ARDRONE2_START_PAPARAZZI ?= 0 +ARDRONE2_WIFI_MODE ?= 0 +ARDRONE2_SSID ?= ardrone2_paparazzi +ARDRONE2_IP_ADDRESS_BASE ?= 192.168.1. +ARDRONE2_IP_ADDRESS_PROBE ?= 1 +# ----------------------------------------------------------------------- # The GPS sensor is connected trough USB so we have to define the device GPS_PORT ?= UART1 diff --git a/sw/airborne/boards/ardrone/electrical_raw.c b/sw/airborne/boards/ardrone/electrical_raw.c index f47f0157bd..56acd4d9cc 100644 --- a/sw/airborne/boards/ardrone/electrical_raw.c +++ b/sw/airborne/boards/ardrone/electrical_raw.c @@ -68,10 +68,11 @@ static struct { int fd; void electrical_init(void) { + // First we try to kill the program.elf if it is running (done here because initializes first) + system("killall -9 program.elf"); + // Initialize 12c device for power fd = open( "/dev/i2c-1", O_RDWR ); - - if ( ioctl( fd, I2C_SLAVE_FORCE, 0x4a) < 0 ) { fprintf( stderr, "Failed to set slave address: %m\n" ); } diff --git a/sw/ext/ardrone2_drivers/check_update.sh b/sw/ext/ardrone2_drivers/check_update.sh new file mode 100755 index 0000000000..3fee525f48 --- /dev/null +++ b/sw/ext/ardrone2_drivers/check_update.sh @@ -0,0 +1,96 @@ +#!/bin/sh + +UPDATE_DIR=/update +UPDATE_PATH=$UPDATE_DIR/ardrone2_update.plf +VERSION_PATH=$UPDATE_DIR/version.txt +ERR_PATH=$UPDATE_DIR/err.log + +echo "Check if need to start paparazzi ..." +START_PAPARAZZI=`grep start_paparazzi /data/config.ini | awk -F "=" '{ gsub(/ */,"",$2); print $2}'` +case $START_PAPARAZZI in +1) + START_PAPARAZZI=raw + ;; +2) + START_PAPARAZZI=sdk + ;; +*) + START_PAPARAZZI=no + ;; +esac +echo "START_PAPARAZZI=$START_PAPARAZZI" + +echo "Copy version.txt file in ftp directory" +cp /firmware/version.txt $VERSION_PATH + +PELF_ARGS=$(cat /tmp/.program.elf.arguments | tr '\n' ' ') + +echo "Check if update is necessary ..." +if [ -e $UPDATE_PATH ] ; then + VERSION=`cat $VERSION_PATH` + + if [ -e $ERR_PATH ] ; then + CHECK_ERR=`cat $ERR_PATH` + if [ "$CHECK_ERR" = "NEED_TO_FLASH" ] ; then + CHECK_PLF=`/bin/checkplf $UPDATE_PATH $VERSION` + if [ "$CHECK_PLF" = "NEED_TO_FLASH" ] ; then + echo "ERR=FLASH_KO" > $ERR_PATH + else + /bin/checkplf $UPDATE_PATH $VERSION > $ERR_PATH + fi + else + /bin/checkplf $UPDATE_PATH $VERSION > $ERR_PATH + fi + else + /bin/checkplf $UPDATE_PATH $VERSION > $ERR_PATH + fi + + CHECK_ERR=`cat $ERR_PATH` + if [ "$CHECK_ERR" = "NEED_TO_FLASH" ] ; then + echo "File $UPDATE_PATH exists... Start updating..." + pinst_trigger + echo "Rebooting..." + reboot + else + if [ "$CHECK_ERR" = "VERSION_OK" ] ; then + echo "Version OK" + elif [ "$CHECK_ERR" = "ERR=FLASH_KO" ] ; then + echo "Error during Updating... Removing..." + else + echo "File $UPDATE_PATH not valid... Removing..." + fi +# Cleaning update directory + rm -Rf $UPDATE_DIR/* + cp /firmware/version.txt $VERSION_PATH + echo "Start Drone software..." + inetd + + # Check what to start + if [ "$START_PAPARAZZI" = "raw" ] ; then + (/data/video/raw/ap.elf; gpio 181 -d ho 1) & + elif [ "$START_PAPARAZZI" = "sdk" ] ; then + (/data/video/sdk/ap.elf; gpio 181 -d ho 1) & + else + (/bin/program.elf ${PELF_ARGS}; gpio 181 -d ho 1) & + fi + fi +else + echo "File $UPDATE_PATH doesn't exists... Start Drone software..." +# Cleaning update directory + rm -Rf $UPDATE_DIR/* + cp /firmware/version.txt $VERSION_PATH + + inetd + # Check what to start + if [ "$START_PAPARAZZI" = "raw" ] ; then + (/bin/program.elf ${PELF_ARGS}; gpio 181 -d ho 1) & + sleep 10 + (/data/video/raw/ap.elf; gpio 181 -d ho 1) & + elif [ "$START_PAPARAZZI" = "sdk" ] ; then + (/bin/program.elf ${PELF_ARGS}; gpio 181 -d ho 1) & + sleep 10 + (/data/video/sdk/ap.elf; gpio 181 -d ho 1) & + else + (/bin/program.elf ${PELF_ARGS}; gpio 181 -d ho 1) & + fi +fi diff --git a/sw/ext/ardrone2_drivers/wifi_setup.sh b/sw/ext/ardrone2_drivers/wifi_setup.sh new file mode 100755 index 0000000000..a1e075d98d --- /dev/null +++ b/sw/ext/ardrone2_drivers/wifi_setup.sh @@ -0,0 +1,201 @@ +#!/bin/sh +# +# Script to see if an IP adress is already used or not +# +# Getting SSID from config.ini file. + +#initializing random generator +cat /data/random_mac.txt > /dev/urandom +/bin/random_mac > /data/random_mac.txt + +#echo 2 > /proc/cpu/alignment + +export NETIF=ath0 +export WORKAREA="/lib/firmware" +export ATH_PLATFORM="parrot-omap-sdio" +export ATH_MODULE_ARGS="ifname=$NETIF" + +# Switch Wifi mode depending on value into /data/config.ini +# + +WIFI_MODE=`grep wifi_mode /data/config.ini | awk -F "=" '{ gsub(/ */,"",$2); print $2}'` + +case $WIFI_MODE in +0) + WIFI_MODE=master + ;; +1) + WIFI_MODE=ad-hoc + ;; +2) + WIFI_MODE=managed + ;; +*) + WIFI_MODE=master + ;; +esac + + +if [ -s /factory/mac_address.txt ] +then +MAC_ADDR=`cat /factory/mac_address.txt` +else +MAC_ADDR=`cat /data/random_mac.txt` +fi + +loadAR6000.sh -i $NETIF --setmac $MAC_ADDR + +# Waiting 2s for the wifi chip to be ready +sleep 2 + +AR6K_PID=`ps_procps -A -T -c | grep AR6K | awk '{print $1}'` +SDIO_PID=`ps_procps -A -T -c | grep ksdioirqd | awk '{print $1}'` + +#Changing wifi priority +chrt -p -r 25 $SDIO_PID +chrt -p -r 24 $AR6K_PID + + +# Disabling powersaving +wmiconfig -i $NETIF --power maxperf +# Disabling 802.11n aggregation +wmiconfig -i $NETIF --allow_aggr 0 0 +# enabling WMM +wmiconfig -i $NETIF --setwmm 1 + +i=0 + +while [ ! -n "$SSID" ] && [ $i -lt 10 ] +do +i=`expr $i + 1` +SSID=`grep ssid_single_player /data/config.ini | awk -F "=" '{print $2}'` + +# Removing leading and trailing spaces +SSID=`echo $SSID` +sleep 1 +done + +if [ -n "$SSID" ] +then +echo "SSID=$SSID" +else +#default SSID. +SSID=ardrone2_wifi +echo "SSID=\"$SSID\"" +fi + +RANDOM_CHAN=auto + + +echo "Creating $WIFI_MODE Network $SSID" + +iwconfig $NETIF mode $WIFI_MODE +iwconfig $NETIF essid "$SSID" + +if [ "$WIFI_MODE" != "managed" ] +then +# Allowing ACS to select only channels 1 & 6 +wmiconfig -i $NETIF --acsdisablehichannels 1 +iwconfig $NETIF channel $RANDOM_CHAN +iwconfig $NETIF rate auto +iwconfig $NETIF commit +else +# The Wifi connection freezes when in managed mode if there is no keepalive +wmiconfig -i ath0 --setkeepalive 1 +fi + +wmiconfig -i $NETIF --dtim 1 +wmiconfig -i $NETIF --commit + +OK=0 +BASE_ADRESS=`grep static_ip_address_base /data/config.ini | awk -F "=" '{print $2}'` +PROBE=`grep static_ip_address_probe /data/config.ini | awk -F "=" '{print $2}'` + +# Removing leading and trailing spaces +BASE_ADRESS=`echo $BASE_ADRESS` +PROBE=`echo $PROBE` + +# Default base address +if [ -n "$BASE_ADRESS" ] +then +echo "BASE_ADRESS=$BASE_ADRESS" +else +#default BASE_ADDRESS. +BASE_ADRESS=192.168.1. +echo "BASE_ADRESS=\"$BASE_ADRESS\"" +fi + +# Default probe +if [ -n "$PROBE" ] +then +echo "PROBE=$PROBE" +else +#default PROBE. +PROBE=1 +echo "PROBE=\"$PROBE\"" +fi + +while [ $OK -eq 0 ] +do +#configuring interface. +ifconfig $NETIF $BASE_ADRESS$PROBE +arping -I $NETIF -q -f -D -w 2 $BASE_ADRESS$PROBE + +if [ $? -eq 1 ] +then + if [ -s /data/old_adress.txt ] + then + # Testing previously given adress. + PROBE=`cat /data/old_adress.txt` + else + #generating random odd IP address + PROBE=`/bin/random_ip` + fi + /bin/random_ip > /data/old_adress.txt +else + echo $PROBE > /data/old_adress.txt + OK=1 +fi + +done + +#Configuring DHCP server. +echo "Using address $BASE_ADRESS$PROBE" +echo "start $BASE_ADRESS`expr $PROBE + 1`" > /tmp/udhcpd.conf +echo "end $BASE_ADRESS`expr $PROBE + 4`" >> /tmp/udhcpd.conf +echo "interface $NETIF" >> /tmp/udhcpd.conf +echo "decline_time 1" >> /tmp/udhcpd.conf +echo "conflict_time 1" >> /tmp/udhcpd.conf +echo "opt router $BASE_ADRESS$PROBE" >> /tmp/udhcpd.conf +echo "opt subnet 255.255.255.0" >> /tmp/udhcpd.conf +echo "opt lease 1200" >> /tmp/udhcpd.conf + +/bin/pairing_setup.sh + +# Saving random info for initialization at next reboot +echo $MAC_ADDR `date` `/bin/random_mac` > /dev/urandom +/bin/random_mac > /data/random_mac.txt + + + +telnetd -l /bin/sh + +# Check if not booting in master mode +if [ "$WIFI_MODE" != "managed" ] +then + udhcpd /tmp/udhcpd.conf +fi + +# Adding route for multicast-packet +route add -net 224.0.0.0 netmask 240.0.0.0 dev $NETIF + +# Allow reconnection to dirty TCP ports +echo "1" > /proc/sys/net/ipv4/tcp_tw_reuse +echo "1" > /proc/sys/net/ipv4/tcp_tw_recycle + +# Starting the daemon which responds to the AUTH messages from FreeFlight if not in master mode +if [ "$WIFI_MODE" != "managed" ] +then + /bin/parrotauthdaemon +fi + From 9c4b3284ab1be128667a5f83eea8a985f9b431f9 Mon Sep 17 00:00:00 2001 From: fvantienen Date: Wed, 11 Sep 2013 10:04:18 +0200 Subject: [PATCH 267/309] [conf] TU Delft AR.Drone dummy calibration files and auto startup --- .../TUDelft/IMAV2013/ARDrone/182_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/184_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/186_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/188_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/189_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/190_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/191_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/192_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/193_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/194_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/195_calib.xml | 18 ++ .../TUDelft/IMAV2013/ARDrone/196_calib.xml | 18 ++ .../TUDelft/IMAV2013/ardrone2_raw.xml | 208 ++++++++++++++++++ conf/airframes/TUDelft/IMAV2013/conf.xml | 180 ++++++++++++++- 14 files changed, 599 insertions(+), 5 deletions(-) create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml create mode 100644 conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml new file mode 100644 index 0000000000..469c8e94b3 --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml new file mode 100644 index 0000000000..f92bae4a6d --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml new file mode 100644 index 0000000000..4b8a0a3b79 --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml new file mode 100644 index 0000000000..688c81d4db --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml @@ -0,0 +1,18 @@ + + + +
+ + + + + + + + + + + + +
+
\ No newline at end of file diff --git a/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml b/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml new file mode 100644 index 0000000000..c67a98311e --- /dev/null +++ b/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml @@ -0,0 +1,208 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + +
+ + + + + + + + + + +
+ + + + + + + + +
+ + + +
+ + + +
+ +
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + +
+ +
+ + + + +
+ +
+ + + + +
+ +
+ + + + + +
+
diff --git a/conf/airframes/TUDelft/IMAV2013/conf.xml b/conf/airframes/TUDelft/IMAV2013/conf.xml index 5581e4ce28..9c7ec3c285 100644 --- a/conf/airframes/TUDelft/IMAV2013/conf.xml +++ b/conf/airframes/TUDelft/IMAV2013/conf.xml @@ -1,7 +1,177 @@ + + + + + + + + + + + + + + + + + Date: Wed, 11 Sep 2013 09:51:44 +0200 Subject: [PATCH 268/309] [generator] Aircraft generator added AC_ID --- sw/tools/gen_aircraft.ml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/sw/tools/gen_aircraft.ml b/sw/tools/gen_aircraft.ml index e82a21c4c9..3065443de0 100644 --- a/sw/tools/gen_aircraft.ml +++ b/sw/tools/gen_aircraft.ml @@ -264,12 +264,13 @@ let dump_firmware_sections = fun xml makefile_ac -> (** Extracts the makefile sections of an airframe file *) -let extract_makefile = fun airframe_file makefile_ac -> +let extract_makefile = fun ac_id airframe_file makefile_ac -> let xml = Xml.parse_file airframe_file in let f = open_out makefile_ac in fprintf f "# This file has been generated from %s by %s\n" airframe_file Sys.argv.(0); fprintf f "# Please DO NOT EDIT\n"; + fprintf f "AC_ID=%s\n" ac_id; (** Search and dump makefile sections that have a "location" attribute set to "before" or no attribute *) dump_makefile_section xml f airframe_file "before"; @@ -397,7 +398,7 @@ let () = let temp_makefile_ac = Filename.temp_file "Makefile.ac" "tmp" in let abs_airframe_file = paparazzi_conf // airframe_file in - let modules_files = extract_makefile abs_airframe_file temp_makefile_ac in + let modules_files = extract_makefile (value "ac_id") abs_airframe_file temp_makefile_ac in (* Create Makefile.ac only if needed *) let makefile_ac = aircraft_dir // "Makefile.ac" in From b8d3b4794d4dd52c02cc39765fcbeccc77fe30e8 Mon Sep 17 00:00:00 2001 From: hendrixgr Date: Wed, 11 Sep 2013 22:34:09 +0300 Subject: [PATCH 269/309] [stm32] actuators_pwm: add TIM1,8,9 and 12 --- .../subsystems/actuators/actuators_pwm_arch.c | 73 ++++++++++++++++++- 1 file changed, 69 insertions(+), 4 deletions(-) diff --git a/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c b/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c index 6a4ba6bf7e..79b6e4f0ce 100644 --- a/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c +++ b/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c @@ -23,6 +23,8 @@ * STM32 PWM servos handling. */ +//VALID TIMERS ARE TIM1,2,3,4,5,8,9,12 + #include "subsystems/actuators/actuators_pwm_arch.h" #include "subsystems/actuators/actuators_pwm.h" @@ -41,6 +43,7 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; #endif #define ONE_MHZ_CLK 1000000 + /** Default servo update rate in Hz */ #ifndef SERVO_HZ #define SERVO_HZ 40 @@ -62,19 +65,31 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; #ifndef TIM5_SERVO_HZ #define TIM5_SERVO_HZ SERVO_HZ #endif +#ifndef TIM9_SERVO_HZ +#define TIM9_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM12_SERVO_HZ +#define TIM12_SERVO_HZ SERVO_HZ +#endif + /** Set PWM channel configuration */ static inline void actuators_pwm_arch_channel_init(uint32_t timer_peripheral, - enum tim_oc_id oc_id) { + enum tim_oc_id oc_id) { timer_disable_oc_output(timer_peripheral, oc_id); - timer_disable_oc_clear(timer_peripheral, oc_id); + //There is no such register in TIM9 and 12. + if (timer_peripheral != TIM9 && timer_peripheral != TIM12){ + timer_disable_oc_clear(timer_peripheral, oc_id); + } timer_enable_oc_preload(timer_peripheral, oc_id); timer_set_oc_slow_mode(timer_peripheral, oc_id); timer_set_oc_mode(timer_peripheral, oc_id, TIM_OCM_PWM1); timer_set_oc_polarity_high(timer_peripheral, oc_id); timer_enable_oc_output(timer_peripheral, oc_id); + // Used for TIM1 and TIM8, the function does nothing if other timer is specified. + timer_enable_break_main_output(timer_peripheral); } /** Set GPIO configuration @@ -103,9 +118,22 @@ static inline void set_servo_timer(uint32_t timer, uint32_t period, uint8_t chan * - Alignement edge. * - Direction up. */ - timer_set_mode(timer, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); + if (timer != TIM9 && timer != TIM12 ) { + timer_set_mode(timer, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - timer_set_prescaler(timer, (PCLK / ONE_MHZ_CLK) - 1); // 1uS + } else { + //There are no EDGE and DIR settings in TIM9 and TIM12 + timer_set_mode(timer, TIM_CR1_CKD_CK_INT, 0, 0); + } + + //TIM9, 1 and 8 use APB2 clock which runs at double speed (APB1 X2). + if (timer != TIM9 && timer != TIM1 && timer != TIM8) { + timer_set_prescaler(timer, (PCLK / ONE_MHZ_CLK) - 1); // 1uS + + } else { + // 1uS, APB2 runs on double the frequency of APB1. + timer_set_prescaler(timer, ((PCLK / ONE_MHZ_CLK)*2) - 1); + } timer_disable_preload(timer); @@ -148,6 +176,7 @@ static inline void set_servo_timer(uint32_t timer, uint32_t period, uint8_t chan /* Counter enable. */ timer_enable_counter(timer); + } /** PWM arch init called by generic pwm driver @@ -158,6 +187,7 @@ void actuators_pwm_arch_init(void) { * Configure timer peripheral clocks *-----------------------------------*/ #if PWM_USE_TIM1 + // APB2 runs on double the frequency of APB1. rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_TIM1EN); #endif #if PWM_USE_TIM2 @@ -172,6 +202,17 @@ void actuators_pwm_arch_init(void) { #if PWM_USE_TIM5 rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM5EN); #endif +#if PWM_USE_TIM8 + // APB2 runs on double the frequency of APB1. + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_TIM8EN); +#endif +#if PWM_USE_TIM9 + // APB2 runs on double the frequency of APB1. + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_TIM9EN); +#endif +#if PWM_USE_TIM12 + rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM12EN); +#endif /*---------------- * Configure GPIO @@ -211,6 +252,12 @@ void actuators_pwm_arch_init(void) { #ifdef PWM_SERVO_9 set_servo_gpio(PWM_SERVO_9_GPIO, PWM_SERVO_9_PIN, PWM_SERVO_9_AF, PWM_SERVO_9_RCC_IOP); #endif +#ifdef PWM_SERVO_10 + set_servo_gpio(PWM_SERVO_10_GPIO, PWM_SERVO_10_PIN, PWM_SERVO_10_AF, PWM_SERVO_10_RCC_IOP); +#endif +#ifdef PWM_SERVO_11 + set_servo_gpio(PWM_SERVO_11_GPIO, PWM_SERVO_11_PIN, PWM_SERVO_11_AF, PWM_SERVO_11_RCC_IOP); +#endif #if PWM_USE_TIM1 @@ -233,6 +280,18 @@ void actuators_pwm_arch_init(void) { set_servo_timer(TIM5, TIM5_SERVO_HZ, PWM_TIM5_CHAN_MASK); #endif +#if PWM_USE_TIM8 + set_servo_timer(TIM8, TIM8_SERVO_HZ, PWM_TIM8_CHAN_MASK); +#endif + +#if PWM_USE_TIM9 + set_servo_timer(TIM9, TIM9_SERVO_HZ, PWM_TIM9_CHAN_MASK); +#endif + +#if PWM_USE_TIM12 + set_servo_timer(TIM12, TIM12_SERVO_HZ, PWM_TIM12_CHAN_MASK); +#endif + } /** Set pulse widths from actuator values, assumed to be in us @@ -268,5 +327,11 @@ void actuators_pwm_commit(void) { #ifdef PWM_SERVO_9 timer_set_oc_value(PWM_SERVO_9_TIMER, PWM_SERVO_9_OC, actuators_pwm_values[PWM_SERVO_9]); #endif +#ifdef PWM_SERVO_10 + timer_set_oc_value(PWM_SERVO_10_TIMER, PWM_SERVO_10_OC, actuators_pwm_values[PWM_SERVO_10]); +#endif +#ifdef PWM_SERVO_11 + timer_set_oc_value(PWM_SERVO_11_TIMER, PWM_SERVO_11_OC, actuators_pwm_values[PWM_SERVO_11]); +#endif } From 95650f488d89d38070d064530d0ac1e693f0b0bb Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 11 Sep 2013 22:42:21 +0200 Subject: [PATCH 270/309] [stm32] actuators_pwm: TIM9 and TIM12 only available on STM32F4 --- .../subsystems/actuators/actuators_pwm_arch.c | 54 ++++++++++++++----- 1 file changed, 41 insertions(+), 13 deletions(-) diff --git a/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c b/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c index 79b6e4f0ce..7f891b22c9 100644 --- a/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c +++ b/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c @@ -32,7 +32,6 @@ #include #include -int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; #if defined(STM32F1) //#define PCLK 72000000 @@ -44,6 +43,26 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; #define ONE_MHZ_CLK 1000000 +#ifdef STM32F1 +/** + * HCLK = 72MHz, Timer clock also 72MHz since + * TIM1_CLK = APB2 = 72MHz + * TIM2_CLK = 2 * APB1 = 2 * 32MHz + */ +#define TIMER_APB1_CLK AHB_CLK +#define TIMER_APB2_CLK AHB_CLK +#endif + +#ifdef STM32F4 +/* Since APB prescaler != 1 : + * Timer clock frequency (before prescaling) is twice the frequency + * of the APB domain to which the timer is connected. + */ +#define TIMER_APB1_CLK (rcc_ppre1_frequency * 2) +#define TIMER_APB2_CLK (rcc_ppre2_frequency * 2) +#endif + + /** Default servo update rate in Hz */ #ifndef SERVO_HZ #define SERVO_HZ 40 @@ -73,16 +92,21 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; #endif + +int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; + + /** Set PWM channel configuration */ static inline void actuators_pwm_arch_channel_init(uint32_t timer_peripheral, enum tim_oc_id oc_id) { timer_disable_oc_output(timer_peripheral, oc_id); +#if STM32F4 //There is no such register in TIM9 and 12. - if (timer_peripheral != TIM9 && timer_peripheral != TIM12){ + if (timer_peripheral != TIM9 && timer_peripheral != TIM12) +#endif timer_disable_oc_clear(timer_peripheral, oc_id); - } timer_enable_oc_preload(timer_peripheral, oc_id); timer_set_oc_slow_mode(timer_peripheral, oc_id); timer_set_oc_mode(timer_peripheral, oc_id, TIM_OCM_PWM1); @@ -118,21 +142,25 @@ static inline void set_servo_timer(uint32_t timer, uint32_t period, uint8_t chan * - Alignement edge. * - Direction up. */ - if (timer != TIM9 && timer != TIM12 ) { - timer_set_mode(timer, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - - } else { +#if STM32F4 + if ((timer == TIM9) || (timer == TIM12)) //There are no EDGE and DIR settings in TIM9 and TIM12 timer_set_mode(timer, TIM_CR1_CKD_CK_INT, 0, 0); - } + else +#endif + timer_set_mode(timer, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - //TIM9, 1 and 8 use APB2 clock which runs at double speed (APB1 X2). - if (timer != TIM9 && timer != TIM1 && timer != TIM8) { - timer_set_prescaler(timer, (PCLK / ONE_MHZ_CLK) - 1); // 1uS + // TIM1, 8 and 9 use APB2 clock, all others APB1 +#if STM32F4 + if (timer != TIM1 && timer != TIM8 && timer != TIM9) { +#else + if (timer != TIM1 && timer != TIM8) { +#endif + timer_set_prescaler(timer, (TIMER_APB1_CLK / ONE_MHZ_CLK) - 1); // 1uS } else { - // 1uS, APB2 runs on double the frequency of APB1. - timer_set_prescaler(timer, ((PCLK / ONE_MHZ_CLK)*2) - 1); + // TIM9, 1 and 8 use APB2 clock + timer_set_prescaler(timer, (TIMER_APB2_CLK / ONE_MHZ_CLK) - 1); } timer_disable_preload(timer); From b7ef46b74b3f162e1d2a3613580a2a922dc93154 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Sep 2013 15:36:27 +0200 Subject: [PATCH 271/309] [conf.xml] update configure gui replace os.systems calls with generic remove and copy commands that work on multiple platforms. The os.symlink still only works on posix systems of course. --- configure.py | 56 +++++++++++++++++++++++++++++++--------------------- 1 file changed, 33 insertions(+), 23 deletions(-) diff --git a/configure.py b/configure.py index 03f7042200..de6c9b8809 100755 --- a/configure.py +++ b/configure.py @@ -8,11 +8,14 @@ pygtk.require('2.0') import os +import shutil import datetime from fnmatch import fnmatch import subprocess + + class ConfChooser: # General Functions @@ -57,44 +60,49 @@ class ConfChooser: os.system("./paparazzi &"); gtk.main_quit() - def backupconf(self, personal=0): + def backupconf(self, use_personal=False): timestr = datetime.datetime.now().strftime("%Y-%m-%d_%H:%M") - newname = "conf.xml." + timestr if " -> " in self.explain.get_text(): print("Symlink does not need backup"); else: - os.system("cd " + self.pwd + "/conf && cp conf.xml " + newname) + newname = "conf.xml." + timestr + backup_file = os.path.join(self.conf_dir, newname) + shutil.copyfile(self.conf_xml, backup_file) print("Made a backup: " + newname) - if personal == 1: - if os.path.exists(self.pwd + "/conf/conf.xml.personal"): + if use_personal: + conf_personal = os.path.join(self.conf_dir, "conf.xml.personal") + conf_personal_backup = os.path.join(self.conf_dir, "conf.xml.personal." + timestr) + if os.path.exists(conf_personal): print("Backup conf.xml.personal to conf.xml.personal." + timestr) - os.system("cd " + self.pwd + "/conf && cp conf.xml.personal conf.xml.personal." + timestr) + shutil.copyfile(conf_personal, conf_personal_backup) def delete(self, widget): - cmd = "cd " + self.pwd + "/conf && rm -f " + self.conf_file_combo.get_active_text() + filename = os.path.join(self.conf_dir, self.conf_file_combo.get_active_text()) # TODO: dialog: are you certain? - os.system(cmd) + os.remove(filename) self.find_conf_files() - + def accept(self, widget): self.backupconf() - cmd = "cd " + self.pwd + "/conf && ln -f -s " + self.conf_file_combo.get_active_text() + " conf.xml" - print(cmd) - os.system(cmd) + link_source = self.conf_file_combo.get_active_text() + os.remove(self.conf_xml) + os.symlink(link_source, self.conf_xml) self.update_label() self.find_conf_files() def personal(self, widget): - self.backupconf(1) - cmd = "cd " + self.pwd + "/conf && cp " + self.conf_file_combo.get_active_text() + " conf.xml.personal && ln -f -s conf.xml.personal conf.xml" - print(cmd) - os.system(cmd) + self.backupconf(True) + template_file = os.path.join(self.conf_dir, self.conf_file_combo.get_active_text()) + personal_file = os.path.join(self.conf_dir, "conf.xml.personal") + shutil.copyfile(template_file, personal_file) + os.remove(self.conf_xml) + os.symlink("conf.xml.personal", self.conf_xml) self.update_label() self.find_conf_files() - # Constructor Functions + # Constructor Functions def destroy(self, widget, data=None): gtk.main_quit() @@ -105,9 +113,12 @@ class ConfChooser: self.my_vbox = gtk.VBox() - # Where Am I? - self.pwd = subprocess.Popen("pwd", stdout=subprocess.PIPE,stderr=subprocess.STDOUT, shell=True).stdout.read().strip() - + # if PAPARAZZI_HOME not set, then assume the tree containing this + # file is a reasonable substitute + self.paparazzi_home = os.getenv("PAPARAZZI_HOME", os.path.dirname(os.path.abspath(__file__))) + self.conf_dir = os.path.join(self.paparazzi_home, "conf") + self.conf_xml = os.path.join(self.conf_dir, "conf.xml") + # MenuBar mb = gtk.MenuBar() @@ -147,7 +158,7 @@ class ConfChooser: self.find_conf_files() # self.firmwares_combo.connect("changed", self.parse_list_of_airframes) self.conf_file_combo.set_size_request(600,30) - + self.confbar = gtk.HBox() self.confbar.pack_start(self.conf_label) self.confbar.pack_start(self.conf_file_combo) @@ -194,7 +205,7 @@ class ConfChooser: self.my_vbox.pack_start(self.toolbar, False) - ##### Bottom + ##### Bottom self.window.add(self.my_vbox) self.window.show_all() @@ -210,4 +221,3 @@ if __name__ == "__main__": airframe_file = sys.argv[1] gui = ConfChooser() gui.main() - From 3a4aab5ed355d6e3fa544e751a20f28358270c55 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Sep 2013 16:20:02 +0200 Subject: [PATCH 272/309] [conf.xml] configure gui improvements - sort list - use python tools to get info about current conf, i.e. link to which file --- configure.py | 32 +++++++++++++++++++++----------- 1 file changed, 21 insertions(+), 11 deletions(-) diff --git a/configure.py b/configure.py index de6c9b8809..0035527254 100755 --- a/configure.py +++ b/configure.py @@ -29,28 +29,38 @@ class ConfChooser: combo.set_sensitive(True) def update_label(self): - r = subprocess.Popen("ls -altr ./conf/conf.xml", stdout=subprocess.PIPE,stderr=subprocess.STDOUT, shell=True).stdout.read() - r = r.strip() - self.explain.set_text("Currently set to: " + r) + desc = "Current conf: " + if not os.path.lexists(self.conf_xml): + desc += "does not exist" + else: + if os.path.islink(self.conf_xml): + if os.path.exists(self.conf_xml): + desc += "symlink to " + else: + desc += "broken symlink to " + real_conf_path = os.path.realpath(self.conf_xml) + desc += os.path.relpath(real_conf_path, self.conf_dir) + self.explain.set_text(desc) # CallBack Functions def find_conf_files(self): - list_of_conf_files = [] + conf_files = [] - root = './conf/' pattern = "*conf.xml*" - for path, subdirs, files in os.walk(root): + for path, subdirs, files in os.walk(self.conf_dir): for name in files: if fnmatch(name, pattern): - entry = os.path.join(path, name).replace("./conf/","") - if entry != "conf.xml": - list_of_conf_files.append(entry) + filepath = os.path.join(path, name) + entry = os.path.relpath(filepath, self.conf_dir) + if not os.path.islink(filepath) and entry != "conf.xml": + conf_files.append(entry) - self.update_combo(self.conf_file_combo,list_of_conf_files) + conf_files.sort() + self.update_combo(self.conf_file_combo, conf_files) def about(self): @@ -62,7 +72,7 @@ class ConfChooser: def backupconf(self, use_personal=False): timestr = datetime.datetime.now().strftime("%Y-%m-%d_%H:%M") - if " -> " in self.explain.get_text(): + if os.path.islink(self.conf_xml): print("Symlink does not need backup"); else: newname = "conf.xml." + timestr From 7ffb3343e852f1262d0256cc5805d9271acfc711 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Sep 2013 16:44:06 +0200 Subject: [PATCH 273/309] [conf.xml] gui: exclude backups from list --- configure.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/configure.py b/configure.py index 0035527254..c3d49c42f0 100755 --- a/configure.py +++ b/configure.py @@ -50,13 +50,17 @@ class ConfChooser: conf_files = [] pattern = "*conf.xml*" + backup_pattern = "conf.xml.2[0-9][0-9][0-9]-[01][0-9]-[0-3][0-9]_*" + excludes = ["conf.xml", "%gconf.xml"] for path, subdirs, files in os.walk(self.conf_dir): for name in files: + if self.exclude_backups and fnmatch(name, backup_pattern): + continue if fnmatch(name, pattern): filepath = os.path.join(path, name) entry = os.path.relpath(filepath, self.conf_dir) - if not os.path.islink(filepath) and entry != "conf.xml": + if not os.path.islink(filepath) and entry not in excludes: conf_files.append(entry) conf_files.sort() @@ -91,6 +95,7 @@ class ConfChooser: filename = os.path.join(self.conf_dir, self.conf_file_combo.get_active_text()) # TODO: dialog: are you certain? os.remove(filename) + self.update_label() self.find_conf_files() @@ -129,6 +134,8 @@ class ConfChooser: self.conf_dir = os.path.join(self.paparazzi_home, "conf") self.conf_xml = os.path.join(self.conf_dir, "conf.xml") + self.exclude_backups = True + # MenuBar mb = gtk.MenuBar() From bcdb047f2d067836d1839db7b19fb6485b9eddd2 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Sep 2013 17:47:11 +0200 Subject: [PATCH 274/309] [conf.xml] gui improvements - non-editable combo box - set current conf as active selection - only ignore conf.xml if it's already a symlink --- configure.py | 37 +++++++++++++++++++++++-------------- 1 file changed, 23 insertions(+), 14 deletions(-) diff --git a/configure.py b/configure.py index c3d49c42f0..c7e693e232 100755 --- a/configure.py +++ b/configure.py @@ -20,12 +20,15 @@ class ConfChooser: # General Functions - def update_combo(self,combo,list): + def update_combo(self, combo, list): combo.set_sensitive(False) combo.get_model().clear() - for i in list: - combo.append_text(i) - combo.set_active(0) + current_index = 0 + for (i, text) in enumerate(list): + combo.append_text(text) + if os.path.join(self.conf_dir, text) == os.path.realpath(self.conf_xml): + current_index = i + combo.set_active(current_index) combo.set_sensitive(True) def update_label(self): @@ -50,8 +53,8 @@ class ConfChooser: conf_files = [] pattern = "*conf.xml*" - backup_pattern = "conf.xml.2[0-9][0-9][0-9]-[01][0-9]-[0-3][0-9]_*" - excludes = ["conf.xml", "%gconf.xml"] + backup_pattern = "conf.xml.*2[0-9][0-9][0-9]-[01][0-9]-[0-3][0-9]_*" + excludes = ["%gconf.xml"] for path, subdirs, files in os.walk(self.conf_dir): for name in files: @@ -77,7 +80,8 @@ class ConfChooser: def backupconf(self, use_personal=False): timestr = datetime.datetime.now().strftime("%Y-%m-%d_%H:%M") if os.path.islink(self.conf_xml): - print("Symlink does not need backup"); + if self.verbose: + print("Symlink does not need backup"); else: newname = "conf.xml." + timestr backup_file = os.path.join(self.conf_dir, newname) @@ -100,12 +104,16 @@ class ConfChooser: def accept(self, widget): - self.backupconf() - link_source = self.conf_file_combo.get_active_text() - os.remove(self.conf_xml) - os.symlink(link_source, self.conf_xml) - self.update_label() - self.find_conf_files() + selected = self.conf_file_combo.get_active_text() + if selected == "conf.xml": + print("conf.xml is not a symlink, maybe you want to copy it to your personal file first?") + else: + self.backupconf() + link_source = self.conf_file_combo.get_active_text() + os.remove(self.conf_xml) + os.symlink(selected, self.conf_xml) + self.update_label() + self.find_conf_files() def personal(self, widget): self.backupconf(True) @@ -135,6 +143,7 @@ class ConfChooser: self.conf_xml = os.path.join(self.conf_dir, "conf.xml") self.exclude_backups = True + self.verbose = False # MenuBar mb = gtk.MenuBar() @@ -171,7 +180,7 @@ class ConfChooser: self.conf_label = gtk.Label("Conf:") - self.conf_file_combo = gtk.combo_box_entry_new_text() + self.conf_file_combo = gtk.combo_box_new_text() self.find_conf_files() # self.firmwares_combo.connect("changed", self.parse_list_of_airframes) self.conf_file_combo.set_size_request(600,30) From ef294b3ebe105913e1aeb68e37c59f1cfe7222be Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Sep 2013 18:25:34 +0200 Subject: [PATCH 275/309] [conf.xml] gui: checkbox for showing backups --- configure.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/configure.py b/configure.py index c7e693e232..4fda73f70f 100755 --- a/configure.py +++ b/configure.py @@ -73,6 +73,10 @@ class ConfChooser: def about(self): gui_dialogs.about(paparazzi.home_dir) + def set_backups(self, widget): + self.exclude_backups = not widget.get_active() + self.find_conf_files() + def launch(self, widget): os.system("./paparazzi &"); gtk.main_quit() @@ -190,6 +194,11 @@ class ConfChooser: self.confbar.pack_start(self.conf_file_combo) self.my_vbox.pack_start(self.confbar, False) + ### show backups button + self.btnBackups = gtk.CheckButton("show backups") + self.btnBackups.connect("toggled", self.set_backups) + self.my_vbox.pack_start(self.btnBackups, False) + ##### Explain current config self.explain = gtk.Label(""); From 4f43ee260d9a4d5a6092ec61fa80e71a0a978e5b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Sep 2013 21:18:07 +0200 Subject: [PATCH 276/309] [rotorcraft] simplify nav_is_in_flight --- sw/airborne/firmwares/rotorcraft/navigation.c | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c index 2fdc841aa0..366ff9d010 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.c +++ b/sw/airborne/firmwares/rotorcraft/navigation.c @@ -342,10 +342,7 @@ bool_t nav_detect_ground(void) { } bool_t nav_is_in_flight(void) { - if (autopilot_in_flight) - return TRUE; - else - return FALSE; + return autopilot_in_flight; } void nav_home(void) {} From dd3de820d423506bbf4a7b96b6c24769560b414c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 10:46:07 +0200 Subject: [PATCH 277/309] [tools][modules] add MODULES_FREQUENCY in generated/modules.h --- sw/airborne/firmwares/fixedwing/main_ap.c | 6 +++--- sw/airborne/firmwares/rotorcraft/main.c | 6 +++--- sw/tools/gen_modules.ml | 10 ++++++---- 3 files changed, 12 insertions(+), 10 deletions(-) diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index ee1a5795a3..3da798c060 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -111,9 +111,9 @@ PRINT_CONFIG_VAR(CONTROL_FREQUENCY) #endif PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY) -#ifndef MODULES_FREQUENCY -#define MODULES_FREQUENCY 60 -#endif +/* MODULES_FREQUENCY is defined in generated/modules.h + * according to main_freq parameter set for modules in airframe file + */ PRINT_CONFIG_VAR(MODULES_FREQUENCY) diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index b942a084ac..44144f6430 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -82,9 +82,9 @@ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) #endif PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY) -#ifndef MODULES_FREQUENCY -#define MODULES_FREQUENCY PERIODIC_FREQUENCY -#endif +/* MODULES_FREQUENCY is defined in generated/modules.h + * according to main_freq parameter set for modules in airframe file + */ PRINT_CONFIG_VAR(MODULES_FREQUENCY) #ifndef BARO_PERIODIC_FREQUENCY diff --git a/sw/tools/gen_modules.ml b/sw/tools/gen_modules.ml index 1b4db5371f..ddd39ea0ee 100644 --- a/sw/tools/gen_modules.ml +++ b/sw/tools/gen_modules.ml @@ -355,16 +355,18 @@ let () = fprintf out_h "#define MODULES_START 2\n"; fprintf out_h "#define MODULES_STOP 3\n"; nl (); + (* Extract main_freq parameter *) + let modules = try (ExtXml.child xml "modules") with _ -> Xml.Element("modules",[],[]) in + let main_freq = try (int_of_string (Xml.attrib modules "main_freq")) with _ -> !freq in + freq := main_freq; + fprintf out_h "#define MODULES_FREQUENCY %d\n" !freq; + nl (); fprintf out_h "#ifdef MODULES_C\n"; fprintf out_h "#define EXTERN_MODULES\n"; fprintf out_h "#else\n"; fprintf out_h "#define EXTERN_MODULES extern\n"; fprintf out_h "#endif"; nl (); - (* Extract main_freq parameter *) - let modules = try (ExtXml.child xml "modules") with _ -> Xml.Element("modules",[],[]) in - let main_freq = try (int_of_string (Xml.attrib modules "main_freq")) with _ -> !freq in - freq := main_freq; (* Extract modules list *) let modules = GC.get_modules_of_airframe xml in let modules = GC.unload_unused_modules modules true in From c061e60246739c2818917b5618cdb17af0753812 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 10:49:10 +0200 Subject: [PATCH 278/309] [conf] explicitly specify modules main_freq for some rotorcraft airframes --- .../examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml | 2 +- conf/airframes/examples/quadrotor_px4fmu.xml | 2 +- conf/airframes/examples/stm32f4_discovery_test.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml index 06a69c6cf2..9f7210bd3e 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum_geo_mag.xml @@ -38,7 +38,7 @@ - + diff --git a/conf/airframes/examples/quadrotor_px4fmu.xml b/conf/airframes/examples/quadrotor_px4fmu.xml index a67d1738fd..fb02773791 100644 --- a/conf/airframes/examples/quadrotor_px4fmu.xml +++ b/conf/airframes/examples/quadrotor_px4fmu.xml @@ -33,7 +33,7 @@ - + diff --git a/conf/airframes/examples/stm32f4_discovery_test.xml b/conf/airframes/examples/stm32f4_discovery_test.xml index 2f10e1c38b..ed339e5a4a 100644 --- a/conf/airframes/examples/stm32f4_discovery_test.xml +++ b/conf/airframes/examples/stm32f4_discovery_test.xml @@ -29,7 +29,7 @@ - + From ae0a26a45a925a9d264105403fa91a5d64d390e9 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 11:04:16 +0200 Subject: [PATCH 279/309] [tools][conf] add TELEMETRY_FREQUENCY in generated/periodic_telemetry.h --- conf/firmwares/rotorcraft.makefile | 3 --- conf/firmwares/subsystems/fixedwing/autopilot.makefile | 3 --- conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile | 2 -- sw/airborne/firmwares/fixedwing/main_ap.c | 6 +++--- sw/airborne/firmwares/rotorcraft/main.c | 6 +++--- sw/tools/gen_periodic.ml | 1 + 6 files changed, 7 insertions(+), 14 deletions(-) diff --git a/conf/firmwares/rotorcraft.makefile b/conf/firmwares/rotorcraft.makefile index 42ae945568..884bc9a178 100644 --- a/conf/firmwares/rotorcraft.makefile +++ b/conf/firmwares/rotorcraft.makefile @@ -84,9 +84,6 @@ endif PERIODIC_FREQUENCY ?= 512 ap.CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY) -TELEMETRY_FREQUENCY ?= 60 -ap.CFLAGS += -DTELEMETRY_FREQUENCY=$(TELEMETRY_FREQUENCY) - # # Systime # diff --git a/conf/firmwares/subsystems/fixedwing/autopilot.makefile b/conf/firmwares/subsystems/fixedwing/autopilot.makefile index 6c93338ac6..9970e344d7 100644 --- a/conf/firmwares/subsystems/fixedwing/autopilot.makefile +++ b/conf/firmwares/subsystems/fixedwing/autopilot.makefile @@ -60,9 +60,6 @@ $(TARGET).CFLAGS += -DTRAFFIC_INFO PERIODIC_FREQUENCY ?= 60 $(TARGET).CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY) -TELEMETRY_FREQUENCY ?= 60 -$(TARGET).CFLAGS += -DTELEMETRY_FREQUENCY=$(TELEMETRY_FREQUENCY) - $(TARGET).srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c $(TARGET).CFLAGS += -DUSE_SYS_TIME diff --git a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile index b2b9ba8090..25afc4658b 100644 --- a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile @@ -69,9 +69,7 @@ nps.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c PERIODIC_FREQUENCY ?= 512 -TELEMETRY_FREQUENCY ?= 60 nps.CFLAGS += -DPERIODIC_FREQUENCY=$(PERIODIC_FREQUENCY) -nps.CFLAGS += -DTELEMETRY_FREQUENCY=$(TELEMETRY_FREQUENCY) #nps.CFLAGS += -DUSE_LED nps.srcs += mcu_periph/sys_time.c $(SRC_ARCH)/mcu_periph/sys_time_arch.c diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 3da798c060..3ad0007e58 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -106,9 +106,9 @@ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) PRINT_CONFIG_VAR(NAVIGATION_FREQUENCY) PRINT_CONFIG_VAR(CONTROL_FREQUENCY) -#ifndef TELEMETRY_FREQUENCY -#define TELEMETRY_FREQUENCY 60 -#endif +/* TELEMETRY_FREQUENCY is defined in generated/periodic_telemetry.h + * defaults to 60Hz or set by TELEMETRY_FREQUENCY configure option in airframe file + */ PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY) /* MODULES_FREQUENCY is defined in generated/modules.h diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 44144f6430..cb04be854d 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -77,9 +77,9 @@ /* if PRINT_CONFIG is defined, print some config options */ PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) -#ifndef TELEMETRY_FREQUENCY -#define TELEMETRY_FREQUENCY 60 -#endif +/* TELEMETRY_FREQUENCY is defined in generated/periodic_telemetry.h + * defaults to 60Hz or set by TELEMETRY_FREQUENCY configure option in airframe file + */ PRINT_CONFIG_VAR(TELEMETRY_FREQUENCY) /* MODULES_FREQUENCY is defined in generated/modules.h diff --git a/sw/tools/gen_periodic.ml b/sw/tools/gen_periodic.ml index 253182f8c3..1fdb99a7b4 100644 --- a/sw/tools/gen_periodic.ml +++ b/sw/tools/gen_periodic.ml @@ -142,6 +142,7 @@ let _ = fprintf out_h "#define _VAR_PERIODIC_H_\n\n"; fprintf out_h "#include \"std.h\"\n"; fprintf out_h "#include \"generated/airframe.h\"\n\n"; + fprintf out_h "#define TELEMETRY_FREQUENCY %d\n\n" freq; (** For each process *) List.iter From 6ea53c5c15ac95fdbf00f89f1bd70d40cb6f5cc5 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 11:28:41 +0200 Subject: [PATCH 280/309] [tools] generated MODULES_FREQUENCY defaults to PERIODIC_FREQUENCY --- Makefile.ac | 12 ++++++++++-- sw/tools/gen_modules.ml | 9 +++++---- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/Makefile.ac b/Makefile.ac index 90e2b5e3d0..1886c829bc 100644 --- a/Makefile.ac +++ b/Makefile.ac @@ -64,11 +64,19 @@ Q=@ # ifeq ($(MAKECMDGOALS),all_ac_h) -include $(MAKEFILE_AC) -endif # telemetry periodic frequency defaults to 60Hz TELEMETRY_FREQUENCY ?= 60 +ifdef PERIODIC_FREQUENCY +DEFAULT_MODULES_FREQUENCY = $(PERIODIC_FREQUENCY) +else +$(error Error: PERIODIC_FREQUENCY not configured) +endif + +endif + + init: @[ -d $(PAPARAZZI_HOME) ] || (echo "Copying config example in your $(PAPARAZZI_HOME) directory"; mkdir -p $(PAPARAZZI_HOME); cp -a conf $(PAPARAZZI_HOME); cp -a data $(PAPARAZZI_HOME); mkdir -p $(PAPARAZZI_HOME)/var/maps; mkdir -p $(PAPARAZZI_HOME)/var/include) @@ -147,7 +155,7 @@ $(MODULES_H) : $(CONF)/$(AIRFRAME_XML) $(TOOLS)/gen_modules.out $(CONF)/modules/ $(Q)test -d $(AC_GENERATED) || mkdir -p $(AC_GENERATED) @echo GENERATE $@ $(eval $@_TMP := $(shell $(MKTEMP))) - $(Q)$(TOOLS)/gen_modules.out $(SETTINGS_MODULES) $< > $($@_TMP) + $(Q)$(TOOLS)/gen_modules.out $(SETTINGS_MODULES) $(DEFAULT_MODULES_FREQUENCY) $< > $($@_TMP) $(Q)mv $($@_TMP) $@ $(Q)chmod a+r $@ diff --git a/sw/tools/gen_modules.ml b/sw/tools/gen_modules.ml index ddd39ea0ee..7a32fcfe1c 100644 --- a/sw/tools/gen_modules.ml +++ b/sw/tools/gen_modules.ml @@ -344,9 +344,10 @@ let write_settings = fun xml_file out_set modules -> let h_name = "MODULES_H" let () = - if Array.length Sys.argv <> 3 then - failwith (Printf.sprintf "Usage: %s out_settings_file xml_file" Sys.argv.(0)); - let xml_file = Sys.argv.(2) + if Array.length Sys.argv <> 4 then + failwith (Printf.sprintf "Usage: %s out_settings_file default_freq xml_file" Sys.argv.(0)); + let xml_file = Sys.argv.(3) + and default_freq = int_of_string(Sys.argv.(2)) and out_set = open_out Sys.argv.(1) in try let xml = start_and_begin xml_file h_name in @@ -357,7 +358,7 @@ let () = nl (); (* Extract main_freq parameter *) let modules = try (ExtXml.child xml "modules") with _ -> Xml.Element("modules",[],[]) in - let main_freq = try (int_of_string (Xml.attrib modules "main_freq")) with _ -> !freq in + let main_freq = try (int_of_string (Xml.attrib modules "main_freq")) with _ -> default_freq in freq := main_freq; fprintf out_h "#define MODULES_FREQUENCY %d\n" !freq; nl (); From 3e1b88fe3e1ebd82368ec5079fb9be03cd51993f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 13:18:09 +0200 Subject: [PATCH 281/309] [nps] bat_voltage adjustable via settings --- .../examples/quadrotor_lisa_m_2_pwm_spektrum.xml | 2 +- .../subsystems/fixedwing/fdm_jsbsim.makefile | 1 + .../subsystems/rotorcraft/fdm_jsbsim.makefile | 1 + conf/settings/nps.xml | 1 + sw/simulator/nps/nps_autopilot_fixedwing.c | 15 ++++++--------- sw/simulator/nps/nps_autopilot_rotorcraft.c | 14 ++++++-------- 6 files changed, 16 insertions(+), 18 deletions(-) diff --git a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml index d2b0a0ab4d..4d68ce1534 100644 --- a/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml +++ b/conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml @@ -217,7 +217,7 @@
- +
diff --git a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile index 688d5b7cb4..ed7ce66951 100644 --- a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile @@ -52,6 +52,7 @@ nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_sensor_mag.c \ $(NPSDIR)/nps_sensor_baro.c \ $(NPSDIR)/nps_sensor_gps.c \ + $(NPSDIR)/nps_electrical.c \ $(NPSDIR)/nps_radio_control.c \ $(NPSDIR)/nps_radio_control_joystick.c \ $(NPSDIR)/nps_radio_control_spektrum.c \ diff --git a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile index 25afc4658b..45b618f08d 100644 --- a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile @@ -48,6 +48,7 @@ nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_sensor_mag.c \ $(NPSDIR)/nps_sensor_baro.c \ $(NPSDIR)/nps_sensor_gps.c \ + $(NPSDIR)/nps_electrical.c \ $(NPSDIR)/nps_radio_control.c \ $(NPSDIR)/nps_radio_control_joystick.c \ $(NPSDIR)/nps_radio_control_spektrum.c \ diff --git a/conf/settings/nps.xml b/conf/settings/nps.xml index 8fb6ed6513..279caca01c 100644 --- a/conf/settings/nps.xml +++ b/conf/settings/nps.xml @@ -6,6 +6,7 @@ + diff --git a/sw/simulator/nps/nps_autopilot_fixedwing.c b/sw/simulator/nps/nps_autopilot_fixedwing.c index 5cf695e12c..27826df4e3 100644 --- a/sw/simulator/nps/nps_autopilot_fixedwing.c +++ b/sw/simulator/nps/nps_autopilot_fixedwing.c @@ -38,13 +38,13 @@ #include "nps_sensors.h" #include "nps_radio_control.h" +#include "nps_electrical.h" #include "nps_fdm.h" #include "subsystems/radio_control.h" #include "subsystems/imu.h" #include "subsystems/sensors/baro.h" #include "baro_board.h" -#include "subsystems/electrical.h" #include "mcu_periph/sys_time.h" #include "state.h" #include "subsystems/commands.h" @@ -65,18 +65,13 @@ bool_t nps_bypass_ahrs; void nps_autopilot_init(enum NpsRadioControlType type_rc, int num_rc_script, char* rc_dev) { nps_radio_control_init(type_rc, num_rc_script, rc_dev); + nps_electrical_init(); + nps_bypass_ahrs = NPS_BYPASS_AHRS; Fbw(init); Ap(init); - -#ifdef MAX_BAT_LEVEL - electrical.vsupply = MAX_BAT_LEVEL * 10; -#else - electrical.vsupply = 111; -#endif - } void nps_autopilot_run_systime_step( void ) { @@ -86,7 +81,9 @@ void nps_autopilot_run_systime_step( void ) { #include #include "subsystems/gps.h" -void nps_autopilot_run_step(double time __attribute__ ((unused))) { +void nps_autopilot_run_step(double time) { + + nps_electrical_run_step(time); #ifdef RADIO_CONTROL_TYPE_PPM if (nps_radio_control_available(time)) { diff --git a/sw/simulator/nps/nps_autopilot_rotorcraft.c b/sw/simulator/nps/nps_autopilot_rotorcraft.c index 0064c2f897..6641cc5dc8 100644 --- a/sw/simulator/nps/nps_autopilot_rotorcraft.c +++ b/sw/simulator/nps/nps_autopilot_rotorcraft.c @@ -24,13 +24,13 @@ #include "firmwares/rotorcraft/main.h" #include "nps_sensors.h" #include "nps_radio_control.h" +#include "nps_electrical.h" #include "nps_fdm.h" #include "subsystems/radio_control.h" #include "subsystems/imu.h" #include "subsystems/sensors/baro.h" #include "baro_board.h" -#include "subsystems/electrical.h" #include "mcu_periph/sys_time.h" #include "state.h" #include "subsystems/ahrs.h" @@ -56,17 +56,13 @@ bool_t nps_bypass_ins; void nps_autopilot_init(enum NpsRadioControlType type_rc, int num_rc_script, char* rc_dev) { nps_radio_control_init(type_rc, num_rc_script, rc_dev); + nps_electrical_init(); + nps_bypass_ahrs = NPS_BYPASS_AHRS; nps_bypass_ins = NPS_BYPASS_INS; main_init(); -#ifdef MAX_BAT_LEVEL - electrical.vsupply = MAX_BAT_LEVEL * 10; -#else - electrical.vsupply = 111; -#endif - } void nps_autopilot_run_systime_step( void ) { @@ -76,7 +72,9 @@ void nps_autopilot_run_systime_step( void ) { #include #include "subsystems/gps.h" -void nps_autopilot_run_step(double time __attribute__ ((unused))) { +void nps_autopilot_run_step(double time) { + + nps_electrical_run_step(time); #ifdef RADIO_CONTROL_TYPE_PPM if (nps_radio_control_available(time)) { From c8487dc5735875de98d630749b377761c13b2414 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 14:36:47 +0200 Subject: [PATCH 282/309] [nps] ups, add missing nps_electrical files --- sw/simulator/nps/nps_electrical.c | 42 +++++++++++++++++++++++++++++++ sw/simulator/nps/nps_electrical.h | 34 +++++++++++++++++++++++++ 2 files changed, 76 insertions(+) create mode 100644 sw/simulator/nps/nps_electrical.c create mode 100644 sw/simulator/nps/nps_electrical.h diff --git a/sw/simulator/nps/nps_electrical.c b/sw/simulator/nps/nps_electrical.c new file mode 100644 index 0000000000..bc4c3e520a --- /dev/null +++ b/sw/simulator/nps/nps_electrical.c @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + + +#include "nps_electrical.h" +#include "generated/airframe.h" +#include "subsystems/electrical.h" + +struct NpsElectrical nps_electrical; + +void nps_electrical_init(void) { + +#ifdef MAX_BAT_LEVEL + nps_electrical.supply_voltage = MAX_BAT_LEVEL; +#else + nps_electrical.supply_voltage = 11.1; +#endif + +} + +void nps_electrical_run_step(double time __attribute__ ((unused))) { + // todo: auto-decrease bat voltage + electrical.vsupply = nps_electrical.supply_voltage * 10; +} diff --git a/sw/simulator/nps/nps_electrical.h b/sw/simulator/nps/nps_electrical.h new file mode 100644 index 0000000000..a8f6054814 --- /dev/null +++ b/sw/simulator/nps/nps_electrical.h @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef NPS_ELECTRICAL_H +#define NPS_ELECTRICAL_H + +struct NpsElectrical { + float supply_voltage; +}; + +extern struct NpsElectrical nps_electrical; + +extern void nps_electrical_init(void); +extern void nps_electrical_run_step(double time); + +#endif From 06e69bcaeab8fcfe96449dcccb1c51aea1b2a74d Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 14:12:35 +0200 Subject: [PATCH 283/309] TELEMETRY_FREQUENCY defaults to PERIODIC_FREQUENCY also default to 60Hz if PERIODIC_FREQUENCY is not configured --- Makefile.ac | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Makefile.ac b/Makefile.ac index 1886c829bc..7fd56cd35a 100644 --- a/Makefile.ac +++ b/Makefile.ac @@ -65,13 +65,14 @@ Q=@ ifeq ($(MAKECMDGOALS),all_ac_h) -include $(MAKEFILE_AC) -# telemetry periodic frequency defaults to 60Hz -TELEMETRY_FREQUENCY ?= 60 - -ifdef PERIODIC_FREQUENCY +ifdef PERIODIC_FREQUENC +# telemetry and module periodic frequency default to PERIODIC_FREQUENCY +TELEMETRY_FREQUENCY ?= $(PERIODIC_FREQUENCY) DEFAULT_MODULES_FREQUENCY = $(PERIODIC_FREQUENCY) else -$(error Error: PERIODIC_FREQUENCY not configured) +$(warning Info: PERIODIC_FREQUENCY not configured, defaulting to 60Hz for modules and telemetry) +TELEMETRY_FREQUENCY ?= 60 +DEFAULT_MODULES_FREQUENCY = 60 endif endif From d12572dcdc5fb9f4c0288cb1f29fbfd570fd44e4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 15:55:10 +0200 Subject: [PATCH 284/309] fix typo --- Makefile.ac | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile.ac b/Makefile.ac index 7fd56cd35a..9939768bcd 100644 --- a/Makefile.ac +++ b/Makefile.ac @@ -65,7 +65,7 @@ Q=@ ifeq ($(MAKECMDGOALS),all_ac_h) -include $(MAKEFILE_AC) -ifdef PERIODIC_FREQUENC +ifdef PERIODIC_FREQUENCY # telemetry and module periodic frequency default to PERIODIC_FREQUENCY TELEMETRY_FREQUENCY ?= $(PERIODIC_FREQUENCY) DEFAULT_MODULES_FREQUENCY = $(PERIODIC_FREQUENCY) From 09e5bb497e0b4142603e41d41e11683cd63aea59 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 18:38:34 +0200 Subject: [PATCH 285/309] [nps] simple wind simulation No vertical wind component for now, only magnitude and direction. Also no gusts so far... Can be changed via settings. Towards solving issue #540 --- .../subsystems/fixedwing/fdm_jsbsim.makefile | 1 + .../subsystems/rotorcraft/fdm_jsbsim.makefile | 1 + conf/settings/nps.xml | 2 + sw/simulator/nps/nps_atmosphere.c | 55 +++++++++++++++++++ sw/simulator/nps/nps_atmosphere.h | 39 +++++++++++++ sw/simulator/nps/nps_electrical.c | 4 ++ sw/simulator/nps/nps_electrical.h | 5 ++ sw/simulator/nps/nps_fdm.h | 3 + sw/simulator/nps/nps_fdm_jsbsim.c | 18 +++++- sw/simulator/nps/nps_ivy_common.c | 7 +++ sw/simulator/nps/nps_main.c | 5 +- 11 files changed, 137 insertions(+), 3 deletions(-) create mode 100644 sw/simulator/nps/nps_atmosphere.c diff --git a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile index ed7ce66951..3587d244df 100644 --- a/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/fixedwing/fdm_jsbsim.makefile @@ -53,6 +53,7 @@ nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_sensor_baro.c \ $(NPSDIR)/nps_sensor_gps.c \ $(NPSDIR)/nps_electrical.c \ + $(NPSDIR)/nps_atmosphere.c \ $(NPSDIR)/nps_radio_control.c \ $(NPSDIR)/nps_radio_control_joystick.c \ $(NPSDIR)/nps_radio_control_spektrum.c \ diff --git a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile index 45b618f08d..8db11612fd 100644 --- a/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile +++ b/conf/firmwares/subsystems/rotorcraft/fdm_jsbsim.makefile @@ -49,6 +49,7 @@ nps.srcs += $(NPSDIR)/nps_main.c \ $(NPSDIR)/nps_sensor_baro.c \ $(NPSDIR)/nps_sensor_gps.c \ $(NPSDIR)/nps_electrical.c \ + $(NPSDIR)/nps_atmosphere.c \ $(NPSDIR)/nps_radio_control.c \ $(NPSDIR)/nps_radio_control_joystick.c \ $(NPSDIR)/nps_radio_control_spektrum.c \ diff --git a/conf/settings/nps.xml b/conf/settings/nps.xml index 279caca01c..60dfaa5c98 100644 --- a/conf/settings/nps.xml +++ b/conf/settings/nps.xml @@ -7,6 +7,8 @@ + + diff --git a/sw/simulator/nps/nps_atmosphere.c b/sw/simulator/nps/nps_atmosphere.c new file mode 100644 index 0000000000..e676b089cb --- /dev/null +++ b/sw/simulator/nps/nps_atmosphere.c @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file nps_atmosphere.c + * Atmosphere model (pressure, wind) for NPS. + */ + +#include "nps_atmosphere.h" +#include "nps_fdm.h" + +#ifndef NPS_QNH +#define NPS_QNH 101325.0 +#endif + +#ifndef NPS_WIND_SPEED +#define NPS_WIND_SPEED 0.0 +#endif + +#ifndef NPS_WIND_DIR +#define NPS_WIND_DIR 0 +#endif + +struct NpsAtmosphere nps_atmosphere; + +void nps_atmosphere_init(void) { + + nps_atmosphere.qnh = NPS_QNH; + nps_atmosphere.wind_speed = NPS_WIND_SPEED; + nps_atmosphere.wind_dir = NPS_WIND_DIR; + +} + +void nps_atmosphere_update(double dt __attribute__((unused))) { + nps_fdm_set_wind(nps_atmosphere.wind_speed, nps_atmosphere.wind_dir); +} + diff --git a/sw/simulator/nps/nps_atmosphere.h b/sw/simulator/nps/nps_atmosphere.h index d167c77dff..88cc1cf820 100644 --- a/sw/simulator/nps/nps_atmosphere.h +++ b/sw/simulator/nps/nps_atmosphere.h @@ -1,6 +1,45 @@ +/* + * Copyright (C) 2013 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/** + * @file nps_atmosphere.h + * Atmosphere model (pressure, wind) for NPS. + */ + #ifndef NPS_ATMOSPHERE_H #define NPS_ATMOSPHERE_H +#include "math/pprz_algebra_double.h" + +struct NpsAtmosphere { + double qnh; ///< barometric pressure at sea level in Pascal + double wind_speed; ///< wind magnitude in m/s + double wind_dir; ///< wind direction in radians north=0, increasing CCW +}; + +extern struct NpsAtmosphere nps_atmosphere; + +extern void nps_atmosphere_init(void); +extern void nps_atmosphere_update(double dt); + #endif /* NPS_ATMOSPHERE_H */ diff --git a/sw/simulator/nps/nps_electrical.c b/sw/simulator/nps/nps_electrical.c index bc4c3e520a..97e66eb908 100644 --- a/sw/simulator/nps/nps_electrical.c +++ b/sw/simulator/nps/nps_electrical.c @@ -19,6 +19,10 @@ * Boston, MA 02111-1307, USA. */ +/** + * @file nps_electrical.c + * Electrical status (bat voltage) for NPS. + */ #include "nps_electrical.h" #include "generated/airframe.h" diff --git a/sw/simulator/nps/nps_electrical.h b/sw/simulator/nps/nps_electrical.h index a8f6054814..d1b15bcfdb 100644 --- a/sw/simulator/nps/nps_electrical.h +++ b/sw/simulator/nps/nps_electrical.h @@ -19,6 +19,11 @@ * Boston, MA 02111-1307, USA. */ +/** + * @file nps_electrical.h + * Electrical status (bat voltage) for NPS. + */ + #ifndef NPS_ELECTRICAL_H #define NPS_ELECTRICAL_H diff --git a/sw/simulator/nps/nps_fdm.h b/sw/simulator/nps/nps_fdm.h index 4332fe0104..c223c9fda6 100644 --- a/sw/simulator/nps/nps_fdm.h +++ b/sw/simulator/nps/nps_fdm.h @@ -86,11 +86,14 @@ struct NpsFdm { struct DoubleVect3 ltp_g; struct DoubleVect3 ltp_h; + struct DoubleVect3 wind; ///< velocity in m/s in NED + }; extern struct NpsFdm fdm; extern void nps_fdm_init(double dt); extern void nps_fdm_run_step(double* commands); +extern void nps_fdm_set_wind(double speed, double dir); #endif /* NPS_FDM */ diff --git a/sw/simulator/nps/nps_fdm_jsbsim.c b/sw/simulator/nps/nps_fdm_jsbsim.c index 4487ae8c14..64dd9dc813 100644 --- a/sw/simulator/nps/nps_fdm_jsbsim.c +++ b/sw/simulator/nps/nps_fdm_jsbsim.c @@ -35,6 +35,7 @@ #include #include #include +#include #include "nps_fdm.h" #include "math/pprz_geodetic.h" @@ -179,6 +180,12 @@ void nps_fdm_run_step(double* commands) { } +void nps_fdm_set_wind(double speed, double dir) { + FGWinds* Winds = FDMExec->GetWinds(); + Winds->SetWindspeed(FeetOfMeters(speed)); + Winds->SetWindPsi(dir); +} + /** * Feed JSBSim with the latest actuator commands. * @@ -199,6 +206,7 @@ static void feed_jsbsim(double* commands) { } + /** * Populates the NPS fdm struct after a simulation step. */ @@ -295,9 +303,15 @@ static void fetch_state(void) { /* * rotational speed and accelerations */ - jsbsimvec_to_rate(&fdm.body_ecef_rotvel,&propagate->GetPQR()); - jsbsimvec_to_rate(&fdm.body_ecef_rotaccel,&accelerations->GetPQRdot()); + jsbsimvec_to_rate(&fdm.body_ecef_rotvel, &propagate->GetPQR()); + jsbsimvec_to_rate(&fdm.body_ecef_rotaccel, &accelerations->GetPQRdot()); + + /* + * wind + */ + const FGColumnVector3& fg_wind_ned = FDMExec->GetWinds()->GetTotalWindNED(); + jsbsimvec_to_vec(&fdm.wind, &fg_wind_ned); } /** diff --git a/sw/simulator/nps/nps_ivy_common.c b/sw/simulator/nps/nps_ivy_common.c index c93bd7d4eb..4c869a22ac 100644 --- a/sw/simulator/nps/nps_ivy_common.c +++ b/sw/simulator/nps/nps_ivy_common.c @@ -9,6 +9,7 @@ #include "nps_autopilot.h" #include "nps_fdm.h" #include "nps_sensors.h" +#include "nps_atmosphere.h" #include "subsystems/ins.h" #include "subsystems/navigation/common_flight_plan.h" @@ -186,4 +187,10 @@ void nps_ivy_display(void) { h_body.x, h_body.y, h_body.z); + + IvySendMsg("%d NPS_WIND %f %f %f", + AC_ID, + fdm.wind.x, + fdm.wind.y, + fdm.wind.z); } diff --git a/sw/simulator/nps/nps_main.c b/sw/simulator/nps/nps_main.c index a740eb15e0..6686beb324 100644 --- a/sw/simulator/nps/nps_main.c +++ b/sw/simulator/nps/nps_main.c @@ -84,7 +84,7 @@ double time_to_double(struct timeval *t) { return ((double)t->tv_sec + (double)(t->tv_usec * 1e-6)); } -int main ( int argc, char** argv) { +int main (int argc, char** argv) { if (!nps_main_parse_options(argc, argv)) return 1; @@ -121,6 +121,7 @@ static void nps_main_init(void) { nps_ivy_init(nps_main.ivy_bus); nps_fdm_init(SIM_DT); + nps_atmosphere_init(); nps_sensors_init(nps_main.sim_time); printf("Simulating with dt of %f\n", SIM_DT); @@ -153,6 +154,8 @@ static void nps_main_init(void) { static void nps_main_run_sim_step(void) { // printf("sim at %f\n", nps_main.sim_time); + nps_atmosphere_update(SIM_DT); + nps_autopilot_run_systime_step(); nps_fdm_run_step(autopilot.commands); From b83b291e1d203164fab435b76e849a9262fb7d9f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 18:49:38 +0200 Subject: [PATCH 286/309] [nps] ability to set gps outage via settings --- conf/settings/nps.xml | 1 + sw/airborne/subsystems/gps/gps_sim_nps.c | 7 ++++++- sw/airborne/subsystems/gps/gps_sim_nps.h | 1 + 3 files changed, 8 insertions(+), 1 deletion(-) diff --git a/conf/settings/nps.xml b/conf/settings/nps.xml index 60dfaa5c98..073e4e0b7f 100644 --- a/conf/settings/nps.xml +++ b/conf/settings/nps.xml @@ -6,6 +6,7 @@ + diff --git a/sw/airborne/subsystems/gps/gps_sim_nps.c b/sw/airborne/subsystems/gps/gps_sim_nps.c index 549630a8d5..546d32d549 100644 --- a/sw/airborne/subsystems/gps/gps_sim_nps.c +++ b/sw/airborne/subsystems/gps/gps_sim_nps.c @@ -29,6 +29,7 @@ #endif bool_t gps_available; +bool_t gps_has_fix; void gps_feed_value() { gps.ecef_pos.x = sensors.gps.ecef_pos.x * 100.; @@ -75,10 +76,14 @@ void gps_feed_value() { gps.utm_pos.zone = nav_utm_zone0; #endif - gps.fix = GPS_FIX_3D; + if (gps_has_fix) + gps.fix = GPS_FIX_3D; + else + gps.fix = GPS_FIX_NONE; gps_available = TRUE; } void gps_impl_init() { gps_available = FALSE; + gps_has_fix = TRUE; } diff --git a/sw/airborne/subsystems/gps/gps_sim_nps.h b/sw/airborne/subsystems/gps/gps_sim_nps.h index e1dd5fc05d..9c327590a2 100644 --- a/sw/airborne/subsystems/gps/gps_sim_nps.h +++ b/sw/airborne/subsystems/gps/gps_sim_nps.h @@ -6,6 +6,7 @@ #define GPS_NB_CHANNELS 16 extern bool_t gps_available; +extern bool_t gps_has_fix; extern void gps_feed_value(); From 593c686a50d219a22ac89c890207588b5099655b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 22:04:28 +0200 Subject: [PATCH 287/309] [stm32][actuators_pwm] add defines for TIM9 and TIM12 --- .../stm32/subsystems/actuators/actuators_pwm_arch.c | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c b/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c index 7f891b22c9..70e309b299 100644 --- a/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c +++ b/sw/airborne/arch/stm32/subsystems/actuators/actuators_pwm_arch.c @@ -92,6 +92,9 @@ #endif +/** @todo: these should go into libopencm3 */ +#define TIM9 TIM9_BASE +#define TIM12 TIM12_BASE int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; @@ -102,10 +105,8 @@ static inline void actuators_pwm_arch_channel_init(uint32_t timer_peripheral, enum tim_oc_id oc_id) { timer_disable_oc_output(timer_peripheral, oc_id); -#if STM32F4 //There is no such register in TIM9 and 12. if (timer_peripheral != TIM9 && timer_peripheral != TIM12) -#endif timer_disable_oc_clear(timer_peripheral, oc_id); timer_enable_oc_preload(timer_peripheral, oc_id); timer_set_oc_slow_mode(timer_peripheral, oc_id); @@ -142,21 +143,15 @@ static inline void set_servo_timer(uint32_t timer, uint32_t period, uint8_t chan * - Alignement edge. * - Direction up. */ -#if STM32F4 if ((timer == TIM9) || (timer == TIM12)) //There are no EDGE and DIR settings in TIM9 and TIM12 timer_set_mode(timer, TIM_CR1_CKD_CK_INT, 0, 0); else -#endif timer_set_mode(timer, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // TIM1, 8 and 9 use APB2 clock, all others APB1 -#if STM32F4 if (timer != TIM1 && timer != TIM8 && timer != TIM9) { -#else - if (timer != TIM1 && timer != TIM8) { -#endif timer_set_prescaler(timer, (TIMER_APB1_CLK / ONE_MHZ_CLK) - 1); // 1uS } else { // TIM9, 1 and 8 use APB2 clock From b2b114c689374ec5d334b013ab24237494805f3b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 23:25:55 +0200 Subject: [PATCH 288/309] [conf] rename configre.py to select_conf.py some other minor improvements --- configure.py => select_conf.py | 30 +++++++++++++++++------------- 1 file changed, 17 insertions(+), 13 deletions(-) rename configure.py => select_conf.py (88%) diff --git a/configure.py b/select_conf.py similarity index 88% rename from configure.py rename to select_conf.py index 4fda73f70f..56fcf684c1 100755 --- a/configure.py +++ b/select_conf.py @@ -93,11 +93,11 @@ class ConfChooser: print("Made a backup: " + newname) if use_personal: - conf_personal = os.path.join(self.conf_dir, "conf.xml.personal") - conf_personal_backup = os.path.join(self.conf_dir, "conf.xml.personal." + timestr) - if os.path.exists(conf_personal): - print("Backup conf.xml.personal to conf.xml.personal." + timestr) - shutil.copyfile(conf_personal, conf_personal_backup) + backup_name = self.conf_personal_name + "." + timestr + conf_personal_backup = os.path.join(self.conf_dir, backup_name) + if os.path.exists(self.conf_personal): + print("Backup conf.xml.personal to " + backup_name) + shutil.copyfile(self.conf_personal, conf_personal_backup) def delete(self, widget): filename = os.path.join(self.conf_dir, self.conf_file_combo.get_active_text()) @@ -120,14 +120,16 @@ class ConfChooser: self.find_conf_files() def personal(self, widget): - self.backupconf(True) - template_file = os.path.join(self.conf_dir, self.conf_file_combo.get_active_text()) - personal_file = os.path.join(self.conf_dir, "conf.xml.personal") - shutil.copyfile(template_file, personal_file) - os.remove(self.conf_xml) - os.symlink("conf.xml.personal", self.conf_xml) - self.update_label() - self.find_conf_files() + if os.path.exists(self.conf_personal): + print("Your personal conf file already exists!") + else: + self.backupconf(True) + template_file = os.path.join(self.conf_dir, self.conf_file_combo.get_active_text()) + shutil.copyfile(template_file, self.conf_personal) + os.remove(self.conf_xml) + os.symlink(self.conf_personal_name, self.conf_xml) + self.update_label() + self.find_conf_files() # Constructor Functions @@ -145,6 +147,8 @@ class ConfChooser: self.paparazzi_home = os.getenv("PAPARAZZI_HOME", os.path.dirname(os.path.abspath(__file__))) self.conf_dir = os.path.join(self.paparazzi_home, "conf") self.conf_xml = os.path.join(self.conf_dir, "conf.xml") + self.conf_personal_name = "conf.xml.personal" + self.conf_personal = os.path.join(self.conf_dir, self.conf_personal_name) self.exclude_backups = True self.verbose = False From 80a007f15568b264e39440a27a6a0c4176aca3ae Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 13 Sep 2013 23:56:14 +0200 Subject: [PATCH 289/309] [conf] rename from *.xml.example to *_example.xml - select_conf: personal conf file is conf_personal.xml --- .gitignore | 1 + Makefile | 4 ++-- conf/{conf.xml.example => conf_example.xml} | 0 conf/{tests_conf.xml => conf_tests.xml} | 0 conf/{conf.xml.tri => conf_tri.xml} | 0 ...{control_panel.xml.example => control_panel_example.xml} | 0 conf/{maps.xml.example => maps_example.xml} | 0 select_conf.py | 6 +++--- tests/examples/01_compile_all_test_targets.t | 2 +- 9 files changed, 7 insertions(+), 6 deletions(-) rename conf/{conf.xml.example => conf_example.xml} (100%) rename conf/{tests_conf.xml => conf_tests.xml} (100%) rename conf/{conf.xml.tri => conf_tri.xml} (100%) rename conf/{control_panel.xml.example => control_panel_example.xml} (100%) rename conf/{maps.xml.example => maps_example.xml} (100%) diff --git a/.gitignore b/.gitignore index da442c20b7..3f6f5456a1 100644 --- a/.gitignore +++ b/.gitignore @@ -40,6 +40,7 @@ # /conf/ /conf/conf.xml /conf/conf.xml.20* +/conf/conf_personal.xml.20* /conf/control_panel.xml /conf/%gconf.xml /conf/maps_data/* diff --git a/Makefile b/Makefile index b845818f72..b46b46b178 100644 --- a/Makefile +++ b/Makefile @@ -113,7 +113,7 @@ update_google_version: conf: conf/conf.xml conf/control_panel.xml conf/maps.xml -conf/%.xml :conf/%.xml.example +conf/%.xml :conf/%_example.xml [ -L $@ ] || [ -f $@ ] || cp $< $@ @@ -294,7 +294,7 @@ ab_clean: replace_current_conf_xml: test conf/conf.xml && mv conf/conf.xml conf/conf.xml.backup.$(BUILD_DATETIME) - cp conf/tests_conf.xml conf/conf.xml + cp conf/conf_tests.xml conf/conf.xml restore_conf_xml: test conf/conf.xml.backup.$(BUILD_DATETIME) && mv conf/conf.xml.backup.$(BUILD_DATETIME) conf/conf.xml diff --git a/conf/conf.xml.example b/conf/conf_example.xml similarity index 100% rename from conf/conf.xml.example rename to conf/conf_example.xml diff --git a/conf/tests_conf.xml b/conf/conf_tests.xml similarity index 100% rename from conf/tests_conf.xml rename to conf/conf_tests.xml diff --git a/conf/conf.xml.tri b/conf/conf_tri.xml similarity index 100% rename from conf/conf.xml.tri rename to conf/conf_tri.xml diff --git a/conf/control_panel.xml.example b/conf/control_panel_example.xml similarity index 100% rename from conf/control_panel.xml.example rename to conf/control_panel_example.xml diff --git a/conf/maps.xml.example b/conf/maps_example.xml similarity index 100% rename from conf/maps.xml.example rename to conf/maps_example.xml diff --git a/select_conf.py b/select_conf.py index 56fcf684c1..08e91c004a 100755 --- a/select_conf.py +++ b/select_conf.py @@ -52,8 +52,8 @@ class ConfChooser: conf_files = [] - pattern = "*conf.xml*" - backup_pattern = "conf.xml.*2[0-9][0-9][0-9]-[01][0-9]-[0-3][0-9]_*" + pattern = "conf[._-]*xml*" + backup_pattern = "conf[._-]*xml.20[0-9][0-9]-[01][0-9]-[0-3][0-9]_*" excludes = ["%gconf.xml"] for path, subdirs, files in os.walk(self.conf_dir): @@ -147,7 +147,7 @@ class ConfChooser: self.paparazzi_home = os.getenv("PAPARAZZI_HOME", os.path.dirname(os.path.abspath(__file__))) self.conf_dir = os.path.join(self.paparazzi_home, "conf") self.conf_xml = os.path.join(self.conf_dir, "conf.xml") - self.conf_personal_name = "conf.xml.personal" + self.conf_personal_name = "conf_personal.xml" self.conf_personal = os.path.join(self.conf_dir, self.conf_personal_name) self.exclude_backups = True diff --git a/tests/examples/01_compile_all_test_targets.t b/tests/examples/01_compile_all_test_targets.t index f18feddaa5..03bab305bf 100644 --- a/tests/examples/01_compile_all_test_targets.t +++ b/tests/examples/01_compile_all_test_targets.t @@ -8,7 +8,7 @@ use Data::Dumper; use Config; $|++; -my $examples = XMLin("$ENV{'PAPARAZZI_SRC'}/conf/tests_conf.xml"); +my $examples = XMLin("$ENV{'PAPARAZZI_SRC'}/conf/conf_tests.xml"); use Data::Dumper; From 952530864fe3fd21fb98f4bfd48e2babc5f447a7 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 14 Sep 2013 16:07:00 +0200 Subject: [PATCH 290/309] [tools] calibration: improve bounding box in mag plot --- sw/tools/calibration/calibration_utils.py | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/sw/tools/calibration/calibration_utils.py b/sw/tools/calibration/calibration_utils.py index c079fd8bb9..0cc8f54b75 100644 --- a/sw/tools/calibration/calibration_utils.py +++ b/sw/tools/calibration/calibration_utils.py @@ -200,7 +200,6 @@ def plot_mag_3d(measured, calibrated, p): mx = measured[:, 0] my = measured[:, 1] mz = measured[:, 2] - m_max = amax(abs(measured)) # calibrated values cx = calibrated[:, 0] @@ -224,17 +223,24 @@ def plot_mag_3d(measured, calibrated, p): ax.scatter(mx, my, mz) hold(True) # plot line from center to ellipsoid center - ax.plot([0.0, p[0]], [0.0, p[1]], [0.0, p[2]], color='black', marker='+') + ax.plot([0.0, p[0]], [0.0, p[1]], [0.0, p[2]], color='black', marker='+', markersize=10) # plot ellipsoid ax.plot_wireframe(ex, ey, ez, color='grey', alpha=0.5) + # Create cubic bounding box to simulate equal aspect ratio + max_range = np.array([mx.max()-mx.min(), my.max()-my.min(), mz.max()-mz.min()]).max() + Xb = 0.5*max_range*np.mgrid[-1:2:2,-1:2:2,-1:2:2][0].flatten() + 0.5*(mx.max()+mx.min()) + Yb = 0.5*max_range*np.mgrid[-1:2:2,-1:2:2,-1:2:2][1].flatten() + 0.5*(my.max()+my.min()) + Zb = 0.5*max_range*np.mgrid[-1:2:2,-1:2:2,-1:2:2][2].flatten() + 0.5*(mz.max()+mz.min()) + # uncomment following both lines to test the fake bounding box: + #for xb, yb, zb in zip(Xb, Yb, Zb): + # ax.plot([xb], [yb], [zb], 'r*') + ax.set_title('MAG raw with fitted ellipsoid and center offset') ax.set_xlabel('x') ax.set_ylabel('y') ax.set_zlabel('z') - ax.set_xlim3d(-m_max, m_max) - ax.set_ylim3d(-m_max, m_max) - ax.set_zlim3d(-m_max, m_max) + if matplotlib.__version__.startswith('0'): ax = Axes3D(fig, rect=rect_r) From bf49a7f1b24d21bf9834d678294dcfa45c35754b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 14 Sep 2013 19:58:37 +0200 Subject: [PATCH 291/309] [nps] add turbulence --- conf/settings/nps.xml | 1 + sw/simulator/nps/nps_atmosphere.c | 8 +++++++- sw/simulator/nps/nps_atmosphere.h | 1 + sw/simulator/nps/nps_fdm.h | 2 +- sw/simulator/nps/nps_fdm_jsbsim.c | 6 +++++- 5 files changed, 15 insertions(+), 3 deletions(-) diff --git a/conf/settings/nps.xml b/conf/settings/nps.xml index 073e4e0b7f..ba8aa8f8c6 100644 --- a/conf/settings/nps.xml +++ b/conf/settings/nps.xml @@ -10,6 +10,7 @@ + diff --git a/sw/simulator/nps/nps_atmosphere.c b/sw/simulator/nps/nps_atmosphere.c index e676b089cb..d3aba4bfcf 100644 --- a/sw/simulator/nps/nps_atmosphere.c +++ b/sw/simulator/nps/nps_atmosphere.c @@ -39,6 +39,10 @@ #define NPS_WIND_DIR 0 #endif +#ifndef NPS_TURBULENCE_SEVERITY +#define NPS_TURBULENCE_SEVERITY 0 +#endif + struct NpsAtmosphere nps_atmosphere; void nps_atmosphere_init(void) { @@ -46,10 +50,12 @@ void nps_atmosphere_init(void) { nps_atmosphere.qnh = NPS_QNH; nps_atmosphere.wind_speed = NPS_WIND_SPEED; nps_atmosphere.wind_dir = NPS_WIND_DIR; + nps_atmosphere.turbulence_severity = NPS_TURBULENCE_SEVERITY; } void nps_atmosphere_update(double dt __attribute__((unused))) { - nps_fdm_set_wind(nps_atmosphere.wind_speed, nps_atmosphere.wind_dir); + nps_fdm_set_wind(nps_atmosphere.wind_speed, nps_atmosphere.wind_dir, + nps_atmosphere.turbulence_severity); } diff --git a/sw/simulator/nps/nps_atmosphere.h b/sw/simulator/nps/nps_atmosphere.h index 88cc1cf820..683db7e974 100644 --- a/sw/simulator/nps/nps_atmosphere.h +++ b/sw/simulator/nps/nps_atmosphere.h @@ -33,6 +33,7 @@ struct NpsAtmosphere { double qnh; ///< barometric pressure at sea level in Pascal double wind_speed; ///< wind magnitude in m/s double wind_dir; ///< wind direction in radians north=0, increasing CCW + int turbulence_severity; ///< turbulence severity from 0-7 }; extern struct NpsAtmosphere nps_atmosphere; diff --git a/sw/simulator/nps/nps_fdm.h b/sw/simulator/nps/nps_fdm.h index c223c9fda6..99c0ec8691 100644 --- a/sw/simulator/nps/nps_fdm.h +++ b/sw/simulator/nps/nps_fdm.h @@ -94,6 +94,6 @@ extern struct NpsFdm fdm; extern void nps_fdm_init(double dt); extern void nps_fdm_run_step(double* commands); -extern void nps_fdm_set_wind(double speed, double dir); +extern void nps_fdm_set_wind(double speed, double dir, int turbulence_severity); #endif /* NPS_FDM */ diff --git a/sw/simulator/nps/nps_fdm_jsbsim.c b/sw/simulator/nps/nps_fdm_jsbsim.c index 64dd9dc813..30a438d7e2 100644 --- a/sw/simulator/nps/nps_fdm_jsbsim.c +++ b/sw/simulator/nps/nps_fdm_jsbsim.c @@ -180,10 +180,14 @@ void nps_fdm_run_step(double* commands) { } -void nps_fdm_set_wind(double speed, double dir) { +void nps_fdm_set_wind(double speed, double dir, int turbulence_severity) { FGWinds* Winds = FDMExec->GetWinds(); Winds->SetWindspeed(FeetOfMeters(speed)); Winds->SetWindPsi(dir); + + /* wind speed used for turbulence */ + Winds->SetWindspeed20ft(FeetOfMeters(speed)/2); + Winds->SetProbabilityOfExceedence(turbulence_severity); } /** From 7dda3e0a1aedf8caf004d7f6dca6bdc9f5bdeed4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 16 Sep 2013 13:40:41 +0200 Subject: [PATCH 292/309] [conf] aspirin_v2.2: don't set USE_SPI_SLAVE1 by default since most lpc based boards only have one SlaveSelct line (e.g. tiny,twog,yapa, ...) --- conf/firmwares/subsystems/shared/imu_aspirin_v2.2.makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/firmwares/subsystems/shared/imu_aspirin_v2.2.makefile b/conf/firmwares/subsystems/shared/imu_aspirin_v2.2.makefile index f9198a182c..9a1633ad9f 100644 --- a/conf/firmwares/subsystems/shared/imu_aspirin_v2.2.makefile +++ b/conf/firmwares/subsystems/shared/imu_aspirin_v2.2.makefile @@ -47,7 +47,7 @@ include $(CFG_SHARED)/imu_aspirin_v2_common.makefile # so that it will be unselected at init (baro CS line high) # ifeq ($(ARCH), lpc21) -IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE1 +#IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE1 else ifeq ($(ARCH), stm32) # SLAVE3 is on PC13, which is the baro CS IMU_ASPIRIN_2_CFLAGS += -DUSE_SPI_SLAVE3 From c0e0a45260030d1647a5e0499939b39287c166b9 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 16 Sep 2013 14:03:57 +0200 Subject: [PATCH 293/309] [lib] fix default maps file in maps support --- sw/lib/ocaml/maps_support.ml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sw/lib/ocaml/maps_support.ml b/sw/lib/ocaml/maps_support.ml index b6aacd5807..9d15ffe48c 100644 --- a/sw/lib/ocaml/maps_support.ml +++ b/sw/lib/ocaml/maps_support.ml @@ -24,9 +24,10 @@ let home = Env.paparazzi_home let (//) = Filename.concat let maps_xml_path = home // "conf" // "maps.xml" +let maps_xml_default_path = home // "conf" // "maps_example.xml" let maps_xml = ExtXml.parse_file maps_xml_path -let maps_xml_default = ExtXml.parse_file (maps_xml_path^".example") +let maps_xml_default = ExtXml.parse_file (maps_xml_default_path) let gv = try Some (ExtXml.int_attrib maps_xml "google_version") with _ -> None let gv_default = try ExtXml.int_attrib maps_xml_default "google_version" with _ -> 0 From d6a17e308ad340231ad083c54faf46810e25ec19 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 17 Sep 2013 00:55:11 +0200 Subject: [PATCH 294/309] [maps] update_google_version: only one try and 10s timeout --- data/maps/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/maps/Makefile b/data/maps/Makefile index f20aff033b..e13be3e9e8 100644 --- a/data/maps/Makefile +++ b/data/maps/Makefile @@ -21,7 +21,7 @@ $(DATADIR): $(DATADIR)/maps.google.com: $(DATADIR) FORCE @echo "-----------------------------------------------" @echo "DOWNLOAD: google maps version code"; - $(Q)wget -q -t 2 -T 20 -O $(@) http://maps.google.com/ || \ + $(Q)wget -q -t 1 -T 10 -O $(@) http://maps.google.com/ || \ (rm -f $(@) && \ echo "Could not download google maps version code" && \ echo "-----------------------------------------------" && \ From 1a14316e1e1e38f507309b870b9f5f0f58a98593 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 17 Sep 2013 03:38:40 +0200 Subject: [PATCH 295/309] [imu] add LISA_S_UPSIDE_DOWN hack --- sw/airborne/subsystems/imu/imu_aspirin_2_spi.c | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c index 207b0df6ab..ef708b53ee 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c @@ -176,9 +176,21 @@ void imu_aspirin2_event(void) VECT3_ASSIGN(imu.mag_unscaled, -mag.x, -mag.y, mag.z); #else #ifdef LISA_S +#ifdef LISA_S_UPSIDE_DOWN + RATES_ASSIGN(imu.gyro_unscaled, + imu_aspirin2.mpu.data_rates.rates.p, + -imu_aspirin2.mpu.data_rates.rates.q, + -imu_aspirin2.mpu.data_rates.rates.r); + VECT3_ASSIGN(imu.accel_unscaled, + imu_aspirin2.mpu.data_accel.vect.x, + -imu_aspirin2.mpu.data_accel.vect.y, + -imu_aspirin2.mpu.data_accel.vect.z); + VECT3_ASSIGN(imu.mag_unscaled, mag.x, -mag.y, -mag.z); +#else RATES_COPY(imu.gyro_unscaled, imu_aspirin2.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_aspirin2.mpu.data_accel.vect); VECT3_COPY(imu.mag_unscaled, mag); +#endif #else RATES_COPY(imu.gyro_unscaled, imu_aspirin2.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_aspirin2.mpu.data_accel.vect); From f0b857ed40ddb688c51222afe9d963171ad8945a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 21 Sep 2013 11:56:41 +0200 Subject: [PATCH 296/309] [rotorcraft] FAILSAFE mode: neutral attitude, downward vel even if FAILSAFE_GROUND_DETECT not used --- sw/airborne/firmwares/rotorcraft/autopilot.c | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 4a78cdfad4..2f326c1f27 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -137,13 +137,11 @@ INFO("Using FAILSAFE_GROUND_DETECT") } #endif - /* set failsafe commands, if in FAILSAFE or KILL mode */ -#if !FAILSAFE_GROUND_DETECT - if (autopilot_mode == AP_MODE_KILL || - autopilot_mode == AP_MODE_FAILSAFE) { -#else + /* Set fixed "failsafe" commands from airframe file if in KILL mode. + * If in FAILSAFE mode, run normal loops with failsafe attitude and + * downwards velocity setpoints. + */ if (autopilot_mode == AP_MODE_KILL) { -#endif SetCommands(commands_failsafe); } else { From 16d5bd44780784574dfb291005c47d12da651a80 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 21 Sep 2013 15:42:00 +0200 Subject: [PATCH 297/309] [gcs] on flight plan save: correct dtd for subdirs not nice, but works... --- sw/ground_segment/cockpit/editFP.ml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/sw/ground_segment/cockpit/editFP.ml b/sw/ground_segment/cockpit/editFP.ml index 6b87f0c156..8c0e90213b 100644 --- a/sw/ground_segment/cockpit/editFP.ml +++ b/sw/ground_segment/cockpit/editFP.ml @@ -50,7 +50,11 @@ let save_fp = fun geomap -> None -> () | Some file -> let f = open_out file in - fprintf f "\n\n"; + let fp_path = Str.replace_first (Str.regexp Env.flight_plans_path) "" (Filename.dirname file) in + let l = Str.split (Str.regexp Filename.dir_sep) fp_path in + let rel_path = String.concat Filename.dir_sep (Array.to_list (Array.make (List.length l) Filename.parent_dir_name)) in + let fp_dtd = rel_path // "flight_plan.dtd" in + fprintf f "\n\n" fp_dtd; fprintf f "%s\n" (ExtXml.to_string_fmt fp#xml); close_out f; current_fp := Some (fp, file); From 0901318807232ecff90849a6a2648b4602fb4bd7 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 22 Sep 2013 03:02:32 +0200 Subject: [PATCH 298/309] [rotorcraft] failsafe and ground_detect - always reset ground detection - KILL if in FAILSAFE and not in_flight anymore --- sw/airborne/firmwares/rotorcraft/autopilot.c | 28 +++++++++++++++----- 1 file changed, 22 insertions(+), 6 deletions(-) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 2f326c1f27..adf1490c9b 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -129,13 +129,28 @@ void autopilot_init(void) { void autopilot_periodic(void) { RunOnceEvery(NAV_PRESCALER, nav_periodic_task()); + + + /* If in FAILSAFE mode and either already not in_flight anymore + * or just "detected" ground, go to KILL mode. + */ + if (autopilot_mode == AP_MODE_FAILSAFE) { + if (!autopilot_in_flight) + autopilot_set_mode(AP_MODE_KILL); + #if FAILSAFE_GROUND_DETECT -INFO("Using FAILSAFE_GROUND_DETECT") - if (autopilot_mode == AP_MODE_FAILSAFE && autopilot_ground_detected) { - autopilot_set_mode(AP_MODE_KILL); - autopilot_ground_detected = FALSE; - } +INFO("Using FAILSAFE_GROUND_DETECT: KILL") + if (autopilot_ground_detected) + autopilot_set_mode(AP_MODE_KILL); #endif + } + + /* Reset ground detection _after_ running flight plan + */ + if (!autopilot_in_flight || autopilot_ground_detected) { + autopilot_ground_detected = FALSE; + autopilot_detect_ground_once = FALSE; + } /* Set fixed "failsafe" commands from airframe file if in KILL mode. * If in FAILSAFE mode, run normal loops with failsafe attitude and @@ -169,7 +184,6 @@ void autopilot_set_mode(uint8_t new_autopilot_mode) { break; #endif case AP_MODE_KILL: - autopilot_set_motors_on(FALSE); autopilot_in_flight = FALSE; autopilot_in_flight_counter = 0; guidance_h_mode_changed(GUIDANCE_H_MODE_KILL); @@ -213,6 +227,8 @@ void autopilot_set_mode(uint8_t new_autopilot_mode) { break; #endif case AP_MODE_KILL: + autopilot_set_motors_on(FALSE); + stabilization_cmd[COMMAND_THRUST] = 0; guidance_v_mode_changed(GUIDANCE_V_MODE_KILL); break; case AP_MODE_RC_DIRECT: From 255bc0b06d95c670cd983fbbc3d51d14607db220 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 22 Sep 2013 12:40:31 +0200 Subject: [PATCH 299/309] [math] dox cleanup --- sw/airborne/math/pprz_geodetic_double.h | 2 -- sw/airborne/math/pprz_geodetic_float.h | 2 -- sw/airborne/math/pprz_geodetic_int.h | 2 -- 3 files changed, 6 deletions(-) diff --git a/sw/airborne/math/pprz_geodetic_double.h b/sw/airborne/math/pprz_geodetic_double.h index 69df6f8e44..5903506386 100644 --- a/sw/airborne/math/pprz_geodetic_double.h +++ b/sw/airborne/math/pprz_geodetic_double.h @@ -48,8 +48,6 @@ struct EcefCoor_d { /** * @brief vector in Latitude, Longitude and Altitude - * @details Units lat,lon: radians - * Unit alt: meters above MSL */ struct LlaCoor_d { double lon; ///< in radians diff --git a/sw/airborne/math/pprz_geodetic_float.h b/sw/airborne/math/pprz_geodetic_float.h index 9d021880ad..7d964bf742 100644 --- a/sw/airborne/math/pprz_geodetic_float.h +++ b/sw/airborne/math/pprz_geodetic_float.h @@ -48,8 +48,6 @@ struct EcefCoor_f { /** * @brief vector in Latitude, Longitude and Altitude - * @details Units lat,lon: radians - * Unit alt: meters above MSL */ struct LlaCoor_f { float lon; ///< in radians diff --git a/sw/airborne/math/pprz_geodetic_int.h b/sw/airborne/math/pprz_geodetic_int.h index ddd35318fe..f17ff2dc5a 100644 --- a/sw/airborne/math/pprz_geodetic_int.h +++ b/sw/airborne/math/pprz_geodetic_int.h @@ -50,8 +50,6 @@ struct EcefCoor_i { /** * @brief vector in Latitude, Longitude and Altitude - * @details Units lat,lon: radians*1e7 - * Unit alt: centimeters above MSL */ struct LlaCoor_i { int32_t lon; ///< in radians*1e7 From 1aab59fef0a9fd3961b8f90d99cd8bbf0311ff44 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 12:43:21 +0200 Subject: [PATCH 300/309] [airframe] Lisa-S enable possibility for auto-takeoff --- conf/airframes/examples/quadrotor_lisa_s.xml | 24 +++++++++++--------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/conf/airframes/examples/quadrotor_lisa_s.xml b/conf/airframes/examples/quadrotor_lisa_s.xml index 877026c43b..bc0ffa17be 100644 --- a/conf/airframes/examples/quadrotor_lisa_s.xml +++ b/conf/airframes/examples/quadrotor_lisa_s.xml @@ -63,15 +63,16 @@ - - - + + +
+ - +
@@ -117,10 +118,10 @@ - + - + @@ -155,9 +156,9 @@ - - - + + + @@ -172,9 +173,9 @@
- + - +
@@ -201,6 +202,7 @@ + From 8bc84c29c543175443beb1397c0a09fab547e78b Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 12:51:45 +0200 Subject: [PATCH 301/309] [SuperBifRf] Smaller Message for vertical loop tuning --- .../rotorcraft_basic_superbitrf.xml | 113 ++++++++++++++++++ conf/messages.xml | 8 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 8 ++ 3 files changed, 128 insertions(+), 1 deletion(-) create mode 100644 conf/flight_plans/rotorcraft_basic_superbitrf.xml diff --git a/conf/flight_plans/rotorcraft_basic_superbitrf.xml b/conf/flight_plans/rotorcraft_basic_superbitrf.xml new file mode 100644 index 0000000000..635610b6ae --- /dev/null +++ b/conf/flight_plans/rotorcraft_basic_superbitrf.xml @@ -0,0 +1,113 @@ + + + +
+#include "autopilot.h" +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/messages.xml b/conf/messages.xml index 1e38778f87..687c7c3e4d 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -1860,7 +1860,13 @@ - + + + + + + + diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 5a6916b984..96d9cc0666 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -646,6 +646,14 @@ &guidance_v_delta_t); \ } +#define PERIODIC_SEND_TUNE_VERT(_trans, _dev) { \ + DOWNLINK_SEND_TUNE_VERT(_trans, _dev, \ + &guidance_v_z_sp, \ + &ins_ltp_pos.z, \ + &guidance_v_z_ref, \ + &guidance_v_zd_ref); \ + } + #define PERIODIC_SEND_HOVER_LOOP(_trans, _dev) { \ DOWNLINK_SEND_HOVER_LOOP(_trans, _dev, \ &guidance_h_pos_sp.x, \ From 58add4f2523cd6fa0832e076a2ebdea53dbadab5 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 13:35:54 +0200 Subject: [PATCH 302/309] [airframes] TUDelft IMAV Entries --- .../TUDelft/IMAV2013/ARDrone/182_calib.xml | 2 +- .../TUDelft/IMAV2013/ARDrone/184_calib.xml | 18 ++-- .../TUDelft/IMAV2013/ARDrone/186_calib.xml | 21 +++-- .../TUDelft/IMAV2013/ARDrone/188_calib.xml | 21 +++-- .../TUDelft/IMAV2013/ARDrone/189_calib.xml | 21 +++-- .../TUDelft/IMAV2013/ARDrone/190_calib.xml | 16 ++-- .../TUDelft/IMAV2013/ARDrone/191_calib.xml | 16 ++-- .../TUDelft/IMAV2013/ARDrone/192_calib.xml | 2 +- .../TUDelft/IMAV2013/ARDrone/193_calib.xml | 7 +- .../TUDelft/IMAV2013/ARDrone/194_calib.xml | 21 +++-- .../TUDelft/IMAV2013/ARDrone/195_calib.xml | 22 +++-- .../TUDelft/IMAV2013/ARDrone/196_calib.xml | 21 +++-- .../TUDelft/IMAV2013/ardrone2_raw.xml | 30 +++--- .../TUDelft/IMAV2013/chouchou_lisa_s.xml | 44 ++++----- conf/airframes/TUDelft/IMAV2013/conf.xml | 94 ++++++++++--------- .../TUDelft/IMAV2013/mavrick_lisa_s.xml | 13 ++- .../TUDelft/IMAV2013/walkera_V120D02S.xml | 50 +++++----- 17 files changed, 234 insertions(+), 185 deletions(-) diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml index 469c8e94b3..3a14a4338e 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/182_calib.xml @@ -9,7 +9,7 @@ - + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml index f92bae4a6d..383607ba9b 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/184_calib.xml @@ -2,14 +2,16 @@
- - - - - - - - + + + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml index 4b8a0a3b79..92af0c8aac 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/186_calib.xml @@ -2,14 +2,19 @@
- - - - - - - - + + + + + + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml index 688c81d4db..e3e8ef76bf 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/188_calib.xml @@ -2,14 +2,19 @@
- - - - - - - - + + + + + + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml index 688c81d4db..732f7e7065 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/189_calib.xml @@ -2,14 +2,19 @@
- - - - - - - - + + + + + + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml index 688c81d4db..d699f1a956 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/190_calib.xml @@ -1,15 +1,15 @@ - +
- - - - - - - + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml index 688c81d4db..b5af215403 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/191_calib.xml @@ -1,15 +1,15 @@ - +
- - - - - - - + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml index 688c81d4db..d6dd75562f 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/192_calib.xml @@ -9,7 +9,7 @@ - + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml index 688c81d4db..8fd05e01ae 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/193_calib.xml @@ -2,6 +2,11 @@
+ + + + + @@ -9,7 +14,7 @@ - + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml index 688c81d4db..14840c8c1e 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/194_calib.xml @@ -2,14 +2,19 @@
- - - - - - - - + + + + + + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml index 688c81d4db..36ef1433a2 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/195_calib.xml @@ -1,15 +1,21 @@ - +
+ + + + + - - - - - - - + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml b/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml index 688c81d4db..294856f650 100644 --- a/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml +++ b/conf/airframes/TUDelft/IMAV2013/ARDrone/196_calib.xml @@ -2,14 +2,19 @@
- - - - - - - - + + + + + + + + + + + + + diff --git a/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml b/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml index c67a98311e..cf2739449c 100644 --- a/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml +++ b/conf/airframes/TUDelft/IMAV2013/ardrone2_raw.xml @@ -11,15 +11,15 @@ - + - + - + @@ -36,6 +36,8 @@ + + @@ -58,7 +60,7 @@ - + @@ -76,10 +78,6 @@
- - - - @@ -89,9 +87,9 @@
- - - + + +
@@ -185,10 +183,10 @@
- + - +
@@ -200,9 +198,9 @@
- - - + + +
diff --git a/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml index ace2179575..7a870f3b9c 100644 --- a/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/chouchou_lisa_s.xml @@ -55,12 +55,12 @@ - - - - - - + + + + + + @@ -71,12 +71,12 @@
- +
- +
@@ -106,29 +106,29 @@ - + - + - - + + - - - + + + - - - + + + @@ -154,14 +154,14 @@ - - - + + + - +
diff --git a/conf/airframes/TUDelft/IMAV2013/conf.xml b/conf/airframes/TUDelft/IMAV2013/conf.xml index 9c7ec3c285..dff3725763 100644 --- a/conf/airframes/TUDelft/IMAV2013/conf.xml +++ b/conf/airframes/TUDelft/IMAV2013/conf.xml @@ -1,22 +1,12 @@ - + + diff --git a/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml index 7f719564ee..1dc80175b2 100644 --- a/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml +++ b/conf/airframes/TUDelft/IMAV2013/mavrick_lisa_s.xml @@ -28,11 +28,14 @@ + + + @@ -40,10 +43,12 @@ - - + + + + - + @@ -77,7 +82,7 @@
- + diff --git a/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml b/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml index a11d9f889b..2ee2d7548e 100644 --- a/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml +++ b/conf/airframes/TUDelft/IMAV2013/walkera_V120D02S.xml @@ -50,12 +50,12 @@ - - - - - - + + + + + +
@@ -85,45 +85,43 @@ - - - + - - + + - + - - + + - + - - + + - + - + - - - + + + - + @@ -157,9 +155,9 @@
- - - + + +
From 27ec6e0d37221b7f3a36978c2981c200d2c2c11d Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 14:00:07 +0200 Subject: [PATCH 303/309] [Module] Flight time left --- conf/modules/flight_time.xml | 18 ++++++++++ conf/settings/modules/flight_time.xml | 9 +++++ sw/airborne/modules/time/flight_time.c | 46 ++++++++++++++++++++++++++ sw/airborne/modules/time/flight_time.h | 39 ++++++++++++++++++++++ 4 files changed, 112 insertions(+) create mode 100644 conf/modules/flight_time.xml create mode 100644 conf/settings/modules/flight_time.xml create mode 100644 sw/airborne/modules/time/flight_time.c create mode 100644 sw/airborne/modules/time/flight_time.h diff --git a/conf/modules/flight_time.xml b/conf/modules/flight_time.xml new file mode 100644 index 0000000000..46ab86b367 --- /dev/null +++ b/conf/modules/flight_time.xml @@ -0,0 +1,18 @@ + + + + + + Flight time calculator + Allows to check how much time is left before the end of the competition. + + +
+ +
+ + + + + +
\ No newline at end of file diff --git a/conf/settings/modules/flight_time.xml b/conf/settings/modules/flight_time.xml new file mode 100644 index 0000000000..312ec12ecc --- /dev/null +++ b/conf/settings/modules/flight_time.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/sw/airborne/modules/time/flight_time.c b/sw/airborne/modules/time/flight_time.c new file mode 100644 index 0000000000..16328c7c84 --- /dev/null +++ b/sw/airborne/modules/time/flight_time.c @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2013 Elisabeth van der Sman, 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file modules/time/flight_time.c + * + * Flight time counter that can be set from the gcs + */ + +#include "flight_time.h" +#include "generated/airframe.h" + +uint16_t time_until_land; + +#ifndef FLIGHT_TIME_LEFT +#define FLIGHT_TIME_LEFT 10000 +#endif + +void flight_time_init(void) { + time_until_land = FLIGHT_TIME_LEFT; +} + +void flight_time_periodic( void ) { + // Count downwards + if(time_until_land > 0) + time_until_land--; +} diff --git a/sw/airborne/modules/time/flight_time.h b/sw/airborne/modules/time/flight_time.h new file mode 100644 index 0000000000..2a4ff41f89 --- /dev/null +++ b/sw/airborne/modules/time/flight_time.h @@ -0,0 +1,39 @@ +/* + * Copyright (C) 2013 Elisabeth van der Sman, 2013 Freek van Tienen + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** + * @file modules/time/flight_time.h + * + * Flight time counter that can be set from the gcs + */ + +#ifndef FLIGHT_TIME_H +#define FLIGHT_TIME_H + +#include "std.h" + +extern uint16_t time_until_land; + +void flight_time_init(void); +void flight_time_periodic(void); + +#endif /* FLIGHT_TIME_H */ From 12e78eb5468c65533450831ce21a2e11913241d1 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 14:02:24 +0200 Subject: [PATCH 304/309] [board] Fireswarm --- sw/tools/dfu/stm32_mem.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sw/tools/dfu/stm32_mem.py b/sw/tools/dfu/stm32_mem.py index 48418433f2..7219e7efd3 100644 --- a/sw/tools/dfu/stm32_mem.py +++ b/sw/tools/dfu/stm32_mem.py @@ -136,6 +136,7 @@ if __name__ == "__main__": valid_manufacturers.append("Transition Robotics Inc.") valid_manufacturers.append("STMicroelectronics") valid_manufacturers.append("Black Sphere Technologies") + valid_manufacturers.append("TUDelft MavLab. 2012->13") # list of tuples with possible stm32 (autopilot) devices stm32devs = [] @@ -167,7 +168,7 @@ if __name__ == "__main__": if options.product == "any": stm32devs.append((dfudev, man, product, serial)) elif options.product == "Lisa/Lia": - if "Lisa/M" in product or "Lia" in product: + if "Lisa/M" in product or "Lia" in product or "Fireswarm" in product: stm32devs.append((dfudev, man, product, serial)) if not stm32devs: From f652bae7e91ec8963fe5dd9a52c2c8f480d8c0cf Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 14:35:19 +0200 Subject: [PATCH 305/309] [Ocaml] Block and Setting numbers --- sw/tools/gen_flight_plan.ml | 9 +++++++++ sw/tools/gen_settings.ml | 10 ++++++++++ 2 files changed, 19 insertions(+) diff --git a/sw/tools/gen_flight_plan.ml b/sw/tools/gen_flight_plan.ml index cdcdad33ac..972704966b 100644 --- a/sw/tools/gen_flight_plan.ml +++ b/sw/tools/gen_flight_plan.ml @@ -794,6 +794,15 @@ let () = Xml2h.define "HOME_MODE_HEIGHT" (sof home_mode_height); Xml2h.define "MAX_DIST_FROM_HOME" (sof mdfh); + (** Print defines for blocks **) + lprintf "\n"; + let idx = ref 0 in + List.iter + (fun s -> + let v = ExtXml.attrib s "name" in + lprintf "#define BLOCK_%s %d\n" (Str.global_replace (Str.regexp "[\\. ]") "_" v) !idx; incr idx) blocks; + lprintf "\n"; + let index_of_waypoints = let i = ref (-1) in List.map (fun w -> incr i; (name_of w, !i)) waypoints in diff --git a/sw/tools/gen_settings.ml b/sw/tools/gen_settings.ml index 32313bd37a..087d477f22 100644 --- a/sw/tools/gen_settings.ml +++ b/sw/tools/gen_settings.ml @@ -68,6 +68,16 @@ let print_dl_settings = fun settings -> lprintf "#include \"generated/periodic_telemetry.h\"\n"; lprintf "\n"; + (** Datalink knowing what settings mean **) + let idx = ref 0 in + lprintf "\n"; + List.iter + (fun s -> + let v = ExtXml.attrib s "var" in + lprintf "#define SETTINGS_%s %d\n" (Str.global_replace (Str.regexp "\\.") "_" v) !idx; incr idx) + settings; + lprintf "\n"; + (** Macro to call to set one variable *) lprintf "#define DlSetting(_idx, _value) { \\\n"; right (); From 70ab7ebfdf264e5e308ccc65d431fee443daa674 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Sun, 22 Sep 2013 15:34:43 +0200 Subject: [PATCH 306/309] [ArDrone] Navdata decoder update (incl sonar) --- conf/messages.xml | 7 +- sw/airborne/boards/ardrone/electrical_raw.c | 3 +- sw/airborne/boards/ardrone/navdata.c | 237 +++++++++---------- sw/airborne/boards/ardrone/navdata.h | 23 +- sw/airborne/firmwares/rotorcraft/telemetry.h | 39 ++- sw/airborne/subsystems/sonar.h | 4 + 6 files changed, 162 insertions(+), 151 deletions(-) create mode 100644 sw/airborne/subsystems/sonar.h diff --git a/conf/messages.xml b/conf/messages.xml index 687c7c3e4d..435a83c755 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -48,6 +48,7 @@ + @@ -626,7 +627,11 @@ - + + + + + diff --git a/sw/airborne/boards/ardrone/electrical_raw.c b/sw/airborne/boards/ardrone/electrical_raw.c index 56acd4d9cc..6ffc6a8f5a 100644 --- a/sw/airborne/boards/ardrone/electrical_raw.c +++ b/sw/airborne/boards/ardrone/electrical_raw.c @@ -69,7 +69,8 @@ int fd; void electrical_init(void) { // First we try to kill the program.elf if it is running (done here because initializes first) - system("killall -9 program.elf"); + int ret = system("killall -9 program.elf"); + (void) ret; // Initialize 12c device for power fd = open( "/dev/i2c-1", O_RDWR ); diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 1ddd68a5aa..e4f43a136a 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -36,26 +36,26 @@ #include #include #include + +#include "std.h" #include "navdata.h" +#include "subsystems/ins.h" #define NAVDATA_PACKET_SIZE 60 -#define NAVDATA_BUFFER_SIZE 80 #define NAVDATA_START_BYTE 0x3a -typedef struct { - uint8_t isInitialized; - uint8_t isOpen; - uint16_t bytesRead; - uint32_t totalBytesRead; - uint32_t packetsRead; - uint8_t buffer[NAVDATA_BUFFER_SIZE]; -} navdata_port; - -static navdata_port port; -static int nav_fd; +static inline bool_t acquire_baro_calibration(void); +static void navdata_cropbuffer(int cropsize); +navdata_port nav_port; +static int nav_fd = 0; +static int16_t previousUltrasoundHeight; measures_t navdata; +#include "subsystems/sonar.h" +uint16_t sonar_meas = 0; + + // FIXME(ben): there must be a better home for these ssize_t full_write(int fd, const uint8_t *buf, size_t count) { @@ -100,15 +100,15 @@ static void navdata_write(const uint8_t *buf, size_t count) perror("navdata_write: Write failed"); } -int navdata_init() +bool_t navdata_init() { - nav_fd = open("/dev/ttyO1", O_RDWR | O_NOCTTY | O_NONBLOCK); - if (nav_fd == -1) - { - perror("navdata_init: Unable to open /dev/ttyO1 - "); - return 1; - } else { - port.isOpen = 1; + if (nav_fd <= 0) { + nav_fd = open("/dev/ttyO1", O_RDWR | O_NOCTTY | O_NONBLOCK); + + if (nav_fd == -1) { + perror("navdata_init: Unable to open /dev/ttyO1 - "); + return FALSE; + } } fcntl(nav_fd, F_SETFL, 0); //read calls are non blocking @@ -132,31 +132,40 @@ int navdata_init() uint8_t cmd=0x02; navdata_write(&cmd, 1); - baro_calibrated = 0; - acquire_baro_calibration(); + // read some potential dirt (retry alot of times) + char tmp[100]; + for(int i = 0; i < 100; i++) { + uint16_t dirt = read(nav_fd, tmp, sizeof tmp); + (void) dirt; + + cmd=0x02; + navdata_write(&cmd, 1); + usleep(200); + } + + baro_calibrated = FALSE; + if(!acquire_baro_calibration()) + return FALSE; // start acquisition - cmd=0x01; + cmd = 0x01; navdata_write(&cmd, 1); - navdata_imu_available = 0; - navdata_baro_available = 0; - - port.bytesRead = 0; - port.totalBytesRead = 0; - port.packetsRead = 0; - port.isInitialized = 1; + navdata_imu_available = FALSE; + navdata_baro_available = FALSE; previousUltrasoundHeight = 0; + nav_port.checksum_errors = 0; + nav_port.bytesRead = 0; + nav_port.totalBytesRead = 0; + nav_port.packetsRead = 0; + nav_port.isInitialized = TRUE; - return 0; + return TRUE; } -void acquire_baro_calibration() +static inline bool_t acquire_baro_calibration(void) { - char tmp[100]; - read(nav_fd, tmp, sizeof tmp); // read some potential dirt - // start baro calibration acquisition uint8_t cmd=0x17; // send cmd 23 navdata_write(&cmd, 1); @@ -166,7 +175,7 @@ void acquire_baro_calibration() if (full_read(nav_fd, calibBuffer, sizeof calibBuffer) < 0) { perror("acquire_baro_calibration: read failed"); - return; + return FALSE; } baro_calibration.ac1 = calibBuffer[0] << 8 | calibBuffer[1]; @@ -195,32 +204,19 @@ void acquire_baro_calibration() printf("Calibration MC: %d\n", baro_calibration.mc); printf("Calibration MD: %d\n", baro_calibration.md); - baro_calibrated = 1; -} - -void navdata_close() -{ - port.isOpen = 0; - close(nav_fd); + baro_calibrated = TRUE; + return TRUE; } void navdata_read() { - int newbytes = 0; - - if (port.isInitialized != 1) - navdata_init(); - - if (port.isOpen != 1) - return; - - newbytes = read(nav_fd, port.buffer+port.bytesRead, NAVDATA_BUFFER_SIZE-port.bytesRead); + int newbytes = read(nav_fd, nav_port.buffer+nav_port.bytesRead, NAVDATA_BUFFER_SIZE-nav_port.bytesRead); // because non-blocking read returns -1 when no bytes available if (newbytes > 0) { - port.bytesRead += newbytes; - port.totalBytesRead += newbytes; + nav_port.bytesRead += newbytes; + nav_port.totalBytesRead += newbytes; } } @@ -235,7 +231,7 @@ static void baro_update_logic(void) if (temp_or_press_was_updated_last == 0) // Last update was press so we are now waiting for temp { // temp was updated - temp_or_press_was_updated_last = 1; + temp_or_press_was_updated_last = TRUE; // This means that press must remain constant if (lastpressval != 0) @@ -244,16 +240,16 @@ static void baro_update_logic(void) if (lastpressval != navdata.pressure) { // wait for temp again - temp_or_press_was_updated_last = 0; + temp_or_press_was_updated_last = FALSE; sync_errors++; - navdata_baro_available = 1; + navdata_baro_available = TRUE; } } } else { // press was updated - temp_or_press_was_updated_last = 0; + temp_or_press_was_updated_last = FALSE; // This means that temp must remain constant if (lasttempval != 0) @@ -262,37 +258,52 @@ static void baro_update_logic(void) if (lasttempval != navdata.temperature_pressure) { // wait for press again - temp_or_press_was_updated_last = 1; + temp_or_press_was_updated_last = TRUE; sync_errors++; } } - navdata_baro_available = 1; + navdata_baro_available = TRUE; } lastpressval = navdata.pressure; lasttempval = navdata.temperature_pressure; - - // debug - // navdata->temperature_pressure = sync_errors; } void navdata_update() { + static bool_t last_checksum_wrong = FALSE; + // Check if initialized + if (!nav_port.isInitialized) { + navdata_init(); + return; + } + + // Start reading navdata_read(); // while there is something interesting to do... - while (port.bytesRead >= NAVDATA_PACKET_SIZE) + while (nav_port.bytesRead >= NAVDATA_PACKET_SIZE) { - if (port.buffer[0] == NAVDATA_START_BYTE) + if (nav_port.buffer[0] == NAVDATA_START_BYTE) { - // if checksum is OK - if ( 1 ) // we dont know how to calculate the checksum -// if ( navdata_checksum() == 0 ) - { - assert(sizeof navdata == NAVDATA_PACKET_SIZE); - memcpy(&navdata, port.buffer, NAVDATA_PACKET_SIZE); + assert(sizeof navdata == NAVDATA_PACKET_SIZE); + memcpy(&navdata, nav_port.buffer, NAVDATA_PACKET_SIZE); + // Calculating the checksum + uint16_t checksum = 0; + for(int i = 2; i < NAVDATA_PACKET_SIZE-2; i += 2) { + checksum += nav_port.buffer[i] + (nav_port.buffer[i+1] << 8); + } + + // When checksum is incorrect + if(navdata.chksum != checksum) { + printf("Checksum error [calculated: %d] [packet: %d] [diff: %d]\n",checksum , navdata.chksum, checksum-navdata.chksum); + nav_port.checksum_errors++; + } + + // When we already dropped a packet or checksum is correct + if(last_checksum_wrong || navdata.chksum == checksum) { // Invert byte order so that TELEMETRY works better uint8_t tmp; uint8_t* p = (uint8_t*) &(navdata.pressure); @@ -306,87 +317,59 @@ void navdata_update() baro_update_logic(); - navdata_imu_available = 1; +#ifdef USE_SONAR + if (navdata.ultrasound < 10000) + { + sonar_meas = navdata.ultrasound; + ins_update_sonar(); - port.packetsRead++; -// printf("CCRC=%d, GCRC=%d, error=%d\n", crc, navdata->chksum, abs(crc-navdata->chksum)); - //navdata_getHeight(); + } +#endif + + + navdata_imu_available = TRUE; + last_checksum_wrong = FALSE; + nav_port.packetsRead++; } - navdata_CropBuffer(NAVDATA_PACKET_SIZE); + + // Crop the buffer + navdata_cropbuffer(NAVDATA_PACKET_SIZE); } else { // find start byte, copy all data from startbyte to buffer origin, update bytesread uint8_t * pint; - pint = memchr(port.buffer, NAVDATA_START_BYTE, port.bytesRead); + pint = memchr(nav_port.buffer, NAVDATA_START_BYTE, nav_port.bytesRead); if (pint != NULL) { - navdata_CropBuffer(pint - port.buffer); + navdata_cropbuffer(pint - nav_port.buffer); } else { // if the start byte was not found, it means there is junk in the buffer - port.bytesRead = 0; + nav_port.bytesRead = 0; } } } } -void navdata_CropBuffer(int cropsize) -{ - if (port.bytesRead - cropsize < 0) { - // TODO think about why the amount of bytes read minus the cropsize gets below zero - printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%p\n", port.bytesRead, cropsize, port.buffer); - return; - } - - memmove(port.buffer, port.buffer+cropsize, NAVDATA_BUFFER_SIZE-cropsize); - port.bytesRead -= cropsize; -} - -int16_t navdata_getHeight() { - +int16_t navdata_height(void) { if (navdata.ultrasound > 10000) { return previousUltrasoundHeight; } int16_t ultrasoundHeight = 0; - ultrasoundHeight = (navdata.ultrasound - 880) / 26.553; - previousUltrasoundHeight = ultrasoundHeight; - return ultrasoundHeight; } -// The checksum should be calculated here: we don't know the algorithm -uint16_t navdata_checksum() { - navdata_cks = 0; - navdata_cks += navdata.nu_trame; - navdata_cks += navdata.ax; - navdata_cks += navdata.ay; - navdata_cks += navdata.az; - navdata_cks += navdata.vx; - navdata_cks += navdata.vy; - navdata_cks += navdata.vz; - navdata_cks += navdata.temperature_acc; - navdata_cks += navdata.temperature_gyro; - navdata_cks += navdata.ultrasound; - navdata_cks += navdata.us_debut_echo; - navdata_cks += navdata.us_fin_echo; - navdata_cks += navdata.us_association_echo; - navdata_cks += navdata.us_distance_echo; - navdata_cks += navdata.us_curve_time; - navdata_cks += navdata.us_curve_value; - navdata_cks += navdata.us_curve_ref; - navdata_cks += navdata.nb_echo; - navdata_cks += navdata.sum_echo; - navdata_cks += navdata.gradient; - navdata_cks += navdata.flag_echo_ini; - navdata_cks += navdata.pressure; - navdata_cks += navdata.temperature_pressure; - navdata_cks += navdata.mx; - navdata_cks += navdata.my; - navdata_cks += navdata.mz; -// navdata_cks += navdata->chksum; +static void navdata_cropbuffer(int cropsize) +{ + if (nav_port.bytesRead - cropsize < 0) { + // TODO think about why the amount of bytes read minus the cropsize gets below zero + printf("BytesRead(=%d) - Cropsize(=%d) may not be below zero. port->buffer=%p\n", nav_port.bytesRead, cropsize, nav_port.buffer); + return; + } - return 0; // we dont know how to calculate the checksum + memmove(nav_port.buffer, nav_port.buffer+cropsize, NAVDATA_BUFFER_SIZE-cropsize); + nav_port.bytesRead -= cropsize; } diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index dd3b36f68b..3ed578669c 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -95,25 +95,30 @@ struct bmp180_baro_calibration int32_t b5; }; +#define NAVDATA_BUFFER_SIZE 80 +typedef struct { + uint8_t isInitialized; + uint16_t bytesRead; + uint32_t totalBytesRead; + uint32_t packetsRead; + uint32_t checksum_errors; + uint8_t buffer[NAVDATA_BUFFER_SIZE]; +} navdata_port; + extern measures_t navdata; +extern navdata_port nav_port; struct bmp180_baro_calibration baro_calibration; +navdata_port* port; uint16_t navdata_cks; uint8_t navdata_imu_available; uint8_t navdata_baro_available; int16_t previousUltrasoundHeight; uint8_t baro_calibrated; -int navdata_init(void); -void navdata_close(void); - +bool_t navdata_init(void); void navdata_read(void); void navdata_update(void); -void navdata_CropBuffer(int cropsize); - -uint16_t navdata_checksum(void); -int16_t navdata_getHeight(void); - -void acquire_baro_calibration(void); +int16_t navdata_height(void); ssize_t full_write(int fd, const uint8_t *buf, size_t count); ssize_t full_read(int fd, uint8_t *buf, size_t count); diff --git a/sw/airborne/firmwares/rotorcraft/telemetry.h b/sw/airborne/firmwares/rotorcraft/telemetry.h index 96d9cc0666..808a6371a6 100644 --- a/sw/airborne/firmwares/rotorcraft/telemetry.h +++ b/sw/airborne/firmwares/rotorcraft/telemetry.h @@ -991,7 +991,8 @@ &navdata.mx, \ &navdata.my, \ &navdata.mz, \ - &navdata.chksum \ + &navdata.chksum, \ + &nav_port.checksum_errors \ ) #else #define PERIODIC_SEND_ARDRONE_NAVDATA(_trans, _dev) {} @@ -1006,10 +1007,13 @@ #ifdef USE_UART1 #define PERIODIC_SEND_UART1_ERRORS(_trans, _dev) { \ const uint8_t _bus1 = 1; \ + uint16_t ore = uart1.ore; \ + uint16_t ne_err = uart1.ne_err; \ + uint16_t fe_err = uart1.fe_err; \ DOWNLINK_SEND_UART_ERRORS(_trans, _dev, \ - &uart1.ore, \ - &uart1.ne_err, \ - &uart1.fe_err, \ + &ore, \ + &ne_err, \ + &fe_err, \ &_bus1); \ } #else @@ -1019,10 +1023,13 @@ #ifdef USE_UART2 #define PERIODIC_SEND_UART2_ERRORS(_trans, _dev) { \ const uint8_t _bus2 = 2; \ + uint16_t ore = uart2.ore; \ + uint16_t ne_err = uart2.ne_err; \ + uint16_t fe_err = uart2.fe_err; \ DOWNLINK_SEND_UART_ERRORS(_trans, _dev, \ - &uart2.ore, \ - &uart2.ne_err, \ - &uart2.fe_err, \ + &ore, \ + &ne_err, \ + &fe_err, \ &_bus2); \ } #else @@ -1032,10 +1039,13 @@ #ifdef USE_UART3 #define PERIODIC_SEND_UART3_ERRORS(_trans, _dev) { \ const uint8_t _bus3 = 3; \ + uint16_t ore = uart3.ore; \ + uint16_t ne_err = uart3.ne_err; \ + uint16_t fe_err = uart3.fe_err; \ DOWNLINK_SEND_UART_ERRORS(_trans, _dev, \ - &uart3.ore, \ - &uart3.ne_err, \ - &uart3.fe_err, \ + &ore, \ + &ne_err, \ + &fe_err, \ &_bus3); \ } #else @@ -1045,10 +1055,13 @@ #ifdef USE_UART5 #define PERIODIC_SEND_UART5_ERRORS(_trans, _dev) { \ const uint8_t _bus5 = 5; \ + uint16_t ore = uart5.ore; \ + uint16_t ne_err = uart5.ne_err; \ + uint16_t fe_err = uart5.fe_err; \ DOWNLINK_SEND_UART_ERRORS(_trans, _dev, \ - &uart5.ore, \ - &uart5.ne_err, \ - &uart5.fe_err, \ + &ore, \ + &ne_err, \ + &fe_err, \ &_bus5); \ } #else diff --git a/sw/airborne/subsystems/sonar.h b/sw/airborne/subsystems/sonar.h new file mode 100644 index 0000000000..daf310400d --- /dev/null +++ b/sw/airborne/subsystems/sonar.h @@ -0,0 +1,4 @@ + + + +extern uint16_t sonar_meas; From 84482d8856d8ea29d8b813b2987bd5c04ed950ff Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Mon, 23 Sep 2013 17:36:05 +0200 Subject: [PATCH 307/309] [fix] cleaning - remove compilation warning in gen_airframe - better (?) ocaml relative path substitution for editFP --- sw/ground_segment/cockpit/editFP.ml | 6 ++---- sw/tools/gen_airframe.ml | 2 +- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/sw/ground_segment/cockpit/editFP.ml b/sw/ground_segment/cockpit/editFP.ml index 8c0e90213b..3a3673736f 100644 --- a/sw/ground_segment/cockpit/editFP.ml +++ b/sw/ground_segment/cockpit/editFP.ml @@ -51,10 +51,8 @@ let save_fp = fun geomap -> | Some file -> let f = open_out file in let fp_path = Str.replace_first (Str.regexp Env.flight_plans_path) "" (Filename.dirname file) in - let l = Str.split (Str.regexp Filename.dir_sep) fp_path in - let rel_path = String.concat Filename.dir_sep (Array.to_list (Array.make (List.length l) Filename.parent_dir_name)) in - let fp_dtd = rel_path // "flight_plan.dtd" in - fprintf f "\n\n" fp_dtd; + let rel_path = Str.global_replace (Str.regexp (Printf.sprintf "%s[^%s]+" Filename.dir_sep Filename.dir_sep)) (Filename.parent_dir_name // "") fp_path in + fprintf f "\n\n" rel_path "flight_plan.dtd"; fprintf f "%s\n" (ExtXml.to_string_fmt fp#xml); close_out f; current_fp := Some (fp, file); diff --git a/sw/tools/gen_airframe.ml b/sw/tools/gen_airframe.ml index 8e066b3ec4..d18fead422 100644 --- a/sw/tools/gen_airframe.ml +++ b/sw/tools/gen_airframe.ml @@ -281,7 +281,7 @@ let rec parse_section = fun ac_id s -> List.iter (fun d -> printf " Actuators%sInit();\\\n" d) drivers; printf "}\n\n"; | "include" -> - let filename = Str.global_replace (Str.regexp "\$AC_ID") ac_id (ExtXml.attrib s "href") in + let filename = Str.global_replace (Str.regexp "\\$AC_ID") ac_id (ExtXml.attrib s "href") in let subxml = Xml.parse_file filename in printf "/* XML %s */" filename; nl (); From 0c8572cce2579f115baf316fc33022a8fa6b79a7 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Mon, 23 Sep 2013 18:01:27 +0200 Subject: [PATCH 308/309] [fix] previousUltrasonicHeight in navdata is static now --- sw/airborne/boards/ardrone/navdata.h | 1 - 1 file changed, 1 deletion(-) diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 3ed578669c..f41b52a9c0 100644 --- a/sw/airborne/boards/ardrone/navdata.h +++ b/sw/airborne/boards/ardrone/navdata.h @@ -112,7 +112,6 @@ navdata_port* port; uint16_t navdata_cks; uint8_t navdata_imu_available; uint8_t navdata_baro_available; -int16_t previousUltrasoundHeight; uint8_t baro_calibrated; bool_t navdata_init(void); From 7c474917e056868da375e7f8c7c80f6dfe5cdf24 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 23 Sep 2013 00:10:09 +0200 Subject: [PATCH 309/309] [dox] fix some more MSL vs. ellpsiod alt comments --- sw/airborne/state.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/state.h b/sw/airborne/state.h index cb5d101555..ee1436f1c4 100644 --- a/sw/airborne/state.h +++ b/sw/airborne/state.h @@ -148,7 +148,7 @@ struct State { /** * Position in Latitude, Longitude and Altitude. * Units lat,lon: radians*1e7 - * Units alt: centimeters above MSL + * Units alt: milimeters above reference ellipsoid */ struct LlaCoor_i lla_pos_i; @@ -196,7 +196,7 @@ struct State { /** * Position in Latitude, Longitude and Altitude. * Units lat,lon: radians - * Units alt: meters above MSL + * Units alt: meters above reference ellipsoid */ struct LlaCoor_f lla_pos_f;