116 changes: 116 additions & 0 deletions conf/flight_plans/rotorcraft_joystick_enac.xml
@@ -0,0 +1,116 @@
<!DOCTYPE flight_plan SYSTEM "flight_plan.dtd">

<flight_plan alt="148" ground_alt="146" lat0="43.5640917" lon0="1.4829201" max_dist_from_home="20" name="Rotorcraft Optitrack (ENAC)" security_height="0.3">
<header>
#ifdef NAV_C
#include "firmwares/rotorcraft/stabilization/stabilization_attitude.h"
#include "autopilot.h"
static inline void joystick_handler(uint8_t sender_id __attribute__((unused)), int16_t roll, int16_t pitch, int16_t yaw, int16_t throttle) {
if (And(autopilot_get_mode() == AP_MODE_NAV, nav_block == joystick_block)) {
nav_roll = ANGLE_BFP_OF_REAL(STABILIZATION_ATTITUDE_SP_MAX_PHI * roll / MAX_PPRZ);
nav_pitch = ANGLE_BFP_OF_REAL(STABILIZATION_ATTITUDE_SP_MAX_THETA * pitch / MAX_PPRZ);
nav_heading = ANGLE_BFP_OF_REAL(3.1416f * yaw / MAX_PPRZ);
nav_throttle = throttle;
}
}
#endif
</header>
<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="GOAL" x="2.0" y="2.0"/>
<waypoint name="STDBY" x="-0.7" y="-0.8"/>
<waypoint name="TD" x="0.8" y="-1.7"/>
<waypoint name="S1" x="3" y="4"/>
<waypoint name="S2" x="3" y="-4"/>
<waypoint name="S3" x="-3" y="-4"/>
<waypoint name="S4" x="-3" y="4"/>
<waypoint name="_N1" x="4.5" y="5.2"/>
<waypoint name="_N2" x="4.5" y="-5.2"/>
<waypoint name="_N3" x="-4.5" y="-5.2"/>
<waypoint name="_N4" x="-4.5" y="5.2"/>
</waypoints>
<sectors>
<sector name="Net" color="red">
<corner name="_N1"/>
<corner name="_N2"/>
<corner name="_N3"/>
<corner name="_N4"/>
</sector>
<sector name="Survey" color="green" type="dynamic">
<corner name="S1"/>
<corner name="S2"/>
<corner name="S3"/>
<corner name="S4"/>
</sector>
</sectors>
<variables>
<variable var="joystick_block" type="uint8_t" init="255"/>
<abi_binding name="JOYSTICK" handler="joystick_handler"/>
</variables>
<modules>
<module name="nav" type="survey_rectangle_rotorcraft"/>
<module name="joystick"/>
</modules>
<blocks>
<block name="Wait GPS">
<call_once fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<block name="Holding point">
<call_once fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Start Engine">
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 1.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="STDBY"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
</block>
<block name="START" strip_button="Go" strip_icon="lookfore.png">
<call_once fun="NavSetWaypointHere(WP_GOAL)"/>
</block>
<block name="StayGoal">
<stay wp="GOAL"/>
</block>
<block name="Joystick" strip_button="J">
<set var="horizontal_mode" value="HORIZONTAL_MODE_ATTITUDE"/>
<set var="vertical_mode" value="VERTICAL_MODE_MANUAL"/>
<set var="joystick_block" value="nav_block"/>
<while cond="TRUE"/>
</block>
<block group="extra_pattern" name="Survey S1-S2 Sweep NS SET" strip_button="SvySweep-NS" strip_icon="survey_rect_ns.png">
<call_once fun="nav_survey_rectangle_rotorcraft_setup(WP_S1, WP_S3, 1, NS)"/>
<deroute block="Survey RECTANGLE RUN"/>
</block>
<block group="extra_pattern" name="Survey S1-S2 Sweep WE SET" strip_button="SvySweep-WE" strip_icon="survey_rect_we.png">
<call_once fun="nav_survey_rectangle_rotorcraft_setup(WP_S1, WP_S3, 1, WE)"/>
<deroute block="Survey RECTANGLE RUN"/>
</block>
<block group="extra_pattern" name="Survey RECTANGLE RUN" strip_button="SvySweep CONT" strip_icon="survey_rect_run.png">
<exception cond="rectangle_survey_sweep_num == 1" deroute="Standby"/>
<call fun="nav_survey_rectangle_rotorcraft_run(WP_S1, WP_S3)"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="land">
<go wp="TD"/>
</block>
<block name="flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
33 changes: 0 additions & 33 deletions conf/flight_plans/sectors.xml

This file was deleted.

File renamed without changes.
408 changes: 0 additions & 408 deletions conf/flight_plans/tudelft/obc2016/include_obc2016_mission.xml

This file was deleted.

90 changes: 0 additions & 90 deletions conf/flight_plans/tudelft/obc2016/include_obc2016_safety.xml

This file was deleted.

71 changes: 0 additions & 71 deletions conf/flight_plans/tudelft/obc2016/obc2016.xml

This file was deleted.

101 changes: 101 additions & 0 deletions conf/flight_plans/tudelft/rotorcraft_optitrack_path.xml
@@ -0,0 +1,101 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">

<flight_plan alt="1.0" ground_alt="0" lat0="51.990634" lon0="4.376789"
max_dist_from_home="8" name="Test flight plan" security_height="0.4">
<header>
#include "autopilot.h"
#include "subsystems/radio_control.h"
#include "subsystems/ahrs.h"
#include "subsystems/electrical.h"
#include "subsystems/datalink/datalink.h"
</header>
<waypoints>
<waypoint height="0" name="HOME" x="0.0" y="0.0" />
<waypoint name="CIRCLEWP" x="0.0" y="0.0"/>
<waypoint height="2" name="CLIMB" x="1.2" y="-0.6" />
<waypoint height="1.0" name="STDBY" x="0" y="0" />
<waypoint name="HOVER" x="1.0" y="1.0"/>
<waypoint name="TD" x="0.8" y="-1.7" />
<waypoint name="t0" lat="51.9906059" lon="4.3767772" />
<waypoint name="t1" lat="51.9906269" lon="4.3767829" />
<waypoint name="t2" lat="51.9906216" lon="4.3768187" />
<waypoint name="t3" lat="51.9906388" lon="4.3768251" />
<waypoint name="t4" lat="51.9906637" lon="4.3768005" />
<waypoint name="t5" lat="51.9906425" lon="4.3767879" />
<waypoint name="t6" lat="51.9906470" lon="4.3767547" />
<waypoint name="t7" lat="51.9906290" lon="4.3767502" />
<waypoint lat="51.9906213" lon="4.3768628" name="_CZ1" />
<waypoint lat="51.9905874" lon="4.3767766" name="_CZ2" />
<waypoint lat="51.9906409" lon="4.3767226" name="_CZ3" />
<waypoint lat="51.990667" lon="4.376806" name="_CZ4" />
<waypoint lat="51.9906831" lon="4.3768073" name="_DZ1" />
<waypoint lat="51.9906472" lon="4.3767093" name="_DZ2" />
<waypoint lat="51.9905876" lon="4.3767679" name="_DZ3" />
<waypoint lat="51.9906254" lon="4.3768677" name="_DZ4" />
</waypoints>
<sectors>
<sector color="orange" name="DangerZone">
<corner name="_DZ1" />
<corner name="_DZ2" />
<corner name="_DZ3" />
<corner name="_DZ4" />
</sector>
</sectors>
<exceptions>
<exception cond="datalink_time>=2" deroute="Force Kill Engines"/>
<exception cond="radio_control.status == RC_REALLY_LOST" deroute="Force Kill Engines"/>
</exceptions>
<blocks>
<block name="Wait GPS">
<call_once fun="NavKillThrottle()" />
<while cond="!GpsFixValid()" />
</block>
<block name="Holding point">
<call_once fun="NavKillThrottle()" />
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" />
</block>
<block name="Start Engine">
<call_once fun="NavResurrect()" />
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
<attitude pitch="0" roll="0" throttle="0" vmode="throttle" />
</block>
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 0.5" deroute="Standby" />
<call_once fun="NavSetWaypointHere(WP_CLIMB)" />
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY" />
</block>
<block name="Fly Trajectory">
<while cond="TRUE">
<go wp="t0"/>
<go wp="t1"/>
<go wp="t2"/>
<go wp="t3"/>
<go wp="t7"/>
</while>
</block>
<block name="land here" strip_button="land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)" />
</block>
<block name="land">
<go wp="TD" />
</block>
<block name="flare">
<exception cond="NavDetectGround()" deroute="Holding point" />
<exception cond="!nav_is_in_flight()" deroute="landed" />
<call_once fun="NavStartDetectGround()" />
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD" />
</block>
<block name="landed">
<call_once fun="NavKillThrottle()" />
<attitude pitch="0" roll="0" throttle="0" until="FALSE"
vmode="throttle" />
</block>
<block name="Force Kill Engines">
<call_once fun="autopilot_set_motors_on(FALSE)"/>
<while cond="1"/>
</block>
</blocks>
</flight_plan>
31 changes: 0 additions & 31 deletions conf/flight_plans/tudelft/rotorcraft_selfie.xml

