MAVLab course 2018 (#2268)

* Merge cyberzoo model (squashed)

Squashed commit of the following:

commit 4ea7054205
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Tue Feb 6 11:30:28 2018 +0100

    Remove origin marker from worlds

commit c008c9658a
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Feb 2 17:25:11 2018 +0100

    Compress textures

    Reduced texture dimensions. Size of model folder is now approx.
    20 MB instead of 60+ MB.

commit 5b63fc1988
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Feb 2 17:03:26 2018 +0100

    Minor tweaks to models

commit ed003351d1
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Feb 2 15:26:28 2018 +0100

    Add cyberzoo props

commit 751b94364a
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Feb 1 15:03:30 2018 +0100

    Restore cyberzoo floor collision box

commit 1d4fd2d92f
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Feb 1 14:59:44 2018 +0100

    Add cyberzoo surroundings to main model in separate layers

commit 9df9f2832c
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Feb 1 14:48:06 2018 +0100

    Separate cyberzoo model into layers

    Makes it easier to hide parts of the model in the GUI.

commit f8c4221e98
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Feb 1 11:47:52 2018 +0100

    Add daylight in windows on outer walls

commit b0e6a0c572
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Mon Jan 29 16:25:08 2018 +0100

    Remove old cyberzoo model, fix dependencies

commit dd54000771
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Mon Jan 29 15:04:43 2018 +0100

    Add cyberzoo world with orange poles for orange_avoider

commit a34e285082
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Mon Jan 29 14:30:47 2018 +0100

    Set world coordinates and rotation, fix naming conflict

commit 1a99ebb7bd
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Jan 18 11:58:06 2018 +0100

    Create cyberzoo world

    To-do: set origin coordinates and rotate environment

commit ebf7eaf9a7
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Jan 18 11:41:37 2018 +0100

    Minor fixes to surroundings

commit c57312c557
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Jan 18 11:15:09 2018 +0100

    Add updated cyberzoo surroundings and outside walls

commit 58914e14ae
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Wed Jan 17 17:24:57 2018 +0100

    Add first draft of cyberzoo surroundings

commit 40712f5f3b
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Tue Dec 12 13:45:25 2017 +0100

    Fix cyberzoo origin

commit e47f76cee5
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Tue Dec 12 13:34:11 2017 +0100

    Fix orange_pole2 smoothing errors

commit b1e08695e7
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Tue Dec 12 13:09:09 2017 +0100

    Add orange pole and traffic mat objects

commit 8bd3d214e6
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Dec 8 14:48:53 2017 +0100

    Fix optitrack camera color

commit 59e7b67fef
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Dec 8 14:43:39 2017 +0100

    Fix lighting colors

commit 810e6124c1
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Dec 8 14:20:47 2017 +0100

    Fix optitrack cameras

commit e6e17c2677
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Fri Dec 8 14:10:55 2017 +0100

    Import improved model

commit e9ed496af9
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Thu Nov 30 16:38:22 2017 +0100

    Fix ambient lighting of cyberzoo_solid

commit 0e1c2600d6
Author: Tom van Dijk <tomvand@users.noreply.github.com>
Date:   Wed Nov 29 14:38:05 2017 +0100

    First steps towards detailed cyberzoo model. Got transparency working.

* Fix altitude overshoot in simulation

- Bypass INS
- Set nominal hover throttle to 0.51 (verified in simulation and on real drone).

* Fix INS horizontal offset

- Set flight plan origin to match gazebo spherical coordinates,
prevents https://github.com/paparazzi/paparazzi/issues/2134#issuecomment-342493105

* Increase link lost timeout to 5s

Otherwise gazebo will continuously lose link. Might need to lower
this for real-world flights...

* Fix image.c compilation warnings

* Move dummy waypoint to 0, 0

Should prevent "waypoint 'dummy' too far from HOME" warnings when
max_dist_from_home is small (e.g. cyberzoo flightplans) and when
HOME is set appropriately close to the flight plan origin.

* Rename 2017 -> 2018

Also removed simulation aircraft as it is no longer necessary.

* Move modules to firmware section

* Restore original nominal throttle

Nominal throttle of 0.51 was measured without bumpers! 0.68 is correct
with bumpers attached. Instead, increased the weight of the gazebo model.

* Clean up control panel

- Removed Bebop video stream since it did not work
- Removed the Gazebo tool. When pointed to /usr/bin/gazebo it does actually start, but
  the GAZEBO_MODEL_PATH appears to be ignored this way.

Also added conf/video.sdp to simplify video streaming (no such file
was present in var).

* Tag airframe after successful test flight

Performed test flight in cyberzoo with course2018_orangeavoid flightplan in NAV mode.

* Fix Gazebo tool, add Simulation - Gazebo + Joystick session

The new gzclient_launcher.sh script sets up the correct GAZEBO_MODEL_PATH
(which was not available when gzclient was started from the Paparazzi Center
even if it was added to ~/.bashrc). It also allows the client to be killed
from the pprz center.

* FIX remove natnet from simulation session

* Retune INDI for Bebop1 with bumpers

Previous tuning resulted in slight attitude oscillations.

* Tag after successful testflight

* Add GCS flags

* Change gazebo bebop colors

* Disable light and shadows

Top light caused ogre crash in gazebo 8.3 (not sure if version error or weak gpu).
Disabled shadow for performance since there is no light anymore.

* Reduce bebop front cam FoV to fix AxisAlignedBox crash in gazebo7

Apparaetly gazebo 7 does not yet support wide-angle cameras with
HFoVs above 180deg.

* Distance Counter Python

* Cleanup after merge

* Remove image.c fix (see #2237)

* Add 'Simulation - Gazebo' session

Avoids errors when joystick is not connected.
This commit is contained in:
Tom van Dijk
2018-05-30 17:34:03 +02:00
committed by OpenUAS
parent c870e27ac5
commit c0741e01ab
10 changed files with 265 additions and 287 deletions
@@ -1,215 +0,0 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="ardrone2">
<firmware name="rotorcraft">
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
</target>
<define name="USE_SONAR" value="TRUE"/>
<!-- Subsystem section -->
<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="motor_mixing"/>
<module name="actuators" type="ardrone2"/>
<module name="imu" type="ardrone2"/>
<!-- gps: "ublox" or change to "sirf" for usage with parrot flight recorder -->
<module name="gps" type="ublox"/>
<module name="stabilization" type="int_quat"/>
<module name="ahrs" type="int_cmpl_quat"/>
<module name="ins" type="extended"/>
<module name="bat_voltage_ardrone2"/>
<!-- remove the gps_ubx_ucenter module if you use the sirf gps (flight recorder) -->
<module name="gps" type="ubx_ucenter"/>
<module name="send_imu_mag_current"/>
<module name="air_data"/>
<module name="geo_mag"/>
<!--module name="logger_file"/-->
<module name="video_thread">
</module>
<module name="cv_colorfilter">
<define name="COLORFILTER_CAMERA" value="front_camera"/>
</module>
<module name="orange_avoider" />
<module name="video_rtp_stream">
<define name="VIEWVIDEO_CAMERA" value="front_camera"/>
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="4"/>
<define name="VIEWVIDEO_QUALITY_FACTOR" value="60"/>
</module>
</firmware>
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="3000"/>
</commands>
<servos driver="Default">
<servo name="TOP_LEFT" no="0" min="0" neutral="1" max="500"/>
<servo name="TOP_RIGHT" no="1" min="0" neutral="1" max="500"/>
<servo name="BOTTOM_RIGHT" no="2" min="0" neutral="1" max="500"/>
<servo name="BOTTOM_LEFT" no="3" min="0" neutral="1" max="500"/>
</servos>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<!-- Time cross layout (X), with order NW (CW), NE (CCW), SE (CW), SW (CCW) -->
<define name="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<!-- Gazebo Simulation values -->
<section name="COLORFILTER" prefix="ORANGE_AVOIDER_">
<define name="LUM_MIN" value="41"/>
<define name="LIM_MAX" value="183"/>
<define name="CB_MIN" value="53"/>
<define name="CB_MAX" value="121"/>
<define name="CR_MIN" value="134"/>
<define name="CR_MAX" value="249"/>
</section>
<section name="IMU" prefix="IMU_">
<!-- Accelero -->
<define name="ACCEL_X_NEUTRAL" value="2048"/>
<define name="ACCEL_Y_NEUTRAL" value="2048"/>
<define name="ACCEL_Z_NEUTRAL" value="2048"/>
<!-- Magneto calibration -->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="-180"/>
<define name="MAG_X_SENS" value="16." integer="16"/>
<define name="MAG_Y_SENS" value="16." integer="16"/>
<define name="MAG_Z_SENS" value="16." integer="16"/>
<!-- Magneto current calibration -->
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- Toulouse -->
<define name="H_X" value="0.513081"/>
<define name="H_Y" value="-0.00242783"/>
<define name="H_Z" value="0.858336"/>
<!-- Delft -->
<!--define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/ -->
</section>
<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="600" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="200" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="300." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(4000.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="850"/>
<define name="PHI_DGAIN" value="425"/>
<define name="PHI_IGAIN" value="0"/>
<define name="THETA_PGAIN" value="850"/>
<define name="THETA_DGAIN" value="425"/>
<define name="THETA_IGAIN" value="0"/>
<define name="PSI_PGAIN" value="1000"/>
<define name="PSI_DGAIN" value="700"/>
<define name="PSI_IGAIN" value="0"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="100"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="13"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="79"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_ardrone2" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_ardrone2.h" type="string"/>
</section>
<include href="conf/simulator/gazebo/airframes/ardrone2.xml"/>
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
@@ -1,7 +1,7 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="bebop_avoider">
<description>Vision Course TUDelft V2017
<description>Vision Course TUDelft V2018
</description>
@@ -41,9 +41,7 @@
<!-- <module name="guidance" type="indi"> <define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN"
value="-500.0"/> <define name="GUIDANCE_INDI_THRUST_DYNAMICS" value="0.1"/>
<define name="GUIDANCE_INDI_RC_DEBUG" value="TRUE"/> </module> -->
</firmware>
<modules main_freq="512">
<!--module name="geo_mag"/-->
<module name="air_data"/>
<!--module name="send_imu_mag_current"/-->
@@ -72,8 +70,7 @@
<!-- <define name="VIEWVIDEO_WRITE_VIDEO" value="FALSE" />
<define name="VIEWVIDEO_VIDEO_FILE" value="orangeAvoider" /> -->
</module>
</modules>
</firmware>
<commands>
<axis name="PITCH" failsafe_value="0"/>
@@ -183,10 +180,10 @@
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.0639"/>
<define name="G1_Q" value="0.0361"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.1450"/>
<define name="G1_P" value="0.0397"/>
<define name="G1_Q" value="0.0299"/>
<define name="G1_R" value="0.0014"/>
<define name="G2_R" value="0.1219"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="600.0"/>
@@ -1,6 +1,6 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="1.0" ground_alt="0" lat0="51.9906224" lon0="4.3767678" max_dist_from_home="8" name="Bebop avoid orange TU Delft Cyberzoo" security_height="0.4">
<flight_plan alt="1.0" ground_alt="0" lat0="51.9906361" lon0="4.3767874" max_dist_from_home="8" name="Bebop avoid orange TU Delft Cyberzoo" security_height="0.4">
<header>
#include "subsystems/datalink/datalink.h"
#include "subsystems/electrical.h"
@@ -8,7 +8,7 @@
#include "subsystems/ahrs.h"
// Note: use 'git submodule update --init -- sw/ext/tudelft_gazebo_models/'
// to download the required models.
// to download the required models.
#define NPS_GAZEBO_WORLD "cyberzoo_orange_poles.world"
</header>
<waypoints>
@@ -48,7 +48,7 @@
!(nav_block >= IndexOfBlock('Land here')) &&
(autopilot_in_flight() == true) )" deroute="Standby"/-->
<!-- Datalink lost (constant RPM descent) -->
<exception cond="((datalink_time > 2) &&
<exception cond="((datalink_time > 5) &&
!(IndexOfBlock('Holding point') > nav_block) &&
!(nav_block >= IndexOfBlock('Land here')) &&
(autopilot_in_flight() == true) )" deroute="Land here"/>
@@ -8,6 +8,7 @@
<define name="ACTUATOR_MAX_ANGULAR_MOMENTUM" value="0.19, 0.19, 0.19, 0.19" type="float[]"/>
<define name="GAZEBO_AC_NAME" value="bebop" type="string"/>
<define name="BYPASS_AHRS" value="1"/>
<define name="BYPASS_INS" value="1"/>
<define name="SIMULATE_MT9F002" value="1"/>
</section>
</airframe>
+11 -7
View File
@@ -9,7 +9,7 @@
</velocity_decay>
<inertial>
<mass>0.38905</mass>
<mass>0.536</mass><!-- With bumpers. Tuned for correct nominal hover thrust, mass is higher than in real life (~0.40kg) -->
<inertia>
<ixx> 0.000906 </ixx>
<iyy> 0.001242 </iyy>
@@ -34,6 +34,10 @@
<size>0.15 0.05 0.05</size>
</box>
</geometry>
<material>
<diffuse>0.82 0.07 0.07 1</diffuse>
<ambient>0.82 0.07 0.07 1</ambient>
</material>
</visual>
<sensor name="contactsensor" type="contact">
@@ -65,8 +69,8 @@
</cylinder>
</geometry>
<material>
<diffuse>0.25 0.85 0.95 1</diffuse>
<ambient>0.25 0.85 0.95 1</ambient>
<diffuse>0.82 0.07 0.07 1</diffuse>
<ambient>0.82 0.07 0.07 1</ambient>
</material>
</visual>
</link>
@@ -129,8 +133,8 @@
</cylinder>
</geometry>
<material>
<diffuse>0.25 0.85 0.95 1</diffuse>
<ambient>0.25 0.85 0.95 1</ambient>
<diffuse>0.82 0.07 0.07 1</diffuse>
<ambient>0.82 0.07 0.07 1</ambient>
</material>
</visual>
</link>
@@ -192,11 +196,11 @@
<update_rate>15.0</update_rate><!-- adjust with MT9F002_TARGET_FPS -->
<camera name="front_camera">
<image>
<width>4608</width><!-- with MT9F002_OUTPUT_SCALER = 1.00, will be scaled by NPS -->
<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.69</horizontal_fov>
<horizontal_fov>3.00</horizontal_fov>
<lens>
<type>equisolid_angle</type>
<scale_to_hfov>true</scale_to_hfov>
-26
View File
@@ -1,26 +0,0 @@
<conf>
<aircraft
name="bebop_orange_avoid"
ac_id="42"
airframe="airframes/tudelft/bebop_orangeavoid_course2017.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/course2017_avoid_orange_cyberzoo.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_colorfilter.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="868ce39dbaa0f004ff1fa29fc97f045b8b73fae6"
/>
<aircraft
name="simulate_orange_avoid"
ac_id="232"
airframe="airframes/tudelft/ardrone2_orangeavoid_course2017_gazebo.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/course2017_avoid_orange_cyberzoo.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_colorfilter.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="red"
release="ea9d5a724642442f92503098a32e29a9d90b3385"
/>
</conf>
+14
View File
@@ -0,0 +1,14 @@
<conf>
<aircraft
name="bebop_orange_avoid"
ac_id="42"
airframe="airframes/tudelft/bebop_course2018_orangeavoid.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/course2018_orangeavoid_cyberzoo.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_colorfilter.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"
/>
</conf>
@@ -4,8 +4,15 @@
<program name="Data Link" command="sw/ground_segment/tmtc/link">
<arg flag="-d" constant="/dev/ttyUSB0"/>
</program>
<program name="GCS" command="sw/ground_segment/cockpit/gcs"/>
<program name="Bebop Video Stream" command="/usr/bin/cvlc ftp://192.168.42.1/internal_000/stream.sdp --avcodec-hw=vaapi --no-xlib --quiet --no-interact"/>
<program name="GCS" command="sw/ground_segment/cockpit/gcs">
<arg flag="-speech"/>
<arg flag="-maximize"/>
<arg flag="-center_ac"/>
<arg flag="-mercator"/>
<arg flag="-maps_no_http"/>
<arg flag="-track_size" constant="200"/>
<arg flag="-zoom" constant="40."/>
</program>
<program name="Messages" command="sw/ground_segment/tmtc/messages"/>
<program name="Settings" command="sw/ground_segment/tmtc/settings">
<arg flag="-ac" constant="@AIRCRAFT"/>
@@ -23,7 +30,56 @@
<program name="Gazebo" command="sw/tools/gzclient_launcher.sh"/>
</section>
<section name="sessions">
<session name="Bebop basic">
<session name="Simulation - Gazebo">
<program name="Simulator">
<arg flag="-a" constant="@AIRCRAFT"/>
<arg flag="-t" constant="nps"/>
</program>
<program name="Data Link">
<arg flag="-udp"/>
</program>
<program name="Server">
<arg flag="-n"/>
</program>
<program name="GCS">
<arg flag="-speech"/>
<arg flag="-maximize"/>
<arg flag="-center_ac"/>
<arg flag="-mercator"/>
<arg flag="-maps_no_http"/>
<arg flag="-track_size" constant="200"/>
<arg flag="-zoom" constant="40."/>
</program>
<program name="Gazebo"/>
</session>
<session name="Simulation - Gazebo + Joystick">
<program name="Simulator">
<arg flag="-a" constant="@AIRCRAFT"/>
<arg flag="-t" constant="nps"/>
</program>
<program name="Data Link">
<arg flag="-udp"/>
</program>
<program name="Server">
<arg flag="-n"/>
</program>
<program name="GCS">
<arg flag="-speech"/>
<arg flag="-maximize"/>
<arg flag="-center_ac"/>
<arg flag="-mercator"/>
<arg flag="-maps_no_http"/>
<arg flag="-track_size" constant="200"/>
<arg flag="-zoom" constant="40."/>
</program>
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
<arg flag="-ac" constant="@AIRCRAFT"/>
<arg flag="hobbyking.xml"/>
<arg flag="-d 0"/>
</program>
<program name="Gazebo"/>
</session>
<session name="Flight UDP">
<program name="Data Link">
<arg flag="-udp"/>
</program>
@@ -34,31 +90,11 @@
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
<arg flag="-ac" constant="@AIRCRAFT"/>
<arg flag="hobbyking.xml"/>
<arg flag="-d 0"/>
</program>
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy">
<arg flag="-ac 9999" constant="@AC_ID"/>
</program>
<program name="Bebop Video Stream"/>
<arg flag="-ac 9999" constant="@AC_ID"/>
</program>
</session>
<session name="Bebop extensive">
<program name="Data Link">
<arg flag="-udp"/>
</program>
<program name="Server"/>
<program name="GCS">
<arg flag="-speech"/>
</program>
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
<arg flag="-d" constant="2"/>
<arg flag="-ac" constant="@AIRCRAFT"/>
<arg flag="hobbyking.xml"/>
</program>
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy">
<arg flag="-ac 3" constant="@AC_ID"/>
</program>
<program name="Messages" command="sw/ground_segment/tmtc/messages"/>
</session>
</section>
</control_panel>
+43
View File
@@ -0,0 +1,43 @@
#!/usr/bin/env python
#
# Copyright (C) 2016 TUDelft
#
# This file is part of paparazzi.
#
# paparazzi is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# paparazzi is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with paparazzi. If not, see <http://www.gnu.org/licenses/>.
#
import wx
import sys
import argparse
import distance_counter
parser = argparse.ArgumentParser(description='Capture PAYLOAD messages over the IVY bus and forward to a remote application.', epilog='payload.py is part of the paparazzi-uav project.')
settings = parser.parse_args()
print(settings)
class DistanceFrame(wx.App):
def OnInit(self):
self.main = distance_counter.DistanceCounterFrame(settings)
self.main.Show()
self.SetTopWindow(self.main)
return True
def main():
application = DistanceFrame(0)
application.MainLoop()
if __name__ == '__main__':
main()
@@ -0,0 +1,124 @@
#
# Copyright (C) 2016 TUDelft
#
# This file is part of paparazzi.
#
# paparazzi is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# paparazzi is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with paparazzi. If not, see <http://www.gnu.org/licenses/>.
#
import wx
import sys
import os
import threading
import socket
import array
from cStringIO import StringIO
import wx
import array
import Image
import math
PPRZ_SRC = os.getenv("PAPARAZZI_SRC", os.path.normpath(os.path.join(os.path.dirname(os.path.abspath(__file__)), '../../../..')))
sys.path.append(PPRZ_SRC + "/sw/ext/pprzlink/lib/v1.0/python")
from pprzlink.ivy import IvyMessagesInterface
WIDTH = 300
class DistanceCounterFrame(wx.Frame):
def message_recv(self, ac_id, msg):
if msg.name == "INS":
self.msg_count = self.msg_count + 1
newx = float(msg.get_field(0)) / 256.0
newy = float(msg.get_field(1)) / 256.0
moved = ((newx - self.ins_msg_x) ** 2 + (newy - self.ins_msg_y) ** 2)
if self.init == 0:
self.init = 1
else:
self.distance = self.distance + math.sqrt(moved)
self.ins_msg_x = newx
self.ins_msg_y = newy
self.ins_msg_z = msg.get_field(2)
# graphical update
wx.CallAfter(self.update)
def update(self):
self.Refresh()
def OnSize(self, event):
self.w = event.GetSize()[0]
self.h = event.GetSize()[1]
self.Refresh()
def OnPaint(self, e):
# Paint Area
dc = wx.PaintDC(self)
brush = wx.Brush("white")
dc.SetBackground(brush)
dc.Clear()
# Background
dc.SetBrush(wx.Brush(wx.Colour(0,0,0), wx.TRANSPARENT))
font = wx.Font(11, wx.DEFAULT, wx.NORMAL, wx.NORMAL)
dc.SetFont(font)
dc.DrawText("INS Packets:" + str(self.msg_count),2,2)
dc.DrawText("Data: " + str(self.ins_msg_x) + ", " + str(self.ins_msg_y) + ", " + str(self.ins_msg_z) + ".",2,22)
dc.DrawText("Distance: " + str(round(float(self.distance)/1.0,2)) + " m",2,22+20)
def __init__(self, _settings):
# Command line arguments
self.settings = _settings
# Statistics
self.data = { 'packets': 0, 'bytes': 0}
self.w = WIDTH
self.h = WIDTH
# Frame
wx.Frame.__init__(self, id=-1, parent=None, name=u'Distance Counter',
size=wx.Size(self.w, self.h), title=u'Distance Counter')
self.Bind(wx.EVT_PAINT, self.OnPaint)
self.Bind(wx.EVT_SIZE, self.OnSize)
self.Bind(wx.EVT_CLOSE, self.OnClose)
# IVY
self.interface = IvyMessagesInterface("DistanceCounter")
self.interface.subscribe(self.message_recv)
self.msg_count = 0
self.distance = 0
self.ins_msg_x = 0
self.ins_msg_y = 0
self.ins_msg_z = 0
self.init = 0
def OnClose(self, event):
self.interface.shutdown()
self.Destroy()