Skip to content

Commit

Permalink
Add Gazebo simulation to NPS (#2069)
Browse files Browse the repository at this point in the history
* Setup code for Gazebo

Currently only partially initializes the fdm struct, which produces
incorrect results in the GCS.
Compilation, however, already seems to work as expected!

Next step is to fetch data from Gazebo.

* Closed-loop flight in Gazebo

Finished the first implementation of the Gazebo FDM. It is now possible
to perform closed-loop flights using Paparazzi together with Gazebo.

Look at the example_ardrone2.xml airframe file for the required gazebo tags.
The following modifications are made:
- change fdm type to "gazebo"
- add definitions for ACTUATOR_THRUSTS and ACTUATOR_TORQUES. These were
  obtained from the JSBsim ardrone model. The oredr is the same as the
  ACTUATOR_NAMES.

The Gazebo world needs an aircraft model that is (by default) named
"paparazzi_uav". This model should include links with the names listed
in ACTUATOR_NAMES in the airframe file, as these are used to apply
forces on the quadrotor.

Known bugs:
- No fixed wing aircraft yet.
- Not all fields in the fdm struct are set. Most of the atmosphere
  fields are not implemented yet.
- AHRS and INS need to be bypassed, these do not yet work correctly.
- No quadrotor models are supplied with paparazzi yet (although it is
  included in the example world file).

* Added cameras, but sensor update causes crash

As in the quick standalone examples, gazebo regularly crashes when
cameras are used.

This is an intermediary commit where most of the camera infrastructure
is present, but not functional yet because of an unknown bug regarding
Gazebo.

* Simplified problem, located crash

Crash occurs when gazebo::sensors::run_once() is called during
the fdm update step. The exception (Ogre internal exception,
cannot create GL vertex buffer) only occurs after the main loop
has been performed a few times (10-20x typically).

Ignoring the error by catching the exception does not make it go
away.

* Add ogre to fdm_gazebo makefile

* Further changes for debugging, not fixed yet

* FIX bug

Turns out that fdm_init and fdm_run_step are not running in the same
thread, which apparently caused some problems with Gazebo.

The gazebo initialization code that starts the server is now moved
to the run_step function, and cameras work fine now.

Next step is to get the images from Gazebo to the video_thread_nps module.

* Transport images to Paparazzi

Added code that converts Gazebo's RGB888 images to Paparazzi's
YUV422 format, and calls the registered video callbacks.

* Finish video streaming

Finished video streaming. Video streaming in the paparazzi master
branch does not seem to work in simulation or even on a real ardrone.
Therefore, reverted to v5.10 viewvideo.c and rtp.c and now the streaming
works correctly.

* Separate UAV model from world.

Added a models/ directory to conf/simulator/gazebo, now the UAV model
can be included in the world file. The models/ dir is added to Gazebo's
search paths when the server is launched, so it does not require
any additional steps from the user.

* Move Gazebo modifications from examples/ardrone2.xml to examples/ardrone2_gazebo.xml

Reverted changes to the original airframe and moved these to a
separate example.

* Remove .sdp file

Remove .sdp file that should not have been included with commits.

* Move changes in conf_example.xml to separate entry

Moved the changes to conf_example.xml (selected flightplan, modules etc.)
to a separate etry named 'ardrone2 (Gazebo)'.

* Clean up changes to computer_vision module

- Removed unused viewvideo_nps.c.
- Add doc comments in video_thread_nps.c

* Fix bug in conf_example

Spaces in aircraft name caused compilation error, changed to
'ardrone2_gazebo'.

* Fix duplicate ac_id in conf_example

* Remove debug code from nps_fdm_gazebo.cpp and add comments

* Reduce weight of cameras

Cameras weighed 10 grams, which was quite much. Now reduced to 1 gram.

* Fix camera not active

During the cleanup of the ardrone gazebo model, the always_on tag
was removed. Now, the cameras are activated during gazebo_video_init

Also removed further debug code from nps_fdm_gazebo.cpp.

* Restore master branch video streamer and rtp encoder

The streamer of the master branh does not work correctly atm, but
this will be moved to a separate issue.

* Fix compilation warnings

Fixed all compilation warnings (tested with Gazebo 8).

Unused arguments are now marked as such.

The NPS makefile is modified to use CXXFLAGS in addition to CFLAGS,
which solves the std=c++11 related warnings.

fdm_gazebo.cpp now ignores deprecated warnings, as all of these
come from Gazebo. Not the cleanest solution, but it works for now.

* Add documentation to fdm module xml and add copyright notices where appropriate

* Fix code style

Fixed code style using the tool included with paparazzi.

* Fix missing model.config

.gitignore caused the model.config files for the Gazebo models to
be excluded from the commit. Added an exception to .gitignore and
added the missing file.

* Fix INS by adding placeholder atmospheric data values

Added placeholder values to the atmospheric section of the NPM
struct. These should be valid for low altitude, low speed flights.

Previously, these values were uninitialized which caused INS to fail
(incorrect altitude estimates). With these placeholder values,
the INS works ok and no longer needs to be bypassed.

* Fix makefile targets in video_rtp_stream and cv_colorfilter

(Re)added target="ap|nps" attribute to the module .xml files.
  • Loading branch information
tomvand authored and kirkscheper committed Jun 13, 2017
1 parent 30d5e73 commit 9d1e71b
Show file tree
Hide file tree
Showing 15 changed files with 1,313 additions and 87 deletions.
1 change: 1 addition & 0 deletions .gitignore
Expand Up @@ -65,6 +65,7 @@ paparazzi.sublime-workspace
/conf/maps_data/*
/conf/maps.xml
/conf/gps/ublox_conf
!/conf/simulator/gazebo/**/*.config

# /doc/pprz_algebra/
/doc/pprz_algebra/headfile.log
Expand Down
1 change: 1 addition & 0 deletions conf/Makefile.nps
Expand Up @@ -45,6 +45,7 @@ CFLAGS += $(shell pkg-config --cflags-only-I ivy-glib)
CXXFLAGS = -W -Wall
CXXFLAGS += $(INCLUDES)
CXXFLAGS += $($(TARGET).CFLAGS)
CXXFLAGS += $($(TARGET).CXXFLAGS)
CXXFLAGS += $(USER_CFLAGS) $(BOARD_CFLAGS)
CXXFLAGS += -O$(OPT)
CXXFLAGS += $(DEBUG_FLAGS)
Expand Down
209 changes: 209 additions & 0 deletions conf/airframes/examples/ardrone2_gazebo.xml
@@ -0,0 +1,209 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<airframe name="ardrone2">

<firmware name="rotorcraft">
<target name="ap" board="ardrone2"/>

<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"/>
</firmware>

<modules main_freq="512">
<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="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>
</modules>

<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>

<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="ACTUATOR_THRUSTS" value="1.55, 1.55, 1.55, 1.55" type="double[]"/>
<define name="ACTUATOR_TORQUES" value="0.155, -0.155, 0.155, -0.155" type="double[]"/>
<define name="JSBSIM_MODEL" value="simple_ardrone2" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_ardrone2.h" type="string"/>
<define name="BYPASS_AHRS" value="1"/>
<define name="SIMULATE_VIDEO" value="1"/>
</section>

<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>
11 changes: 11 additions & 0 deletions conf/conf_example.xml
Expand Up @@ -241,6 +241,17 @@
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="red"
/>
<aircraft
name="ardrone2_gazebo"
ac_id="32"
airframe="airframes/examples/ardrone2_gazebo.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_optitrack.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"
/>
<aircraft
name="bebop"
ac_id="33"
Expand Down
2 changes: 1 addition & 1 deletion conf/modules/cv_colorfilter.xml
Expand Up @@ -27,7 +27,7 @@
</header>

<init fun="colorfilter_init()"/>
<makefile target="ap">
<makefile target="ap|nps">
<file name="colorfilter.c"/>
</makefile>
</module>
Expand Down
92 changes: 92 additions & 0 deletions conf/modules/fdm_gazebo.xml
@@ -0,0 +1,92 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="fdm_gazebo" dir="fdm">
<doc>
<description>
Gazebo backend for NPS simulator
NPS doc: http://wiki.paparazziuav.org/wiki/NPS

Usage:
1. Make sure gazebo 7 or 8 is installed. (sudo apt-get install gazebo8 libgazebo8-dev)
2. Prepare the Gazebo world and model:
a) Prepare the UAV model (see conf/simulator/gazebo/models/ardrone/):
Place the aircraft model in the conf/simulator/gazebo/models/
folder, this folder is added to Gazebo&apos;s search path when NPS is
launched.
Gazebo uses a Front, Left, Up coordinate system for aircraft, so
make sure the +x axis points forwards.
The model should include a link for each motor with the same names
as those listed in NPS_ACTUATOR_NAMES (see below), e.g. &apos;nw_motor&apos;.
Camera links should have the name specified in .dev_name in the
corresponding video_config_t struct, see sw/airborne/boards/pc_sim.h
and sw/airborne/modules/computer_vision/video_thread_nps.c.
b) Prepare the world (see conf/simulator/gazebo/worlds/ardrone.world).
Pay attention to the following:
The real-time update rate should be set to zero, as this is
already handled by Paparazzi:
&lt;physics type=&quot;ode&quot;&gt;
&lt;max_step_size&gt;0.001&lt;/max_step_size&gt;
&lt;real_time_update_rate&gt;0&lt;/real_time_update_rate&gt;&lt;!-- Handled by Paparazzi! --&gt;
&lt;/physics&gt;
Spherical coordinates should be provided for navigation.
At this moment, there is an issue where Gazebo incorrectly
uses a WSU coordinate system instead of ENU. This can be fixed
by setting the heading to 180 degrees as shown below:
&lt;spherical_coordinates&gt;
&lt;surface_model&gt;EARTH_WGS84&lt;/surface_model&gt;
&lt;latitude_deg&gt;51.9906&lt;/latitude_deg&gt;
&lt;longitude_deg&gt;4.37679&lt;/longitude_deg&gt;
&lt;elevation&gt;0&lt;/elevation&gt;
&lt;heading_deg&gt;180&lt;/heading_deg&gt;&lt;!-- Temporary fix for issue https://bitbucket.org/osrf/gazebo/issues/2022/default-sphericalcoordinates-frame-should --&gt;
&lt;/spherical_coordinates&gt;
3. Prepare the airframe file (see examples/ardrone2_gazebo.xml):
a) Select Gazebo as the FDM (Flight Dynamics Model)
&lt;target name=&quot;nps&quot; board=&quot;pc&quot;&gt;
&lt;module name=&quot;fdm&quot; type=&quot;gazebo&quot;/&gt;
&lt;/target&gt;
b) Add actuator thrusts and torques to the SIMULATOR section:
&lt;section name=&quot;SIMULATOR&quot; prefix=&quot;NPS_&quot;&gt;
&lt;define name=&quot;ACTUATOR_NAMES&quot; value=&quot;nw_motor, ne_motor, se_motor, sw_motor&quot; type=&quot;string[]&quot;/&gt;
&lt;define name=&quot;ACTUATOR_THRUSTS&quot; value=&quot;1.55, 1.55, 1.55, 1.55&quot; type=&quot;double[]&quot;/&gt;
&lt;define name=&quot;ACTUATOR_TORQUES&quot; value=&quot;0.155, -0.155, 0.155, -0.155&quot; type=&quot;double[]&quot;/&gt;
...
&lt;section&gt;
The thrusts and torques are expressed in SI units (N, Nm) and should
be in the same order as the ACTUATOR_NAMES.
c) In the same section, bypass the AHRS and INS as these are not
supported yet:
&lt;section name=&quot;SIMULATOR&quot; prefix=&quot;NPS_&quot;&gt;
...
&lt;define name=&quot;BYPASS_AHRS&quot; value=&quot;1&quot;/&gt;
&lt;define name=&quot;BYPASS_INS&quot; value=&quot;1&quot;/&gt;
...
&lt;section&gt;
d) If required, enable video thread simulation:
&lt;section name=&quot;SIMULATOR&quot; prefix=&quot;NPS_&quot;&gt;
...
&lt;define name=&quot;SIMULATE_VIDEO&quot; value=&quot;1&quot;/&gt;
...
&lt;section&gt;
e) If required, specify the Gazebo world and aircraft name:
&lt;section name=&quot;SIMULATOR&quot; prefix=&quot;NPS_&quot;&gt;
...
&lt;define name=&quot;GAZEBO_WORLD&quot; value=&quot;my_world.world&quot;/&gt;
&lt;define name=&quot;GAZEBO_AC_NAME&quot; value=&quot;my_uav&quot;/&gt;
&lt;section&gt;
4. Make sure all included modules work with nps. At the moment, most of
the modules that depend on video_thread are only built when ap is
selected as the target. As a quick fix, try to remove the target
attribute from the makefile element in the module xml, e.g.:
&lt;makefile target=&quot;ap&quot;&gt; ---&gt; &lt;makefile&gt;
</description>
</doc>
<header/>
<makefile target="nps">
<raw>
nps.CXXFLAGS += $(shell pkg-config gazebo --cflags)
nps.LDFLAGS += $(shell pkg-config gazebo --libs)
</raw>
<file name="nps_fdm_gazebo.cpp" dir="nps"/>
</makefile>
</module>

2 changes: 1 addition & 1 deletion conf/modules/video_rtp_stream.xml
Expand Up @@ -34,7 +34,7 @@
</header>

<init fun="viewvideo_init()"/>
<makefile target="ap">
<makefile target="ap|nps">

<file name="viewvideo.c"/>
<!-- Include the needed Computer Vision files -->
Expand Down

0 comments on commit 9d1e71b

Please sign in to comment.