This file was deleted.

31 changes: 0 additions & 31 deletions conf/flight_plans/tudelft/rotorcraft_survey_antwerpen.xml

This file was deleted.

68 changes: 0 additions & 68 deletions conf/flight_plans/tudelft/rotorcraft_survey_aubel.xml

This file was deleted.

2 changes: 1 addition & 1 deletion conf/flight_plans/tudelft/rotorcraft_survey_delft.xml
Expand Up @@ -72,7 +72,7 @@
</sector>
</sectors>
<includes>
<include name="Mission" procedure="rotorcraft_survey_mission.xml"/>
<include name="Mission" procedure="include_rotorcraft_survey_mission.xml"/>
</includes>
<blocks>
<block name="Dummy"/>
Expand Down
Expand Up @@ -95,7 +95,7 @@
</sector>
</sectors>
<includes>
<include name="Mission" procedure="rotorcraft_survey_mission.xml"/>
<include name="Mission" procedure="include_rotorcraft_survey_mission.xml"/>
</includes>
<blocks>
<block name="Dummy"/>
Expand Down
198 changes: 0 additions & 198 deletions conf/flight_plans/versatile_geofence.xml

This file was deleted.

24 changes: 24 additions & 0 deletions conf/modules/actuators_dshot.xml
@@ -0,0 +1,24 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="actuators_dshot" dir="actuators" task="actuators">
<doc>
<description>
Driver for DSHOT speed controller.

Beware that servo output from the same timer cannot mix PWM and DSHOT.
It might be required to disable by hand some PWM output to avoid conflicts when they are activated by default on a board.
Currently only implemented over ChibiOS.
</description>
<define name="DSHOT_SPEED" value="600" description="DSHOT speed (150,300,600,1200)"/>
</doc>
<header>
<file name="actuators_dshot.h"/>
</header>
<makefile>
<define name="ACTUATORS"/>
<file_arch name="actuators_dshot_arch.c"/>
<file_arch name="esc_dshot.c" cond="ifeq ($(RTOS),chibios)"/>
<file_arch name="hal_stm32_dma.c" dir="mcu_periph" cond="ifeq ($(RTOS),chibios)"/>
</makefile>
</module>

23 changes: 23 additions & 0 deletions conf/modules/actuators_ostrich.xml
@@ -0,0 +1,23 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="actuators_ostrich" dir="actuators">
<doc>
<description>Driver for the Ostrich rover controller board</description>
<configure name="ACTUATORS_OSTRICH_PORT" value="UARTx" description="UART port (default UART6)"/>
<configure name="ACTUATORS_OSTRICH_BAUD" value="B115200" description="UART baudrate (default 115200)"/>
</doc>
<header>
<file name="actuators_ostrich.h"/>
</header>
<periodic fun="actuators_ostrich_periodic()" freq="10"/>
<makefile target="ap">
<configure name="ACTUATORS_OSTRICH_PORT" case="upper|lower" default="UART6"/>
<configure name="ACTUATORS_OSTRICH_BAUD" default="B115200"/>
<define name="USE_$(ACTUATORS_OSTRICH_PORT_UPPER)"/>
<define name="ACTUATORS_OSTRICH_DEV" value="$(ACTUATORS_OSTRICH_PORT_LOWER)"/>
<define name="$(ACTUATORS_OSTRICH_PORT_UPPER)_BAUD" value="$(ACTUATORS_OSTRICH_BAUD)"/>

<file name="actuators_ostrich.c"/>
</makefile>
</module>

41 changes: 41 additions & 0 deletions conf/modules/airspeed_sdp3x.xml
@@ -0,0 +1,41 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="airspeed_sdp3x" dir="sensors">
<doc>
<description>
SDP3X differential pressure sensor for e.g measuring airspeed.
</description>
<define name="SDP3X_I2C_DEV" value="i2cX" description="set i2c peripheral (default: i2c2)"/>
<define name="SDP3X_I2C_ADDR" value="0x50" description="i2c slave address (default: 0x50)"/>
<define name="SDP3X_SYNC_SEND" value="TRUE|FALSE" description="flag to enable sending every new measurement via telemetry (default:FALSE)"/>
<define name="SDP3X_PRESSURE_SCALE" value="1.0" description="pressure scaling factor to convert raw output to Pa (default: set according to pressure range according to datasheet)"/>
<define name="SDP3X_PRESSURE_OFFSET" value="0." description="pressure offset in Pa (default: set according to pressure range according to datasheet)"/>
<define name="SDP3X_AIRSPEED_SCALE" value="1.6327" description="quadratic scale factor to convert differential pressure to airspeed"/>
</doc>

<settings>
<dl_settings>
<dl_settings NAME="SDP3X">
<dl_setting min="0" max="1" step="1" values="FALSE|TRUE" var="sdp3x.sync_send" type="bool" shortname="sync_send" module="modules/sensors/airspeed_sdp3x" param="SDP3X_SYNC_SEND" persistent="true"/>
<dl_setting min="1.0" max="300." step="1." var="sdp3x.pressure_scale" type="float" shortname="PressScale" module="modules/sensors/airspeed_sdp3x" param="SDP3X_PRESSURE_SCALE" persistent="true"/>
<dl_setting min="-100." max="100.0" step="0.1" var="sdp3x.pressure_offset" type="float" shortname="PressOffset" module="modules/sensors/airspeed_sdp3x" param="SDP3X_PRESSURE_OFFSET" persistent="true"/>
<dl_setting min="1.0" max="2.0" step="0.01" var="sdp3x.airspeed_scale" type="float" shortname="AirScale" module="modules/sensors/airspeed_sdp3x" param="SDP3X_AIRSPEED_SCALE" persistent="true"/>
</dl_settings>
</dl_settings>
</settings>

<header>
<file name="airspeed_sdp3x.h"/>
</header>

<init fun="sdp3x_init()"/>
<periodic fun="sdp3x_periodic()" freq="100."/>
<event fun="sdp3x_event()"/>

<makefile target="ap">
<configure name="SDP3X_I2C_DEV" default="i2c2" case="upper|lower"/>
<define name="USE_$(SDP3X_I2C_DEV_UPPER)"/>
<define name="SDP3X_I2C_DEV" value="$(SDP3X_I2C_DEV_LOWER)"/>
<file name="airspeed_sdp3x.c"/>
</makefile>
</module>
27 changes: 27 additions & 0 deletions conf/modules/baro_bmp3.xml
@@ -0,0 +1,27 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="baro_bmp3" dir="sensors">
<doc>
<description>
Bosch-Sensortech BMP3xx pressure sensor
</description>
<configure name="BMP3_I2C_DEV" value="i2cX" description="select which i2c peripheral to use (default i2c1)"/>
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR|BMP3_I2C_ADDR_ALT" description="i2c slave address (default BMP3_I2C_ADDR)"/>
<define name="BMP3_SYNC_SEND" description="flag to transmit the data as it is acquired"/>
<define name="BMP3_COMPENSATION" value="BMP3_SINGLE_PRECISION_COMPENSATION" description="select precision for compensation (single precision, double precision, or integer)"/>
</doc>
<header>
<file name="baro_bmp3.h"/>
</header>
<init fun="baro_bmp3_init()"/>
<periodic fun="baro_bmp3_periodic()" freq="50"/>
<event fun="baro_bmp3_event()"/>
<makefile target="ap">
<configure name="BMP3_I2C_DEV" default="i2c1" case="upper|lower"/>
<define name="USE_$(BMP3_I2C_DEV_UPPER)"/>
<define name="BMP3_I2C_DEV" value="$(BMP3_I2C_DEV_LOWER)"/>
<file name="baro_bmp3.c"/>
<file name="bmp3_i2c.c" dir="peripherals"/>
</makefile>
</module>

51 changes: 51 additions & 0 deletions conf/modules/filter_1euro_imu.xml
@@ -0,0 +1,51 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="filter_1euro_imu" dir="imu">
<doc>
<description>
Prefiltering for IMU data using 1euro filter.

