| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> | ||
|
|
||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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> |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,2 @@ | ||
| <program command="sw/ground_segment/python/matlab2pprz/matlab2pprz.py" name="Matlab/PPRZ/Natnet bridge" /> | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -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 |