The 1 Euro filter is an first order low pass filter with an adaptive cutoff frequency.
It is able to efficiently remove high frequency noise when the average signal is stable
with very small lag by increasing the bandwith to capture faster movements.

Only two parameters are required to tune the filter:
- mincutoff that defines the minimum bandwith: reduce it if noise at low speed is a problem
- beta that is the adaptation coefficient: increase it if lag at high speed is a problem

In order to use this filter for your IMU (on Gyro and Acell data, Mag passthrough), you only
need to redefine the source of data in the ABI bindings of the AHRS/INS filter being used.
For instance, if the 'ahrs_int_cmpl_quat' AHRS is used, this module should be loaded with
the following options:
define name="AHRS_ICQ_IMU_ID" value="IMU_F1E_ID"
define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"
</description>
<section name="FILTER_1EURO" prefix="FILTER_1EURO_">
<define name="ENABLED" value="FALSE|TRUE" description="activate or not the filter by default"/>
<define name="GYRO_MINCUTOFF" value="10." description="minimum cutoff freq for gyro signal"/>
<define name="GYRO_BETA" value="0.1" description="adaptation coefficient for gyro signal"/>
<define name="ACCEL_MINCUTOFF" value="0.1" description="minimum cutoff freq for accel signal"/>
<define name="ACCEL_BETA" value="0.01" description="adaptation coefficient for accel signal"/>
<define name="FREQ" value="512" description="set fixed frequency, if not defined but INS/AHRS_PROPAGATE_FREQUENCY is defined it is used, otherwise autofreq is used"/>
</section>
</doc>
<settings>
<dl_settings>
<dl_settings name="1e_imu">
<dl_setting min="0" max="1" step="1" var="filter_1e_imu.enabled" module="imu/filter_1euro_imu" shortname="enable" values="DISABLED|ENABLED" handler="reset"/>
<dl_setting min="0.1" max="50." step="0.1" var="filter_1e_imu.gyro_mincutoff" module="imu/filter_1euro_imu" shortname="gyro mincutoff" handler="update_gyro_mincutoff"/>
<dl_setting min="0.0001" max="1." step="0.001" var="filter_1e_imu.gyro_beta" module="imu/filter_1euro_imu" shortname="gyro beta" handler="update_gyro_beta"/>
<dl_setting min="0.01" max="10." step="0.001" var="filter_1e_imu.accel_mincutoff" module="imu/filter_1euro_imu" shortname="accel mincutoff" handler="update_accel_mincutoff"/>
<dl_setting min="0.0001" max=".1" step="0.001" var="filter_1e_imu.accel_beta" module="imu/filter_1euro_imu" shortname="accel beta" handler="update_accel_beta"/>
</dl_settings>
</dl_settings>
</settings>
<header>
<file name="filter_1euro_imu.h"/>
</header>
<init fun="filter_1euro_imu_init()"/>
<makefile>
<file name="filter_1euro_imu.c"/>
</makefile>
</module>

28 changes: 28 additions & 0 deletions conf/modules/guidance_rover_holonomic.xml
@@ -0,0 +1,28 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="guidance_rover_holonomic" dir="guidance">
<doc>
<description>
Holonomic guidance for rover
</description>
</doc>
<settings target="ap">
<dl_settings>
<dl_settings NAME="GuidanceHolo">
<dl_setting var="rover_holo_guidance.speed_pid.p" min="0." step="0.1" max="10." shortname="s_kp" param="ROVER_HOLO_GUIDANCE_SPEED_PGAIN" type="float" persistent="true"/>
<dl_setting var="rover_holo_guidance.speed_pid.d" min="0." step="0.1" max="10." shortname="s_kd" param="ROVER_HOLO_GUIDANCE_SPEED_DGAIN" type="float" persistent="true"/>
<dl_setting var="rover_holo_guidance.speed_pid.i" min="0." step="0.01" max="1." shortname="s_ki" handler="set_speed_igain" param="ROVER_HOLO_GUIDANCE_SPEED_IGAIN" type="float" persistent="true" module="guidance/rover_guidance_holonomic"/>
<dl_setting var="rover_holo_guidance.turn_pid.p" min="0." step="0.01" max="10." shortname="t_kp" param="ROVER_HOLO_GUIDANCE_TURN_PGAIN" type="float" persistent="true"/>
<dl_setting var="rover_holo_guidance.turn_pid.d" min="0." step="0.01" max="10." shortname="t_kd" param="ROVER_HOLO_GUIDANCE_TURN_DGAIN" type="float" persistent="true"/>
<dl_setting var="rover_holo_guidance.turn_pid.i" min="0." step="0.01" max="1." shortname="t_ki" handler="set_turn_igain" param="ROVER_HOLO_GUIDANCE_TURN_IGAIN" type="float" persistent="true" module="guidance/rover_guidance_holonomic"/>
</dl_settings>
</dl_settings>
</settings>
<header>
<file name="rover_guidance_holonomic.h"/>
</header>
<init fun="rover_holo_guidance_init()"/>
<makefile target="ap" firmware="rover">
<file name="rover_guidance_holonomic.c" dir="$(SRC_FIRMWARE)/guidance"/>
</makefile>
</module>
46 changes: 46 additions & 0 deletions conf/modules/ins_ekf2.xml
@@ -0,0 +1,46 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="ekf2" dir="ins">
<doc>
<description>
simple INS and AHRS using EKF2 from PX4
</description>
</doc>
<header>
<file name="ins_ekf2.h" dir="subsystems/ins"/>
</header>
<init fun="ins_ekf2_init()"/>
<periodic fun="ins_ekf2_update()" autorun="TRUE"/>
<makefile target="ap|nps">
<!-- EKF2 files -->
<define name="INS_TYPE_H" value="subsystems/ins/ins_ekf2.h" type="string"/>
<file name="ins.c" dir="subsystems"/>
<file name="ins_ekf2.cpp" dir="subsystems/ins"/>

<!-- Include the ecl and matrix libraries from ext -->
<include name="$(PAPARAZZI_SRC)/sw/ext/ecl/"/>
<include name="$(PAPARAZZI_SRC)/sw/ext/matrix/"/>
<define name="__PAPARAZZI" value="true"/>
<define name="ECL_STANDALONE" value="true"/>
<define name="USE_MAGNETOMETER" value="true"/> <!-- Needed for IMU to get scaled version -->

<!-- Compile needed ecl files -->
<file name="mathlib.cpp" dir="ecl/mathlib"/>
<file name="geo.cpp" dir="ecl/geo"/>
<file name="geo_mag_declination.cpp" dir="ecl/geo_lookup"/>
<file name="airspeed_fusion.cpp" dir="ecl/EKF"/>
<file name="control.cpp" dir="ecl/EKF"/>
<file name="covariance.cpp" dir="ecl/EKF"/>
<file name="drag_fusion.cpp" dir="ecl/EKF"/>
<file name="ekf.cpp" dir="ecl/EKF"/>
<file name="ekf_helper.cpp" dir="ecl/EKF"/>
<file name="estimator_interface.cpp" dir="ecl/EKF"/>
<file name="gps_checks.cpp" dir="ecl/EKF"/>
<file name="mag_fusion.cpp" dir="ecl/EKF"/>
<file name="optflow_fusion.cpp" dir="ecl/EKF"/>
<file name="sideslip_fusion.cpp" dir="ecl/EKF"/>
<file name="terrain_estimator.cpp" dir="ecl/EKF"/>
<file name="vel_pos_fusion.cpp" dir="ecl/EKF"/>
<file name="gps_yaw_fusion.cpp" dir="ecl/EKF"/>
</makefile>
</module>
1 change: 0 additions & 1 deletion conf/modules/ins_mekf_wind.xml
Expand Up @@ -82,7 +82,6 @@
<define name="EIGEN_NO_DEBUG"/>
<flag name="CXXFLAGS" value="Wno-bool-compare"/>
<flag name="CXXFLAGS" value="Wno-logical-not-parentheses"/>
<file name="pprz_syscalls.c" dir="."/>
</makefile>
<makefile target="sim" firmware="fixedwing">
<define name="AHRS_TYPE_H" value="subsystems/ahrs/ahrs_sim.h" type="string"/>
Expand Down
22 changes: 22 additions & 0 deletions conf/modules/joystick.xml
@@ -0,0 +1,22 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="joystick">
<doc>
<description>
Handle JOYSTICK_RAW messages

Each new message is parsed and stored into the joystick structure.
An ABI message JOYSTICK is sent and can be used for control or payload
depending on the application.
</description>
</doc>
<header>
<file name="joystick.h"/>
</header>
<init fun="joystick_init()"/>
<datalink message="JOYSTICK_RAW" fun="joystick_parse()"/>
<makefile>
<file name="joystick.c"/>
</makefile>
</module>

49 changes: 49 additions & 0 deletions conf/modules/lidar_tfmini.xml
@@ -0,0 +1,49 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="lidar_tfmini" dir="lidar">
<doc>
<description>
TFMini Lidar using a single UART for communication
</description>
<configure name="TFMINI_PORT" value="UART3" description="UART device to use for lidar"/>
<configure name="TFMINI_BAUD" value="B115200" description="baudrate of the TFMini UART port"/>
<configure name="USE_TFMINI_AGL" value="0" description="use this lidar for AGL measurements"/>
<configure name="TFMINI_COMPENSATE_ROTATION" value="1" description="compensate AGL measurements for body rotation"/>
</doc>

<settings>
<dl_settings NAME="Lidar TFMini">
<dl_settings NAME="Lidar">
<dl_setting MAX="1" MIN="0" STEP="1" VAR="tfmini.compensate_rotation" shortname="derotate_agl"/>
<dl_setting MAX="1" MIN="0" STEP="1" VAR="tfmini.update_agl" shortname="update_agl"/>
</dl_settings>
</dl_settings>
</settings>

<header>
<file name="tfmini.h"/>
</header>
<init fun="tfmini_init()"/>
<event fun="tfmini_event()"/>
<makefile>
<!-- Configure default UART port and baudrate -->
<configure name="TFMINI_PORT" default="UART3" case="upper|lower"/>
<configure name="TFMINI_BAUD" default="B115200"/>

<!-- Enable UART and set baudrate -->
<define name="USE_$(TFMINI_PORT_UPPER)"/>
<define name="$(TFMINI_PORT_UPPER)_BAUD" value="$(TFMINI_BAUD)"/>
<define name="TFMINI_PORT" value="$(TFMINI_PORT_LOWER)"/>

<configure name="USE_TFMINI_AGL" default="0"/>
<configure name="TFMINI_COMPENSATE_ROTATION" default="0"/>
<define name="USE_TFMINI_AGL" value="$(USE_TFMINI_AGL)"/>
<define name="TFMINI_COMPENSATE_ROTATION" value="$(TFMINI_COMPENSATE_ROTATION)"/>
<file name="tfmini.c"/>
</makefile>
<makefile target="nps">
<define name="USE_SONAR" value="1"/><!-- in NPS use a virtual sonar to simulate lidar measurements -->
</makefile>
</module>


42 changes: 42 additions & 0 deletions conf/modules/mag_lis3mdl.xml
@@ -0,0 +1,42 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="mag_lis3mdl" dir="sensors">
<doc>
<description>
ST LIS3MDL magnetometer.
</description>
<configure name="MAG_LIS3MDL_I2C_DEV" value="i2cX" description="I2C device to use"/>
<define name="MODULE_LIS3MDL_SYNC_SEND" value="TRUE|FALSE" description="Send IMU_RAW message with each new measurement (default: FALSE)"/>
<define name="MODULE_LIS3MDL_UPDATE_AHRS" value="TRUE|FALSE" description="Copy measurements to imu and send as ABI message (default: FALSE)"/>
<define name="LIS3MDL_CHAN_X_SIGN" value="+|-" description="Reverse polarity of x axis (default: +)"/>
<define name="LIS3MDL_CHAN_Y_SIGN" value="+|-" description="Reverse polarity of y axis (default: +)"/>
<define name="LIS3MDL_CHAN_Z_SIGN" value="+|-" description="Reverse polarity of z axis (default: +)"/>
<define name="LIS3MDL_CHAN_X" value="0|1|2" description="Channel id of x axis (default: 0)"/>
<define name="LIS3MDL_CHAN_Y" value="0|1|2" description="Channel id of y axis (default: 1)"/>
<define name="LIS3MDL_CHAN_Z" value="0|1|2" description="Channel id of z axis (default: 2)"/>
<section name="MAG_LIS3MDL" prefix="LIS3MDL_">
<define name="MAG_TO_IMU_PHI" value="0.0" description="Rotation between sensor frame and IMU frame (phi angle)"/>
<define name="MAG_TO_IMU_THETA" value="0.0" description="Rotation between sensor frame and IMU frame (theta angle)"/>
<define name="MAG_TO_IMU_PSI" value="0.0" description="Rotation between sensor frame and IMU frame (psi angle)"/>
</section>
</doc>
<header>
<file name="mag_lis3mdl.h"/>
</header>
<init fun="mag_lis3mdl_module_init()"/>
<periodic fun="mag_lis3mdl_module_periodic()" freq="60"/>
<periodic fun="mag_lis3mdl_report()" freq="10" autorun="FALSE"/>
<event fun="mag_lis3mdl_module_event()"/>
<makefile target="ap">
<file name="mag_lis3mdl.c"/>
<file name="lis3mdl.c" dir="peripherals"/>
<raw>
ifeq ($(MAG_LIS3MDL_I2C_DEV),)
$(error mag_lis3mdl module error: please configure MAG_LIS3MDL_I2C_DEV)
endif
</raw>
<configure name="MAG_LIS3MDL_I2C_DEV" case="upper|lower"/>
<define name="USE_$(MAG_LIS3MDL_I2C_DEV_UPPER)"/>
<define name="MAG_LIS3MDL_I2C_DEV" value="$(MAG_LIS3MDL_I2C_DEV_LOWER)"/>
</makefile>
</module>
7 changes: 0 additions & 7 deletions conf/modules/rust_demo_module.xml
Expand Up @@ -26,13 +26,6 @@
<init fun="rust_function()"/>
<periodic fun="rust_periodic()" freq="1." autorun="TRUE"/>

<makefile target="ap">
<!-->
Additional defines needed by Rust's `alloc` crate
-->
<file name="pprz_syscalls.c" dir="."/>
</makefile>

<makefile target="ap|nps|hitl">
<!--
MODULE_PATH is where the module lives.
Expand Down
14 changes: 14 additions & 0 deletions conf/simulator/gazebo/airframes/bebop2.xml
@@ -0,0 +1,14 @@
<!DOCTYPE airframe SYSTEM "../../../airframes/airframe.dtd">

<airframe>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_THRUSTS" value="2.80, 2.80, 2.80, 2.80" type="float[]"/>
<define name="ACTUATOR_TORQUES" value="0.05, 0.05, 0.05, 0.05" type="float[]"/>
<define name="ACTUATOR_TIME_CONSTANTS" value="0.02, 0.02, 0.02, 0.02" type="float[]"/>
<define name="ACTUATOR_MAX_ANGULAR_MOMENTUM" value="0.5, 0.5, 0.5, 0.5" type="float[]"/>
<define name="GAZEBO_AC_NAME" value="bebop2" type="string"/>
<define name="BYPASS_AHRS" value="1"/>
<define name="BYPASS_INS" value="1"/>
<!-- <define name="SIMULATE_MT9F002" value="1"/> --><!-- TODO -->
</section>
</airframe>
299 changes: 299 additions & 0 deletions conf/simulator/gazebo/models/bebop2/bebop2.sdf
@@ -0,0 +1,299 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="bebop2">
<pose>0 0 .1 0 0 0</pose>

<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>

<inertial>
<mass>0.536</mass>
<inertia>
<ixx> 0.000906 </ixx>
<iyy> 0.002225 </iyy>
<izz> 0.002500 </izz>
<ixy> 0. </ixy>
<ixz> 0. </ixz>
<iyz> 0. </iyz>
</inertia>
</inertial>

<collision name="collision">
<geometry>
<box>
<size>0.4 0.4 0.05</size>
</box>
</geometry>
</collision>

<visual name="visual">
<geometry>
<box>
<size>0.15 0.05 0.05</size>
</box>
</geometry>
<material>
<diffuse>0.82 0.82 0.82 1</diffuse>
<ambient>0.82 0.82 0.82 1</ambient>
</material>
</visual>

<sensor name="contactsensor" type="contact">
<contact>
<collision>collision</collision>
</contact>
</sensor>
</link>

<!-- MOTORS -->
<link name="nw_motor">
<pose>0.0875 0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.82 0.82 0.82 1</diffuse>
<ambient>0.82 0.82 0.82 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="nw_motor_joint">
<parent>chassis</parent>
<child>nw_motor</child>
</joint>

<link name="se_motor">
<pose>-0.0875 -0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
<ambient>0.1 0.1 0.1 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="se_motor_joint">
<parent>chassis</parent>
<child>se_motor</child>
</joint>

<link name="ne_motor">
<pose>0.0875 -0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.82 0.82 0.82 1</diffuse>
<ambient>0.82 0.82 0.82 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="ne_motor_joint">
<parent>chassis</parent>
<child>ne_motor</child>
</joint>

<link name="sw_motor">
<pose>-0.0875 0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
<ambient>0.1 0.1 0.1 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="sw_motor_joint">
<parent>chassis</parent>
<child>sw_motor</child>
</joint>

<link name="sonar">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<sensor name="sonarsensor" type="sonar">
<sonar>
<min>0.20</min>
<max>5.0</max>
<radius>0.50</radius>
</sonar>
</sensor>
</link>

<joint name="sonar_joint" type="fixed">
<parent>chassis</parent>
<child>sonar</child>
</joint>

<!-- CAMERAS -->

<link name="front_camera">
<pose>0.15 0 0 -1.57 0.33 0</pose><!-- Bebop camera output is rotated 90 degrees and pitched slightly downwards -->
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<sensor type="wideanglecamera" name="front_camera">
<update_rate>15.0</update_rate><!-- adjust with MT9F002_TARGET_FPS -->
<camera name="front_camera">
<image>
<width>3746</width><!-- with MT9F002_OUTPUT_SCALER = 1.00, will be scaled by NPS --><!-- Reduced to 3 rad FoV for Gazebo 7 compatibility -->
<height>3288</height>
<format>R8G8B8</format>
</image>
<horizontal_fov>3.00</horizontal_fov>
<lens>
<type>equisolid_angle</type>
<scale_to_hfov>true</scale_to_hfov>
<env_texture_size>2048</env_texture_size><!-- with MT9F002_OUTPUT_SCALER = 1.00, will be scaled by NPS -->
</lens>
<clip>
<near>0.01</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame. That pixel's
noise value is added to each of its color channels, which at that point lie
in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
</sensor>
</link>

<joint name="front_camera_joint" type="fixed">
<parent>chassis</parent>
<child>front_camera</child>
</joint>

<link name="bottom_camera">
<pose>0 0 0 0 1.57 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<sensor type="camera" name="bottom_camera">
<update_rate>30.0</update_rate>
<camera name="bottom_camera">
<horizontal_fov>0.7175</horizontal_fov>
<image>
<width>240</width>
<height>240</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame. That pixel's
noise value is added to each of its color channels, which at that point lie
in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
</sensor>
</link>

<joint name="bottom_camera_joint" type="fixed">
<parent>chassis</parent>
<child>bottom_camera</child>
</joint>
</model>
</sdf>
15 changes: 15 additions & 0 deletions conf/simulator/gazebo/models/bebop2/model.config
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>Bebop 2 (Paparazzi)</name>
<version>1.0</version>
<sdf version='1.4'>bebop2.sdf</sdf>

<author>
<name>Tom van Dijk</name>
<email>tomvand@users.noreply.github.com</email>
</author>

<description>
Simple Bebop 2 model for use with Paparazzi's NPS (http://wiki.paparazziuav.org).
</description>
</model>
@@ -0,0 +1,310 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="bebop2_with_slamdunk">
<pose>0 0 .1 0 0 0</pose>

<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>

<inertial>
<mass>0.536</mass>
<inertia>
<ixx> 0.000906 </ixx>
<iyy> 0.002225 </iyy>
<izz> 0.002500 </izz>
<ixy> 0. </ixy>
<ixz> 0. </ixz>
<iyz> 0. </iyz>
</inertia>
</inertial>

<collision name="collision">
<geometry>
<box>
<size>0.4 0.4 0.05</size>
</box>
</geometry>
</collision>

<visual name="visual">
<geometry>
<box>
<size>0.15 0.05 0.05</size>
</box>
</geometry>
<material>
<diffuse>0.82 0.82 0.82 1</diffuse>
<ambient>0.82 0.82 0.82 1</ambient>
</material>
</visual>

<sensor name="contactsensor" type="contact">
<contact>
<collision>collision</collision>
</contact>
</sensor>
</link>

<!-- SLAMDUNK -->
<include name="slamdunk">
<uri>model://slamdunk</uri>
<pose>0 0 .05 0 0 0</pose>
</include>

<joint type="fixed" name="slamdunk_joint">
<parent>chassis</parent>
<child>slamdunk::slamdunk_link</child>
</joint>

<!-- MOTORS -->
<link name="nw_motor">
<pose>0.0875 0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.82 0.82 0.82 1</diffuse>
<ambient>0.82 0.82 0.82 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="nw_motor_joint">
<parent>chassis</parent>
<child>nw_motor</child>
</joint>

<link name="se_motor">
<pose>-0.0875 -0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
<ambient>0.1 0.1 0.1 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="se_motor_joint">
<parent>chassis</parent>
<child>se_motor</child>
</joint>

<link name="ne_motor">
<pose>0.0875 -0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.82 0.82 0.82 1</diffuse>
<ambient>0.82 0.82 0.82 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="ne_motor_joint">
<parent>chassis</parent>
<child>ne_motor</child>
</joint>

<link name="sw_motor">
<pose>-0.0875 0.1125 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
<ambient>0.1 0.1 0.1 1</ambient>
</material>
</visual>
</link>

<joint type="fixed" name="sw_motor_joint">
<parent>chassis</parent>
<child>sw_motor</child>
</joint>

<link name="sonar">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<sensor name="sonarsensor" type="sonar">
<sonar>
<min>0.20</min>
<max>5.0</max>
<radius>0.50</radius>
</sonar>
</sensor>
</link>

<joint name="sonar_joint" type="fixed">
<parent>chassis</parent>
<child>sonar</child>
</joint>

<!-- CAMERAS -->

<link name="front_camera">
<pose>0.15 0 0 -1.57 0.33 0</pose><!-- Bebop camera output is rotated 90 degrees and pitched slightly downwards -->
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<sensor type="wideanglecamera" name="front_camera">
<update_rate>15.0</update_rate><!-- adjust with MT9F002_TARGET_FPS -->
<camera name="front_camera">
<image>
<width>3746</width><!-- with MT9F002_OUTPUT_SCALER = 1.00, will be scaled by NPS --><!-- Reduced to 3 rad FoV for Gazebo 7 compatibility -->
<height>3288</height>
<format>R8G8B8</format>
</image>
<horizontal_fov>3.00</horizontal_fov>
<lens>
<type>equisolid_angle</type>
<scale_to_hfov>true</scale_to_hfov>
<env_texture_size>2048</env_texture_size><!-- with MT9F002_OUTPUT_SCALER = 1.00, will be scaled by NPS -->
</lens>
<clip>
<near>0.01</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame. That pixel's
noise value is added to each of its color channels, which at that point lie
in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
</sensor>
</link>

<joint name="front_camera_joint" type="fixed">
<parent>chassis</parent>
<child>front_camera</child>
</joint>

<link name="bottom_camera">
<pose>0 0 0 0 1.57 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.0001</ixx>
<iyy>0.0001</iyy>
<izz>0.0001</izz>
<ixy>0</ixy>
<iyz>0</iyz>
<ixz>0</ixz>
</inertia>
</inertial>
<sensor type="camera" name="bottom_camera">
<update_rate>30.0</update_rate>
<camera name="bottom_camera">
<horizontal_fov>0.7175</horizontal_fov>
<image>
<width>240</width>
<height>240</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame. That pixel's
noise value is added to each of its color channels, which at that point lie
in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
</sensor>
</link>

<joint name="bottom_camera_joint" type="fixed">
<parent>chassis</parent>
<child>bottom_camera</child>
</joint>
</model>
</sdf>
15 changes: 15 additions & 0 deletions conf/simulator/gazebo/models/bebop2_with_slamdunk/model.config
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>Bebop 2 (Paparazzi) with SLAMDunk</name>
<version>1.0</version>
<sdf version='1.4'>bebop2_with_slamdunk.sdf</sdf>

<author>
<name>Tom van Dijk</name>
<email>tomvand@users.noreply.github.com</email>
</author>

<description>
Bebop 2 with SLAMDunk
</description>
</model>
15 changes: 15 additions & 0 deletions conf/simulator/gazebo/models/slamdunk/model.config
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>SLAMDunk</name>
<version>1.0</version>
<sdf version='1.4'>slamdunk.sdf</sdf>

<author>
<name>Tom van Dijk</name>
<email>tomvand@users.noreply.github.com</email>
</author>

<description>
Approximate parrot SLAMDunk model
</description>
</model>
134 changes: 134 additions & 0 deletions conf/simulator/gazebo/models/slamdunk/slamdunk.sdf
@@ -0,0 +1,134 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="slamdunk">
<link name="slamdunk_link">
<visual name="visual">
<geometry>
<box>
<size>0.12 0.06 0.025</size>
</box>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
<ambient>0.1 0.1 0.1 1</ambient>
</material>
</visual>
<visual name="visual2">
<pose>0.04 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.005 0.2 0.025</size>
</box>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
<ambient>0.1 0.1 0.1 1</ambient>
</material>
</visual>
<inertial>
<mass>0.135</mass>
<inertia>
<ixx> 0.00010 </ixx>
<iyy> 0.00020 </iyy>
<izz> 0.00020 </izz>
</inertia>
</inertial>
<collision name="slamdunk_collision">
<geometry>
<box>
<size>0.12 0.06 0.025</size>
</box>
</geometry>
</collision>
<!-- <sensor type="depth" name="depth_camera">
<pose>0.05 0.1 0 0 0 0</pose>
<update_rate>30.0</update_rate>
<camera name="depth_cam">
<horizontal_fov>1.19</horizontal_fov>
<image>
<width>96</width>
<height>96</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>1000</far>
</clip>
</camera>
<plugin name="depth_controller" filename="libgazebo_ros_depth_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>slamdunk_camera</cameraName>
<imageTopicName>rgb/image_rect_color</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageTopicName>/depth_map/image</depthImageTopicName>
<depthImageCameraInfoTopicName>/depth_map/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>points</pointCloudTopicName>
<frameName>cam_optical_frame</frameName>
<pointCloudCutoff>0.02</pointCloudCutoff>
</plugin>
</sensor> -->
<sensor type="camera" name="left_rgb_rect">
<pose>0.05 0.1 0 0 0 0</pose>
<update_rate>30.0</update_rate>
<camera name="left_rgb_rect_cam">
<horizontal_fov>1.19</horizontal_fov>
<image>
<width>576</width>
<height>576</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>1000</far>
</clip>
</camera>
<plugin name="left_cam_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>left_rgb_rect</cameraName>
<imageTopicName>image_rect_color</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>cam_optical_frame2</frameName>
</plugin>
</sensor>
<sensor type="camera" name="right_rgb_rect">
<pose>0.05 -0.1 0 0 0 0</pose>
<update_rate>30.0</update_rate>
<camera name="right_rgb_rect_cam">
<horizontal_fov>1.19</horizontal_fov>
<image>
<width>576</width>
<height>576</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>1000</far>
</clip>
</camera>
<plugin name="right_cam_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>right_rgb_rect</cameraName>
<imageTopicName>image_rect_color</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>cam_optical_frame3</frameName>
</plugin>
</sensor>
<sensor type="imu" name="imu_sensor">
<update_rate>200</update_rate>
<imu>
</imu>
<plugin name="imu_controller" filename="libgazebo_ros_imu_sensor.so">
<alwaysOn>true</alwaysOn>
<updateRateHZ>0.0</updateRateHZ>
<robotNamespace></robotNamespace>
<topicName>imu</topicName>
<bodyName>slamdunk_link</bodyName>
<frameName>slamdunk_link</frameName>
</plugin>
</sensor>
</link>
</model>
</sdf>
28 changes: 28 additions & 0 deletions conf/telemetry/default_rotorcraft.xml
Expand Up @@ -32,6 +32,9 @@
<message name="VISION_POSITION_ESTIMATE" period="0.1"/>
<message name="DIVERGENCE" period="0.05"/>
<message name="DRAGSPEED" period="0.02"/>
<message name="LOGGER_STATUS" period="5.1"/>
<message name="LIDAR" period="1.2"/>
<message name="INS_EKF2" period=".25"/>
</mode>

<mode name="ppm">
Expand Down Expand Up @@ -173,5 +176,30 @@

</process>

<process name="FlightRecorder">
<mode name="default">
<message name="AUTOPILOT_VERSION" period="11.1"/>
<message name="DL_VALUE" period="1.1"/>
<message name="ROTORCRAFT_STATUS" period="1.2"/>
<message name="ROTORCRAFT_FP" period="0.25"/>
<message name="INS_REF" period="5.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="WP_MOVED" period="1.3"/>
<message name="GPS_INT" period=".1"/>
<message name="INS" period=".1"/>
<message name="I2C_ERRORS" period="4.1"/>
<message name="UART_ERRORS" period="3.1"/>
<message name="ENERGY" period="2.5"/>
<message name="DATALINK_REPORT" period="5.1"/>
<message name="STATE_FILTER_STATUS" period="3.2"/>
<message name="AIR_DATA" period="1.3"/>
<message name="SURVEY" period="2.5"/>
<message name="IMU_GYRO_SCALED" period=".075"/>
<message name="IMU_ACCEL_SCALED" period=".075"/>
<message name="IMU_MAG_SCALED" period=".2"/>
<message name="LIDAR" period="0.05"/>
</mode>
</process>

</telemetry>

File renamed without changes.
2 changes: 2 additions & 0 deletions conf/tools/matlab2pprz.xml
@@ -0,0 +1,2 @@
<program command="sw/ground_segment/python/matlab2pprz/matlab2pprz.py" name="Matlab/PPRZ/Natnet bridge" />

112 changes: 40 additions & 72 deletions conf/userconf/tudelft/conf.xml
Expand Up @@ -22,17 +22,6 @@
settings_modules="modules/video_rtp_stream.xml modules/geo_mag.xml modules/air_data.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffd633d633"
/>
<aircraft
name="ARDrone2_flip"
ac_id="14"
airframe="airframes/tudelft/ardrone2_flip.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffcd49cd49"
/>
<aircraft
name="ARDrone2_indi"
ac_id="13"
Expand Down Expand Up @@ -66,17 +55,6 @@
settings_modules="modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#fffff996b847"
/>
<aircraft
name="Ardrone2_182"
ac_id="182"
airframe="airframes/tudelft/IMAV2013/ardrone2.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/time_countdown.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="red"
/>
<aircraft
name="BebopMavlink"
ac_id="9"
Expand All @@ -96,7 +74,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotorcraft_survey_imav2015_competition.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/digital_cam_video.xml modules/video_capture.xml modules/nav_survey_poly_rotorcraft.xml [modules/nav_survey_rectangle_rotorcraft.xml] modules/video_rtp_stream.xml modules/cv_blob_locator.xml modules/air_data.xml [modules/geo_mag.xml] modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
settings_modules="modules/digital_cam_video.xml modules/video_capture.xml modules/nav_survey_poly_rotorcraft.xml [modules/nav_survey_rectangle_rotorcraft.xml] modules/video_rtp_stream.xml modules/cv_blob_locator.xml modules/bebop_cam.xml modules/air_data.xml [modules/geo_mag.xml] modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#f84eb57ae827"
/>
<aircraft
Expand Down Expand Up @@ -129,7 +107,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/bebop_ae_awb.xml modules/video_rtp_stream.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
settings_modules="modules/bebop_ae_awb.xml modules/video_rtp_stream.xml modules/bebop_cam.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffbc3bce5b"
/>
<aircraft
Expand All @@ -140,7 +118,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/video_capture.xml modules/cv_opticflow.xml modules/air_data.xml modules/geo_mag.xml modules/ins_hff_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
settings_modules="modules/video_capture.xml modules/cv_opticflow.xml modules/bebop_cam.xml modules/air_data.xml modules/geo_mag.xml modules/ins_hff_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="blue"
/>
<aircraft
Expand Down Expand Up @@ -201,6 +179,17 @@
gui_color="white"
release="65aa9a711dc4a66ed2d7cf73c0f5872bbeeb821d"
/>
<aircraft
name="Heli450"
ac_id="8"
airframe="airframes/tudelft/heli450.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings=""
settings_modules="modules/heli_throttle_curve.xml modules/gps_ubx_ucenter.xml modules/air_data.xml modules/geo_mag.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_rate.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="blue"
/>
<aircraft
name="Iris"
ac_id="66"
Expand Down Expand Up @@ -254,11 +243,11 @@
airframe="airframes/CDW/cdw_mavtec.xml"
radio="radios/R6107SP_7ch.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotorcraft_survey_imav2015_competition.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/modules/config_asctec_v2.xml"
settings_modules="modules/geo_mag.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/gps_ubx_ucenter.xml modules/switch_servo.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="blue"
release="46b814ea46496cfc3f6a874bb5013db1a350bfcf"
release="33e02c9f1e831cb30ba9dc442e055b6e28c72a52"
/>
<aircraft
name="MAVTec4_Bart"
Expand All @@ -281,17 +270,7 @@
settings="settings/rotorcraft_basic.xml settings/modules/config_asctec_v2.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/switch_servo.xml [modules/air_data.xml] [modules/geo_mag.xml] modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#8c63ffff8e00"
/>
<aircraft
name="MavRick_LisaS"
ac_id="131"
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_modules="modules/gps_ubx_ucenter.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/ahrs_float_dcm.xml modules/imu_common.xml modules/radio_control_superbitrf_rc.xml"
gui_color="white"
release="33e02c9f1e831cb30ba9dc442e055b6e28c72a52"
/>
<aircraft
name="MentorEnergy"
Expand All @@ -317,17 +296,6 @@
gui_color="blue"
release="f739a81cfa2c633e33f31ab5f095d8f617276974"
/>
<aircraft
name="Quadrotor_LisaS"
ac_id="132"
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_modules="modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/radio_control_superbitrf_rc.xml modules/gps_ubx_ucenter.xml"
gui_color="blue"
/>
<aircraft
name="Robird"
ac_id="68"
Expand Down Expand Up @@ -363,6 +331,17 @@
settings_modules="modules/spektrum_soft_bind.xml [modules/air_data.xml] modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/imu_common.xml"
gui_color="#fff0cccaccca"
/>
<aircraft
name="Splash3"
ac_id="17"
airframe="airframes/tudelft/splash3.xml"
radio="radios/crossfire_sbus.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/lidar_tfmini.xml modules/stabilization_rate.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/imu_common.xml"
gui_color="blue"
/>
<aircraft
name="TwoSeasTwenty"
ac_id="200"
Expand Down Expand Up @@ -429,17 +408,6 @@
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#baa3d698b729"
/>
<aircraft
name="bebop2_23"
ac_id="23"
airframe="airframes/tudelft/bebop2_indi_MAVlink.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#f6d5baaaffff"
/>
<aircraft
name="bebop2_detect_gate_front"
ac_id="218"
Expand All @@ -448,7 +416,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotorcraft_autonomous_drone_race.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_detect_gate.xml modules/ctrl_module_outerloop_demo.xml modules/video_capture.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_detect_gate.xml modules/ctrl_module_outerloop_demo.xml modules/video_capture.xml modules/bebop_cam.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffbf17bf17"
/>
<aircraft
Expand All @@ -462,6 +430,17 @@
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#baa3d698b729"
/>
<aircraft
name="bebop2_optitrack"
ac_id="48"
airframe="airframes/tudelft/bebop2_optitrack.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotorcraft_optitrack_path.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="blue"
/>
<aircraft
name="bebop2_vision_front"
ac_id="217"
Expand Down Expand Up @@ -518,17 +497,6 @@
settings_modules="modules/digital_cam_video.xml modules/video_capture.xml modules/nav_survey_poly_rotorcraft.xml [modules/nav_survey_rectangle_rotorcraft.xml] modules/video_rtp_stream.xml modules/cv_blob_locator.xml modules/air_data.xml [modules/geo_mag.xml] modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/ahrs_float_mlkf.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#68f5eb116e0c"
/>
<aircraft
name="frog_flip"
ac_id="4"
airframe="airframes/BR/bebop_indi_frog_flip.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/video_rtp_stream.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/ahrs_float_mlkf.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#b777d813cd0b"
/>
<aircraft
name="mavshot"
ac_id="5"
Expand Down
2 changes: 1 addition & 1 deletion conf/userconf/tudelft/course2018_conf.xml
Expand Up @@ -9,6 +9,6 @@
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_colorfilter.xml modules/bebop_cam.xml modules/air_data.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="white"
release="593ed974ecf1a78f2eb2b0168a6fa0c93fad8259"
release="5e3b6247cc7e2770162bf215b8f427eac58fbdaf"
/>
</conf>
1 change: 1 addition & 0 deletions conf/userconf/tudelft/delfly_conf.xml
Expand Up @@ -20,5 +20,6 @@
settings="settings/rotorcraft_basic.xml settings/control/stabilization_att_int.xml"
settings_modules="modules/logger_sd_spi_direct.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_euler.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="blue"
release="bd49f8763f106f69dc87ad735c8bd6ff277a3f62"
/>
</conf>
149 changes: 125 additions & 24 deletions start.py
@@ -1,8 +1,7 @@
#!/usr/bin/env python
#!/usr/bin/env python2

from __future__ import print_function


import pygtk
import gtk
pygtk.require('2.0')
Expand Down Expand Up @@ -67,21 +66,22 @@ def update_controlpanel_label(self):

# CallBack Functions

def find_conf_files(self):
def find_conf_files(self, combo):
conf_files = paparazzi.get_list_of_conf_files(self.exclude_backups)
self.update_combo(self.conf_file_combo, conf_files, self.conf_xml)
self.update_combo(combo, conf_files, self.conf_xml)

def find_controlpanel_files(self):
controlpanel_files = paparazzi.get_list_of_controlpanel_files(self.exclude_backups)
self.update_combo(self.controlpanel_file_combo, controlpanel_files, self.controlpanel_xml)

def count_airframes_in_conf(self):
@staticmethod
def count_airframes_in_conf(combo, conf_airframes):
airframes = 0
releases = 0
if self.conf_file_combo.get_active_text() is None:
if combo.get_active_text() is None:
return
desc = ""
afile = os.path.join(paparazzi.conf_dir, self.conf_file_combo.get_active_text())
afile = os.path.join(paparazzi.conf_dir, combo.get_active_text())
if os.path.exists(afile):
e = xml.etree.ElementTree.parse(afile).getroot()
for atype in e.findall('aircraft'):
Expand All @@ -95,7 +95,7 @@ def count_airframes_in_conf(self):
else:
desc += atype.get('name')
desc = "<b>" + str(airframes) + " airframes:</b> " + desc
self.conf_airframes.set_markup(desc)
conf_airframes.set_markup(desc)
return

def about(self, widget):
Expand All @@ -121,13 +121,22 @@ def sure(self, widget, filename):

def set_backups(self, widget):
self.exclude_backups = not widget.get_active()
self.find_conf_files()
self.find_conf_files(self.conf_file_combo)
self.find_controlpanel_files()

def more_info(self, widget):
obj = PaparazziOverview(0)
obj.run()
self.obj.run()

def show_untested(self, widget, data):
self.obj.run(show_af_detail=False, show_untested=True,
show_airframes=data["Airframes"].get_active(),
show_flightplans=data["Flightplans"].get_active(),
show_boards=data["Boards"].get_active(),
show_modules=data["Modules"].get_active())

def module_usage(self, widget, data):
selected_conf = data.get_active_text()
self.obj.airframe_module_overview(selected_conf)

def launch(self, widget):
self.accept(widget)
Expand Down Expand Up @@ -185,8 +194,8 @@ def delete_conf(self, widget):
if os.path.exists(filename):
os.remove(filename)
self.update_conf_label()
self.count_airframes_in_conf()
self.find_conf_files()
self.count_airframes_in_conf(self.conf_file_combo, self.conf_airframes)
self.find_conf_files(self.conf_file_combo)
self.print_status("Deleted: " + filename)

def delete_controlpanel(self, widget):
Expand All @@ -209,8 +218,8 @@ def accept(self, widget):
os.remove(self.conf_xml)
os.symlink(selected, self.conf_xml)
self.update_conf_label()
self.count_airframes_in_conf()
self.find_conf_files()
self.count_airframes_in_conf(self.conf_file_combo, self.conf_airframes)
self.find_conf_files(self.conf_file_combo)

selected = self.controlpanel_file_combo.get_active_text()
if selected == "control_panel.xml":
Expand All @@ -233,8 +242,8 @@ def personal_conf(self, widget):
os.remove(self.conf_xml)
os.symlink(self.conf_personal_name, self.conf_xml)
self.update_conf_label()
self.count_airframes_in_conf()
self.find_conf_files()
self.count_airframes_in_conf(self.conf_file_combo, self.conf_airframes)
self.find_conf_files(self.conf_file_combo)

def personal_controlpanel(self, widget):
if os.path.exists(self.controlpanel_personal):
Expand All @@ -251,11 +260,94 @@ def personal_controlpanel(self, widget):
def print_status(self, text):
self.statusbar.push(self.context_id, text)

def changed_cb(self, entry):
self.count_airframes_in_conf()
def changed_cb(self, widget, data):
self.count_airframes_in_conf(data["combo"], data["list"])

def maintenance_window(self, widget):
mtn_window = gtk.Window()
mtn_window.set_position(gtk.WIN_POS_CENTER)
mtn_window.set_size_request(750, 300)
mtn_window.set_title("Maintenance Tools")

mnt_vbox = gtk.VBox()

mnt_conf_label = gtk.Label("Conf:")
mnt_conf_label.set_size_request(100, 30)
mnt_conf_file_combo = gtk.combo_box_new_text()
self.find_conf_files(mnt_conf_file_combo)
mnt_conf_file_combo.set_size_request(500, 30)

mnt_conf_airframes = gtk.Label("")
self.count_airframes_in_conf(mnt_conf_file_combo, mnt_conf_airframes)
mnt_conf_airframes.set_size_request(650, 180)
mnt_conf_airframes.set_line_wrap(True)

combo_list = {"combo": mnt_conf_file_combo, "list": mnt_conf_airframes}
mnt_conf_file_combo.connect("changed", self.changed_cb, combo_list)

mnt_confbar = gtk.HBox()
mnt_confbar.pack_start(mnt_conf_label)
mnt_confbar.pack_start(mnt_conf_file_combo)
mnt_vbox.pack_start(mnt_confbar, False)

btnModule = gtk.Button("Module\nUsage")
btnModule.connect("clicked", self.module_usage, mnt_conf_file_combo)
btnModule.set_tooltip_text("More information on the modules used by these airframes")

mnt_caexbar = gtk.HBox()
mnt_caexbar.pack_start(mnt_conf_airframes)
mnt_caexbar.pack_start(btnModule)
mnt_vbox.pack_start(mnt_caexbar)

separator = gtk.HSeparator()
mnt_vbox.pack_start(separator)

cbtnAirframes = gtk.CheckButton()
cbtnAirframes.set_label("Airframes")
cbtnAirframes.set_active(True)

cbtnFlightplans = gtk.CheckButton()
cbtnFlightplans.set_label("Flight plans")
cbtnFlightplans.set_active(True)

cbtnBoards = gtk.CheckButton()
cbtnBoards.set_label("Boards")
cbtnBoards.set_active(True)

cbtnModules = gtk.CheckButton()
cbtnModules.set_label("Modules")
cbtnModules.set_active(False)

selectedOptions = {"Airframes": cbtnAirframes, "Flightplans": cbtnFlightplans,
"Boards": cbtnBoards, "Modules": cbtnModules}

btnUntested = gtk.Button(None, "Show Untested Files")
btnUntested.connect("clicked", self.show_untested, selectedOptions)
btnUntested.set_tooltip_text("For the selected options show the files not tested by any conf")

untestedHBox = gtk.HBox()
cbtnVBox = gtk.VBox()
cbRowUpper = gtk.HBox()
cbRowLower = gtk.HBox()

cbRowUpper.pack_start(cbtnAirframes)
cbRowUpper.pack_start(cbtnBoards)
cbRowLower.pack_start(cbtnFlightplans)
cbRowLower.pack_start(cbtnModules)
cbtnVBox.pack_start(cbRowUpper)
cbtnVBox.pack_start(cbRowLower)
untestedHBox.pack_start(cbtnVBox)
untestedHBox.pack_start(btnUntested)

mnt_vbox.pack_start(untestedHBox)

mtn_window.add(mnt_vbox)
mtn_window.show_all()

# Constructor Functions
def __init__(self):
self.obj = PaparazziOverview(0)

# paparazzi process
self.pp = None

Expand Down Expand Up @@ -312,8 +404,7 @@ def __init__(self):
self.conf_label.set_size_request(100, 30)

self.conf_file_combo = gtk.combo_box_new_text()
self.find_conf_files()
self.conf_file_combo.connect("changed", self.changed_cb)
self.find_conf_files(self.conf_file_combo)
self.conf_file_combo.set_size_request(550, 30)

self.btnDeleteConf = gtk.Button(None, gtk.STOCK_DELETE)
Expand Down Expand Up @@ -345,17 +436,27 @@ def __init__(self):

# Count Airframes
self.conf_airframes = gtk.Label("")
self.count_airframes_in_conf()
self.conf_airframes.set_size_request(650,180)
self.count_airframes_in_conf(self.conf_file_combo, self.conf_airframes)
self.conf_airframes.set_size_request(650, 180)
self.conf_airframes.set_line_wrap(True)

self.combo_list = {"combo": self.conf_file_combo, "list": self.conf_airframes}
self.conf_file_combo.connect("changed", self.changed_cb, self.combo_list)

self.btnInfo = gtk.Button(None, "More\nInfo")
self.btnInfo.connect("clicked", self.more_info)
self.btnInfo.set_tooltip_text("More information on airframe files")

self.btnMaintenance = gtk.Button(None, "Maintenance\n\tTools")
self.btnMaintenance.connect("clicked", self.maintenance_window)
self.btnMaintenance.set_tooltip_text("Show maintenance tools")

self.caexbar = gtk.HBox()
self.caexbar.pack_start(self.conf_airframes)
self.caexbar.pack_start(self.btnInfo)
self.caexbar_btns = gtk.VBox()
self.caexbar.pack_start(self.caexbar_btns)
self.caexbar_btns.pack_start(self.btnInfo)
self.caexbar_btns.pack_start(self.btnMaintenance)

self.my_vbox.pack_start(self.caexbar, False)

Expand Down
86 changes: 86 additions & 0 deletions sw/airborne/arch/chibios/STM32F427xT.ld
@@ -0,0 +1,86 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/

/*
* STM32F427xT memory setup.
* Note: Use of ram1 and ram2 is mutually exclusive with use of ram0.
*/
MEMORY
{
flash0 : org = 0x08004000, len = 2M
flash1 : org = 0x00000000, len = 0
flash2 : org = 0x00000000, len = 0
flash3 : org = 0x00000000, len = 0
flash4 : org = 0x00000000, len = 0
flash5 : org = 0x00000000, len = 0
flash6 : org = 0x00000000, len = 0
flash7 : org = 0x00000000, len = 0
ram0 : org = 0x20000000, len = 192k /* SRAM1 + SRAM2 + SRAM3 */
ram1 : org = 0x20000000, len = 112k /* SRAM1 */
ram2 : org = 0x2001C000, len = 16k /* SRAM2 */
ram3 : org = 0x20020000, len = 64k /* SRAM3 */
ram4 : org = 0x10000000, len = 64k /* CCM SRAM */
ram5 : org = 0x40024000, len = 4k /* BCKP SRAM */
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}

/* For each data/text section two region are defined, a virtual region
and a load region (_LMA suffix).*/

/* Flash region to be used for exception vectors.*/
REGION_ALIAS("VECTORS_FLASH", flash0);
REGION_ALIAS("VECTORS_FLASH_LMA", flash0);

/* Flash region to be used for constructors and destructors.*/
REGION_ALIAS("XTORS_FLASH", flash0);
REGION_ALIAS("XTORS_FLASH_LMA", flash0);

/* Flash region to be used for code text.*/
REGION_ALIAS("TEXT_FLASH", flash0);
REGION_ALIAS("TEXT_FLASH_LMA", flash0);

/* Flash region to be used for read only data.*/
REGION_ALIAS("RODATA_FLASH", flash0);
REGION_ALIAS("RODATA_FLASH_LMA", flash0);

/* Flash region to be used for various.*/
REGION_ALIAS("VARIOUS_FLASH", flash0);
REGION_ALIAS("VARIOUS_FLASH_LMA", flash0);

/* Flash region to be used for RAM(n) initialization data.*/
REGION_ALIAS("RAM_INIT_FLASH_LMA", flash0);

/* RAM region to be used for Main stack. This stack accommodates the processing
of all exceptions and interrupts.*/
REGION_ALIAS("MAIN_STACK_RAM", ram0);

/* RAM region to be used for the process stack. This is the stack used by
the main() function.*/
REGION_ALIAS("PROCESS_STACK_RAM", ram0);

/* RAM region to be used for data segment.*/
REGION_ALIAS("DATA_RAM", ram0);
REGION_ALIAS("DATA_RAM_LMA", flash0);

/* RAM region to be used for BSS segment.*/
REGION_ALIAS("BSS_RAM", ram0);

/* RAM region to be used for the default heap.*/
REGION_ALIAS("HEAP_RAM", ram0);

/* Generic rules inclusion.*/
INCLUDE rules.ld