Giter VIP home page Giter VIP logo

px4-sitl_gazebo-classic's Introduction

PX4 Gazebo Plugin Suite for MAVLink SITL and HITL

Build Status MacOS Build Tests

This is a flight simulator for rovers, boats, multirotors, VTOL, fixed wing. It uses the motor model and other pieces from the RotorS simulator, but in contrast to RotorS has no dependency on ROS. Original project: https://github.com/ethz-asl/rotors_simulator.

If you use this simulator in academic work, please cite RotorS as per the README in the above link.

Installation

This simulator is designed to be used with the PX4 Autopilot. Please follow the official developer toolchain installation instructions: http://docs.px4.io/main/en/sim_gazebo_classic/

Contributing and Testing

Please refer to the installations instructions above for normal usage and to get the development environment installed. This section covers specifics for developers interested to contribute to the simulator.

sitl_gazebo plugin dependencies

Some plugins on this packages require some specific dependencies:

  • Protobuf is required to generate custom protobuf messages to be published and subscribed between topics of different plugins;
  • Jinja 2 is used to generate some SDF models from templates;
  • Gstreamer is required for a plugin that streams video from a simulated camera.

Build sitl_gazebo

Clone the repository to your computer.

IMPORTANT: If you do not clone to ~/src/sitl_gazebo, all remaining paths in these instructions will need to be adjusted.

mkdir -p ~/src
cd src
git clone --recursive https://github.com/PX4/sitl_gazebo.git

Create a build folder in the top level of your repository:

mkdir build

Navigate into the build directory and invoke CMake from it:

cd ~/src/sitl_gazebo
cd build
cmake ..

Now build the gazebo plugins by typing:

make -j$(nproc) -l$(nproc)

Next add the location of this build directory to your gazebo plugin path, e.g. add the following line to your .bashrc (Linux) or .bash_profile (Mac) file:

# Set the plugin path so Gazebo finds our model and sim
export GAZEBO_PLUGIN_PATH=${GAZEBO_PLUGIN_PATH}:$HOME/src/sitl_gazebo/build
# Set the model path so Gazebo finds the airframes
export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:$HOME/src/sitl_gazebo/models
# Disable online model lookup since this is quite experimental and unstable
export GAZEBO_MODEL_DATABASE_URI=""

You also need to add the the root location of this repository, e.g. add the following line to your .bashrc (Linux) or .bash_profile (Mac) file:

# Set path to sitl_gazebo repository
export SITL_GAZEBO_PATH=$HOME/src/sitl_gazebo

Install

If you wish the libraries and models to be usable anywhere on your system without specifying th paths, install as shown below.

Note: If you are using Ubuntu, it is best to see the packaging section.

sudo make install

Testing

Gazebo will now launch when typing 'gazebo' on the shell:

. /usr/share/gazebo/setup.sh
. /usr/share/mavlink_sitl_gazebo/setup.sh
gazebo worlds/iris.world

Please refer to the documentation of the particular flight stack how to run it against this framework, e.g. PX4

Unit Tests

For building and running test an installation of 'googletest' is needed.

On Ubuntu it can be installed with:

sudo apt-get install libgtest-dev
cd /usr/src/googletest
sudo cmake . && cd googletest
sudo make -j$(nproc) -l$(nproc)
sudo cp *.a /usr/lib

On macOS it needs to be installed from source:

git clone https://github.com/google/googletest
pushd googletest
mkdir build
pushd build
cmake ..
make -j$(nproc) -l$(nproc)
make install

When writing test it’s important to be careful which API functions of Gazebo are called. As no Gazebo server is running during the tests some functions can produce undefined behaviour (e.g. segfaults).

CUDA Hardware Accelerated H264 encoding (optional)

  1. Download CUDA 10.0 from https://developer.nvidia.com/cuda-toolkit-archive.
  2. Download Video Codec SDK 9.0 from https://developer.nvidia.com/video-codec-sdk-archive.
  3. Install both archives:
wget https://raw.githubusercontent.com/jackersson/env-setup/master/gst-nvidia-docker/install_video_codec_sdk.sh
chmod +x install_video_codec_sdk.sh
sudo ./install_video_codec_sdk.sh
sudo dpkg -i cuda-repo-ubuntu*.deb
sudo apt-key add /var/cuda-repo-<version>/7fa2af80.pub
sudo apt-get update
sudo apt-get install cuda
  1. Reboot your system and run the command nvidia-smi to verify the successul installation of CUDA.
  2. Install GStreamer 1.18.3:
git clone https://github.com/GStreamer/gst-build -b 1.18.3
cd gst-build
meson -Dbuildtype=release -Dstrip=true -Dgst-plugins-bad:introspection=enabled -Dgst-plugins-bad:nvcodec=enabled builddir
ninja -C builddir
sudo meson install -C builddir
  1. Add <useCuda>true</useCuda> to any gazebo_gst_camera_plugin in a SDF file. For example ./models/fpv_cam/fpv_cam.sdf.

catkin tools

With catkin, the unit tests are enabled by default.

# After setting up the catkin workspace
catkin build -j4 -l4 -DBUILD_ROS_PLUGINS=ON
cd build/mavlink_sitl_gazebo/
catkin run_tests

Plain CMake

For building the tests with plain CMake, the flag ENABLE_UNIT_TESTS needs to be provided.

mkdir build && cd build
cmake -DENABLE_UNIT_TESTS=On ..

Then build and run the tests:

make -j$(nproc) -l$(nproc)
make test

Packaging

Debian packages

To create a debian package for Ubuntu and install it to your system.

cd Build
cmake ..
make
rm *.deb
cpack -G DEB
sudo dpkg -i *.deb

px4-sitl_gazebo-classic's People

Contributors

ahcorde avatar anton-matosov avatar arwagoner avatar bazookajoe1900 avatar bkueng avatar bozkurthan avatar christophtobler avatar dagar avatar devbharat avatar eliatarasov avatar frederictaillandier avatar iwishiwasaneagle avatar jaeyoung-lim avatar jgoppert avatar julianoes avatar kamilritz avatar konradrudin avatar lennartalff avatar lorenzmeier avatar lukaswoodtli avatar mrivi avatar ndepal avatar nicolaerosia avatar ricardom17 avatar romanbapst avatar sfuhrer avatar spurnvoj avatar stmoon avatar tfoote avatar tsc21 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

px4-sitl_gazebo-classic's Issues

PX4 simulation in Gazebo

anyone know how to simulate PX4 in Gazebo? when I enter "make posix_sitl_default gazebo", the error which is
CMakeFiles/Makefile2:9960: recipe for target 'src/firmware/posix/CMakeFiles/gazebo.dir/rule' failed
make[2]: *** [src/firmware/posix/CMakeFiles/gazebo.dir/rule] Error 2
Makefile:3497: recipe for target 'gazebo' failed
make[1]: *** [gazebo] Error 2
Makefile:160: recipe for target 'posix_sitl_default' failed
make: *** [posix_sitl_default] Error 2
will appear.

standard VTOL model scaling incorrect for body and flaps

The scaling for the vtol props and frame etc are correct, but when running on gazebo 7 in a catkin workspace, the scaling for the body and flaps is wrong, they are about 100 times larger than they should be.

vtol-body

./integrations_tests/run_tests.bash

let it run, and it will create a catkin workspace on the parent directory of the px4 source, now navigate to that directory

cd ../catkin
. ./devel/setup.bash
catking build
rostest px4 mavros_posix_tests_standard_vtol.launch gui:=true

Bidirectional Motor

In my project, I have a bidirectional motor and it is controlled using the auxiliary port and an ESC configured to rotate bidirectionally. I know that the motor_model on sitl_gazebo either rotates in CW or CCW. Can anyone give some suggestions about I can go about changing this to make it bidirectional? (eg: -1 to 0 control input for reverse, 0 to 1 for forward).
image

The motor is placed on the tail arm of a tricopter.

@TSC21

SITL with PX4 no GPS and couldn't take off.

I have asked this question in: PX4 issue:9178. When I typed command "make posix_sitl_default gazebo", the iris neither can get home position nor take off. :(
2018-04-03

I tested the ekf2 and gpssim status, they're both not OK:
pxh> ekf2 status
INFO [ekf2] local position OK no
INFO [ekf2] global position OK no

pxh> gpssim status
INFO [gpssim] protocol: SIM
INFO [gpssim] port: , baudrate: 0, status: NOT OK
INFO [gpssim] sat info: disabled, noise: 0, jamming detected: NO

I have tried the different version of Gazebo from 8 to 10, and re-install PX4 firmware, it is still not going well. Can anyone help me to see what's wrong, thank U all !

Gazebo Wind Plugin Protobuf Error

Hi

I've recently decided to try and compile the site_gazebo package on Mac. This entailed building it against Gazebo 8 as well as Protobuf 3.3.0 and protobuf-c 1.2.1. Aside from the expected Gazebo 8 compatibility issues being addressed in the pull request #95, I've also come across a protobuf error in regards to the wind photo file.

/Users/eric1221bday/sandbox/quadcopter/src/sitl_gazebo/src/gazebo_wind_plugin.cpp:25:10: warning: non-portable path to file '"wind.pb.h"'; specified path differs in case from file name on disk [-Wnonportable-include-path]
#include "Wind.pb.h"
         ^~~~~~~~~~~
         "wind.pb.h"
/Users/eric1221bday/sandbox/quadcopter/src/sitl_gazebo/src/gazebo_wind_plugin.cpp:82:39: error: use of undeclared identifier 'wind_msgs'
  wind_pub_ = node_handle_->Advertise<wind_msgs::msgs::Wind>(wind_pub_topic_, 1);
                                      ^
/Users/eric1221bday/sandbox/quadcopter/src/sitl_gazebo/src/gazebo_wind_plugin.cpp:82:61: error: expected unqualified-id
  wind_pub_ = node_handle_->Advertise<wind_msgs::msgs::Wind>(wind_pub_topic_, 1);
                                                            ^
/Users/eric1221bday/sandbox/quadcopter/src/sitl_gazebo/src/gazebo_wind_plugin.cpp:105:3: error: use of undeclared identifier 'wind_msgs'
  wind_msgs::msgs::Wind wind_msg;

Some digging has revealed that because gazebo 8 added a simple Wind class that is different from the currently generated wind class within site_gazebo, there has been a namespace collision resulting in the current #include "Wind.pb.h" mistakening the site_gazebo wind header for the gazebo 8 one.

I've opened this issue for preliminary discussion as to how we might resolve this namespace collision.

Need Octocopter_X Model

Hey,

i want to create a DJI S1000 model. I have created it but it doesnt fly like expected. Is there any sample model working as octocopter? I can provide the ROS package if needed.

Best regards

gazebo_mavlink_interface.cpp: error

/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp: In member function ‘void gazebo::GazeboMavlinkInterface::IRLockCallback(gazebo::IRLockPtr&)’:
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:761:14: error: ‘mavlink_landing_target_t’ has no member named ‘position_valid’
sensor_msg.position_valid = false;
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:762:14: error: ‘mavlink_landing_target_t’ has no member named ‘type’
sensor_msg.type = LANDING_TARGET_TYPE_LIGHT_BEACON;
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:762:21: error: ‘LANDING_TARGET_TYPE_LIGHT_BEACON’ was not declared in this scope
sensor_msg.type = LANDING_TARGET_TYPE_LIGHT_BEACON;
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp: In member function ‘void gazebo::GazeboMavlinkInterface::handle_message(mavlink_message_t*)’:
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:839:8: error: ‘MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS’ was not declared in this scope
case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:840:5: error: ‘mavlink_hil_actuator_controls_t’ was not declared in this scope
mavlink_hil_actuator_controls_t controls;
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:840:37: error: expected ‘;’ before ‘controls’
mavlink_hil_actuator_controls_t controls;
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:841:52: error: ‘controls’ was not declared in this scope
mavlink_msg_hil_actuator_controls_decode(msg, &controls);
^
/home/lyl/PX4/src/Firmware/Tools/sitl_gazebo/src/gazebo_mavlink_interface.cpp:841:60: error: ‘mavlink_msg_hil_actuator_controls_decode’ was not declared in this scope
mavlink_msg_hil_actuator_controls_decode(msg, &controls);

Motors won't arm

Recently changes somewhere after 2ae688 prevent motors from spinning on my matrice 100 model, haven't checked other configs yet.

Can not connect to Intel AERO FC in HITL mode via UDP

Hi all. Currently I am trying to use Gazebo to simulate Intel Aero FC in HITL mode. But without success. (I have been successful in connecting jMavSim after modifications. PX4/jMAVSim#74 ).

Intel AERO RTF is using UDP connection and mavlink-router trough it's USB port on Aero Board.But after looking on

if (serial_enabled_) {
// gcs link
myaddr.sin_addr.s_addr = mavlink_addr;
myaddr.sin_port = htons(mavlink_udp_port);
srcaddr.sin_addr.s_addr = qgc_addr;
srcaddr.sin_port = htons(qgc_udp_port);
}

else {
_myaddr.sin_addr.s_addr = htonl(INADDR_ANY);
// Let the OS pick the port
_myaddr.sin_port = htons(0);
srcaddr.sin_addr.s_addr = mavlink_addr;
srcaddr.sin_port = htons(mavlink_udp_port);
}

in https://github.com/PX4/sitl_gazebo/blob/master/src/gazebo_mavlink_interface.cpp

Problem is, that I need to connect gazebo plugin to exact remote ip address of AeroFC(192.168.7.2) and port of mavlink router (which is always different, you can see all configs from issue link above)

I think that according code above I can use only serial port and serial port will be too slow.Any suggestions please?

Error is occurred when 'make' started #help

I download and install following instruction of README.md

But, at final, when I command "make" there was error as follows

make[2]: *** No rule to make target '../msgs/PROTOBUF_PROTOC_EXECUTABLE-NOTFOUND', needed by 'msgs/MotorSpeed.pb.cc'. Stop.
CMakeFiles/Makefile2:450: recipe for target 'msgs/CMakeFiles/mav_msgs.dir/all' failed
make[1]: *** [msgs/CMakeFiles/mav_msgs.dir/all] Error 2
Makefile:83: recipe for target 'all' failed
make: *** [all] Error 2

After I got this error, I double check procedure and paths of configuration. But I couldn't find and fix it.

Please give me comments, Thank

FindOpenCV.cmake error

Anyone knows what is missing in my setup ?
Build Gazebo Plugins (all operating systems)

CMake Error at CMakeLists.txt:7 (find_package):
By not providing "FindOpenCV.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "OpenCV", but
CMake did not find one.

Could not find a package configuration file provided by "OpenCV" with any
of the following names:

OpenCVConfig.cmake
opencv-config.cmake

Add the installation prefix of "OpenCV" to CMAKE_PREFIX_PATH or set
"OpenCV_DIR" to a directory containing one of the above files. If "OpenCV"
provides a separate development package or SDK, be sure it has been
installed.

-- Configuring incomplete, errors occurred!

[root@localhost Build]# yum install opencv
Loaded plugins: fastestmirror, langpacks
Loading mirror speeds from cached hostfile

  • base: mirror.vodien.com
  • epel: ftp.kddilabs.jp
  • extras: mirror.vodien.com
  • updates: mirror.vodien.com
    Package opencv-2.4.5-3.el7.x86_64 already installed and latest version
    Nothing to do
    [root@localhost Build]#

Fail to start PX4

Hi guys, I've got a problem when trying SITL.
When I input no_sim=1 make posix_sitl_default gazebo,
I was expecting something like this:
image
while it didn't start normally, instead output:

[2/6] Performing configure step for "sitl_gazebo"
-- Boost version: 1.54.0
-- Found the following Boost libraries:
-- thread
-- signals
-- system
-- filesystem
-- program_options
-- regex
-- iostreams
-- date_time
-- chrono
-- atomic
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "2.5.0")
-- Boost version: 1.54.0
-- Looking for OGRE...
-- Found Ogre Byatis (1.8.1)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
CMake Warning (dev) at /usr/local/share/cmake-3.10/Modules/FindBoost.cmake:1545 (if):
Policy CMP0054 is not set: Only interpret if() arguments as variables or
keywords when unquoted. Run "cmake --help-policy CMP0054" for policy
details. Use the cmake_policy command to set the policy and suppress this
warning.
Quoted variables like "thread" will no longer be dereferenced when the
policy is set to NEW. Since the policy is not set the OLD behavior will be
used.
Call Stack (most recent call first):
CMakeLists.txt:29 (FIND_PACKAGE)
This warning is for project developers. Use -Wno-dev to suppress it.
CMake Warning (dev) at /usr/local/share/cmake-3.10/Modules/FindBoost.cmake:1637 (if):
Policy CMP0054 is not set: Only interpret if() arguments as variables or
keywords when unquoted. Run "cmake --help-policy CMP0054" for policy
details. Use the cmake_policy command to set the policy and suppress this
warning.
Quoted variables like "thread" will no longer be dereferenced when the
policy is set to NEW. Since the policy is not set the OLD behavior will be
used.
Call Stack (most recent call first):
CMakeLists.txt:29 (FIND_PACKAGE)
This warning is for project developers. Use -Wno-dev to suppress it.
CMake Warning (dev) at /usr/local/share/cmake-3.10/Modules/FindBoost.cmake:1688 (if):
Policy CMP0054 is not set: Only interpret if() arguments as variables or
keywords when unquoted. Run "cmake --help-policy CMP0054" for policy
details. Use the cmake_policy command to set the policy and suppress this
warning.
Quoted variables like "thread" will no longer be dereferenced when the
policy is set to NEW. Since the policy is not set the OLD behavior will be
used.
Call Stack (most recent call first):
CMakeLists.txt:29 (FIND_PACKAGE)
This warning is for project developers. Use -Wno-dev to suppress it.
-- Boost version: 1.54.0
-- Found the following Boost libraries:
-- system
-- thread
-- chrono
-- date_time
-- atomic
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread;-lpthread (found version "2.5.0")
-- Configuring done
-- Generating done
-- Build files have been written to: /home/ros17/src/Firmware/build/posix_sitl_default/build_gazebo
[3/6] Performing build step for 'sitl_gazebo'
ninja: no work to do.
[6/6] cd /home/ros17/src/Firmware/build/p...s17/src/Firmware/build/posix_sitl_default

It puzzled me because it reports no error, the process seems been held up for some reason.

Plus:
Gazebo7 works fine.
Firmware is the latest.
make posix_sitl_defaultreports no error.

Is there anything I can do ?

multiple autopilots in one SITL gazebo

.i want to run multiple autopilots in one SITL gazebo.i know different physical objects in Gazebo must have different names.i don't know how to add another autopilots on one SITL gazebo.
i use Px4 firmware.

GStreamer Camera Plugin - Corrupted Stream

I want to use the gst camera plugin with the Typhoon H480 model.
For some reason I get a corrupted H.264 stream that crashes most decoders I tried. I get however a few correct frames. If I change the pipline in the source code to the testSrc everything works as expected. So it seems there is no problem with the encoder pipeline but somehow wrong data comes from the dataSrc.

Does anyone currently use this plugin successfully or experienced similar issues?

Gazebo installation failed

Hi all,
I know it's not Px4's problem, but I really want get your help
I install it under the guidance of this http://gazebosim.org/tutorials page.
When I run this command, "sudo apt-get install gazebo7", the error is as follows:

Reading package lists... Done
Building dependency tree
Reading state information... Done
You might want to run 'apt-get -f install' to correct these:
The following packages have unmet dependencies:
gazebo7 : Depends: libboost-program-options1.58.0 but it is not going to be installed
Depends: libboost-regex1.58.0 but it is not going to be installed
Depends: libboost-thread1.58.0 but it is not going to be installed
Depends: libgazebo7 (= 7.8.1-1xenial) but it is not going to be installed
Depends: libsdformat4 but it is not going to be installed
Depends: gazebo7-common (= 7.8.1-1
xenial) but it is not going to be installed
Recommends: gazebo7-plugin-base
linux-image-extra-4.10.0-35-generic : Depends: linux-image-4.10.0-35-generic but it is not going to be installed
linux-image-extra-4.10.0-37-generic : Depends: linux-image-4.10.0-37-generic but it is not going to be installed
linux-image-generic-hwe-16.04 : Depends: linux-image-4.10.0-37-generic but it is not going to be installed
linux-signed-image-4.10.0-35-generic : Depends: linux-image-4.10.0-35-generic (= 4.10.0-35.3916.04.1) but it is not going to be installed
linux-signed-image-4.10.0-37-generic : Depends: linux-image-4.10.0-37-generic (= 4.10.0-37.41
16.04.1) but it is not going to be installed
E: Unmet dependencies. Try 'apt-get -f install' with no packages (or specify a solution).

Then I enter this command "sudo apt-get -f install", and the error is as follows:

dpkg: error processing archive /var/cache/apt/archives/linux-image-4.10.0-37-generic_4.10.0-37.4116.04.1_amd64.deb (--unpack):
cannot copy extracted data for './boot/vmlinuz-4.10.0-37-generic' to '/boot/vmlinuz-4.10.0-37-generic.dpkg-new': failed to write (No space left on device)
No apport report written because the error message indicates a disk full error
dpkg-deb: error: subprocess paste was killed by signal (Broken pipe)
Examining /etc/kernel/postrm.d .
run-parts: executing /etc/kernel/postrm.d/initramfs-tools 4.10.0-37-generic /boot/vmlinuz-4.10.0-37-generic
run-parts: executing /etc/kernel/postrm.d/zz-update-grub 4.10.0-37-generic /boot/vmlinuz-4.10.0-37-generic
Preparing to unpack .../linux-image-4.10.0-35-generic_4.10.0-35.39
16.04.1_amd64.deb ...
Done.
Unpacking linux-image-4.10.0-35-generic (4.10.0-35.3916.04.1) ...
dpkg: error processing archive /var/cache/apt/archives/linux-image-4.10.0-35-generic_4.10.0-35.39
16.04.1_amd64.deb (--unpack):
cannot copy extracted data for './boot/abi-4.10.0-35-generic' to '/boot/abi-4.10.0-35-generic.dpkg-new': failed to write (No space left on device)
No apport report written because the error message indicates a disk full error
dpkg-deb: error: subprocess paste was killed by signal (Broken pipe)
Examining /etc/kernel/postrm.d .
run-parts: executing /etc/kernel/postrm.d/initramfs-tools 4.10.0-35-generic /boot/vmlinuz-4.10.0-35-generic
run-parts: executing /etc/kernel/postrm.d/zz-update-grub 4.10.0-35-generic /boot/vmlinuz-4.10.0-35-generic
Errors were encountered while processing:
/var/cache/apt/archives/linux-image-4.10.0-37-generic_4.10.0-37.4116.04.1_amd64.deb
/var/cache/apt/archives/linux-image-4.10.0-35-generic_4.10.0-35.39
16.04.1_amd64.deb
E: Sub-process /usr/bin/dpkg returned an error code (1)

Can someone help me? Thank you

libgazebo_ros_camera Problem

@LorenzMeier sitl_gazebo has problem with run libgazebo_ros_camera, I followed the (ros_interface) for install and run gazebo simulation. Everything works fine, but after adding the camera, the following error occurs:

roslaunch px4 mavros_posix_sitl.launch
gzserver: /build/ogre-1.9-mqY1wq/ogre-1.9-1.9.0+dfsg1/OgreMain/src/OgreRenderSystem.cpp:546: virtual void Ogre::RenderSystem::setDepthBufferFor(Ogre::RenderTarget*): AssertionbAttached && "A new DepthBuffer for a RenderTarget was created, but after creation" "it says it's incompatible with that RT"' failed.
Aborted
[gazebo-3] process has died [pid 20750, exit code 134, cmd /opt/ros/kinetic/lib/gazebo_ros/gzserver -e ode /home/cv/src/Firmware/Tools/sitl_gazebo/worlds/empty.world __name:=gazebo __log:=/home/cv/.ros/log/68ef15b6-1e60-11e8-b0c8-000c29ddf392/gazebo-3.log].
log file: /home/cv/.ros/log/68ef15b6-1e60-11e8-b0c8-000c29ddf392/gazebo-3*.log
`

this code added to iris.sdf:
<joint name='DownCam_joint' type='fixed'> <child>camera_link</child> <parent>base_link</parent> </joint> <link name='camera_link'> <pose frame=''>0.1 0 0.194923 0 0 0</pose> <inertial> <pose frame=''>0 0 0 0 0 0</pose> <mass>1e-05</mass> <inertia> <ixx>0.0001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.0002</iyy> <iyz>0</iyz> <izz>0.0002</izz> </inertia> </inertial> <visual name='visual'> <geometry> <box> <size>0.005 0.005 0.005</size> </box> </geometry> </visual> <sensor name='FrontCam' type='camera'> <update_rate>30</update_rate> <camera name='head'> <horizontal_fov>1.39626</horizontal_fov> <image> <width>720</width> <height>480</height> <format>R8G8B8</format> </image> <clip> <near>0.02</near> <far>300</far> </clip> <noise> <type>gaussian</type> <mean>0</mean> <stddev>0.007</stddev> </noise> </camera> <plugin name='camera_controller' filename='libgazebo_ros_camera.so'> <alwaysOn>true</alwaysOn> <updateRate>0.0</updateRate> <cameraName>birrobotic/FrontCam</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName> <frameName>camera_link</frameName> <hackBaseline>0.07</hackBaseline> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> </plugin> </sensor> <self_collide>0</self_collide> <enable_wind>0</enable_wind> <kinematic>0</kinematic> </link>

The same problem has already been addressed and debugged in another platform (osrf)

plane motor issue

Something strange happens to the plane model in auto landing at flare. The throttle cuts (in the px4 logs), but the vehicle starts climbing and gets stuck in a flyaway.

gazebo

The only thing noteworthy I saw in the console is this message.

[Wrn] [Publisher.cc:141] Queue limit reached for topic /gazebo/default/plane/gazebo/command/motor_speed, deleting message. This warning is printed only once.

http://logs.uaventure.com/view/xaJwxSYbc7jXBN2Xa7Yuii

how to starting Gazebo and PX4 separately

when i echo the code make posix_sitl_default gazebo,the virtual world and the default PX4 show together
i'm wondering how to starting Gazebo and PX4 separately,and modify the virtual world.
the code make posix_sitl_default gazebo_none_idein PX4 Developer Guide doesn't work

Following model

Is there a way to center the vehicle when using the following mode? Currently the camera view is behind the vehicle during that mode

build fail with gazebo_iris_opt_flow as target

I am using a slightly modified docker version of the px4io/px4-dev-ros:v1.0. The modification is just in terms of Nvidia driver installation. The docker was working fine a couple of weeks ago. Today when I cloned the Firmware repo again and tried to compile with make posix_sitl_default, it compiles fine but with gazebo as a target it gives error..

e.g. the command make posix gazebo_iris_opt_flow gives the following errors:

/home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp: In member function 'virtual void gazebo::IRLockPlugin::Load(gazebo::sensors::SensorPtr, sdf::ElementPtr)': /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:53:81: error: no matching function for call to 'dynamic_pointer_cast(gazebo::sensors::SensorPtr&)' this->camera = std::dynamic_pointer_cast<sensors::LogicalCameraSensor>(_sensor); ^ /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:53:81: note: candidates are: In file included from /usr/include/c++/4.8/bits/shared_ptr.h:52:0, from /usr/include/c++/4.8/memory:82, from /usr/include/boost/smart_ptr/weak_ptr.hpp:16, from /usr/include/boost/smart_ptr/enable_shared_from_this.hpp:16, from /usr/include/boost/enable_shared_from_this.hpp:16, from /usr/include/gazebo-6.6/gazebo/sensors/Sensor.hh:20, from /usr/include/gazebo-6.6/gazebo/sensors/DepthCameraSensor.hh:22, from /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:23: /usr/include/c++/4.8/bits/shared_ptr_base.h:1177:5: note: template<class _Tp, class _Tp1, __gnu_cxx::_Lock_policy _Lp> std::__shared_ptr<_Tp1, _Lp> std::dynamic_pointer_cast(const std::__shared_ptr<_Tp2, _Lp>&) dynamic_pointer_cast(const __shared_ptr<_Tp1, _Lp>& __r) noexcept ^ /usr/include/c++/4.8/bits/shared_ptr_base.h:1177:5: note: template argument deduction/substitution failed: /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:53:81: note: 'gazebo::sensors::SensorPtr {aka boost::shared_ptr<gazebo::sensors::Sensor>}' is not derived from 'const std::__shared_ptr<_Tp2, _Lp>' this->camera = std::dynamic_pointer_cast<sensors::LogicalCameraSensor>(_sensor); ^ In file included from /usr/include/c++/4.8/memory:82:0, from /usr/include/boost/smart_ptr/weak_ptr.hpp:16, from /usr/include/boost/smart_ptr/enable_shared_from_this.hpp:16, from /usr/include/boost/enable_shared_from_this.hpp:16, from /usr/include/gazebo-6.6/gazebo/sensors/Sensor.hh:20, from /usr/include/gazebo-6.6/gazebo/sensors/DepthCameraSensor.hh:22, from /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:23: /usr/include/c++/4.8/bits/shared_ptr.h:447:5: note: template<class _Tp, class _Tp1> std::shared_ptr<_Tp1> std::dynamic_pointer_cast(const std::shared_ptr<_Tp2>&) dynamic_pointer_cast(const shared_ptr<_Tp1>& __r) noexcept ^ /usr/include/c++/4.8/bits/shared_ptr.h:447:5: note: template argument deduction/substitution failed: /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:53:81: note: 'gazebo::sensors::SensorPtr {aka boost::shared_ptr<gazebo::sensors::Sensor>}' is not derived from 'const std::shared_ptr<_Tp2>' this->camera = std::dynamic_pointer_cast<sensors::LogicalCameraSensor>(_sensor); ^ /home/root/src/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:68:38: error: 'class gazebo::sensors::Sensor' has no member named 'ParentName' const string scopedName = _sensor->ParentName();

Could anyone point me in the right direction please. :)

Only change is regarding the host for the docker, I recently upgraded from Ubuntu 14.04 to 16.04 but I don't think that should make any difference.

Regards,

ykhedar

How to put two PX4 drones in Gazebo?

Hello guys,
I have went through some tutorials to run a Gazebo simulation with a drone in it.
However, what I need is to have two drones in one Gazebo simulation and use two ROS to control it. In the control part I am going to use MATLAB Robotics System Toolbox to communicate with the two drones.
Anybody has some ideas on how to finish that two drone simulation?
Thanks,
@cnpcshangbo

Gazebo topics not getting published when running any SITL simulation

I have the latest master clones. When I run the basic IRIS SITL using:

make posix_sitl_default gazebo

After the model loads and PX4 shell opens, I did:

gz topic -l

I get the following
screenshot from 2017-05-25 13 20 35

I just cannot echo any iris related topics using:

gz topic -e /gazebo/default/iris/$NAME

It returns nothing. I'm developing a Tiltrotor Tricopter model for SITL. I need to view what's going into the motor_speed topics to debug my code.

I keep getting these warnings but I think this shouldn't cause the topics to not publish anything.
screenshot from 2017-05-25 13 43 03

How can I append `libgazebo_ros_laser` in iris with gazebo and ros?

I try to append a laser scan in iris like this: [1], [2]
This laser scan is included in ros-kinetic-gazebo-plugins named libgazebo_ros_laser.so which is a ros official package / plugin.

But something strange happened [3]!!
(1): When I drag iris model with the mouse, iris could move to another place with lidar;
(2): But when I send a mavlink command to iris, iris is moving but lidar still stay in previous position.

I think that because I need aonther plugin to replace libgazebo_ros_laser.so, is there any example code or tutorial?

I'm really a fresh man in gazebo and px4, so I need some help.
Anyhelp would be highly appreciated.

Sincerely

[1] : iris.sdf

<sdf version='1.5'>
  <model name='iris_lidar'>

    <include>
      <uri>model://iris</uri>
    </include>

    <include>
      <uri>model://my_lidar</uri>
      <pose>0 0 0.1 0 0 0</pose>
    </include>
    <joint name="lidar_joint" type="fixed">
      <child>my_lidar::link</child>
      <parent>iris::base_link</parent>
    </joint>

  </model>
</sdf>

[2] : my_lidar.sdf

<sdf version="1.4">
  <model name="my_laser">
    <pose>0 0 0.035 0 0 0</pose>
    <link name="link">
      <inertial>
        <mass>0.1</mass>
      </inertial>
      <collision name="collision-base">
        <pose>0 0 -0.0145 0 0 0</pose>
        <geometry>
          <box>
            <size>0.05 0.05 0.041</size>
          </box>
        </geometry>
      </collision>
      <collision name="collision-top">
        <pose>0 0 0.0205 0 0 0</pose>
        <geometry>
          <cylinder>
            <radius>0.021</radius>
            <length>0.029</length>
          </cylinder>
        </geometry>
      </collision>
      <sensor name="laser" type="ray">
        <pose>0.01 0 0.0175 0 -0 0</pose>
        <ray>
          <scan>
            <horizontal>
              <samples>640</samples>
              <resolution>1</resolution>
              <min_angle>-3.1415926</min_angle>
              <max_angle>3.1415926</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.1</min>
            <max>6</max>
            <resolution>0.01</resolution>
          </range>
        </ray>
	<plugin name="laser" filename="libgazebo_ros_laser.so">
	  <topicName>/scan</topicName>
	  <frameName>laser</frameName> 
	  <alwaysOn>true</alwaysOn>
	  <updateRate>10.0</updateRate>
	</plugin>
        <always_on>1</always_on>
        <update_rate>10</update_rate>
        <visualize>true</visualize>
      </sensor>
    </link>
  </model>
</sdf>

[3]
img

Questions about implementing a new copter configuration

I'm planning on implementing a new copter configuration for the sitl_gazebo plugin, I have a few questions about some of the plugin variables:

How are the motorConstant and motorMoment variables calculated? (in the SDF):
https://github.com/PX4/sitl_gazebo/blob/d6c12fb9e68608db2ad56f4ec6c74e5a491e17ee/src/gazebo_motor_model.cpp#L186

Similarly curious about rotorDragCoefficient, and rollingMomentCoefficient. Are these parameters following a paper? Also, curious what unit maxRotVelocity is in.

Rotors stop moving when attached to another moving frame

Hi,
I am simulating a VTOL tiltrotor. I used the standard_vtol as a template to get started. I have attached a link called shaft to the base_link. The shaft link is getting control from channel 4 for tilt servo. Front rotors are attached to the shaft. Now when I use this setup the rotors stop rotating. Notably, when the control on shaft is removed the rotors start spinning.
Any suggestions on how to get both of them working?

Unstability due to addition of camera

Hi, I am trying to add a camera on iris model to publish images on ROS. I am getting the image topic correctly but after adding the camera, the iris model has become very unstable.

ezgif com-gif-maker

I think the added weight is giving an extra moment which is causing the oscillations, and in an attempt to stabilize the drone, the controller is overshooting. Can anyone suggest what would be a possible solution, should I change the PID values, or put the camera in the exact center?

Interference in /.ros/rootfs

simulation in sitl_gazebo:
roslaunch px4 mavros_posix_sitl.launch
QGC connect to sitl_gazebo vehicle, Everything is ok.
Works correctly, then (close and open new terminal) and try
roslaunch px4 multi_uav_mavros_sitl.launch
QGC connect to sitl_gazebo vehicle's, Everything is ok.
Works correctly, Then (close and open new terminal) try again
roslaunch px4 mavros_posix_sitl.launch
QGC waiting for vehicle connection ...

roslaunch px4 mavros_posix_sitl.launch
... logging to /home/ahrovan/.ros/log/f2110c6a-55af-11e8-a327-000c298cb19f/roslaunch-ahrovan-12181.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://ahrovan:41285/

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_rate: 1.0
 * /mavros/conn/system_time_rate: 1.0
 * /mavros/conn/timeout: 10.0
 * /mavros/conn/timesync_rate: 10.0
 * /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
 * /mavros/distance_sensor/hrlv_ez4_pub/id: 0
 * /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
 * /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/laser_1_sub/id: 3
 * /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/laser_1_sub/subscriber: True
 * /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
 * /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
 * /mavros/distance_sensor/lidarlite_pub/id: 1
 * /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
 * /mavros/distance_sensor/lidarlite_pub/send_tf: True
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/sonar_1_sub/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 408.0
 * /mavros/fake_gps/geo_origin/lat: 47.3667
 * /mavros/fake_gps/geo_origin/lon: 8.55
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: True
 * /mavros/fake_gps/satellites_visible: 5
 * /mavros/fake_gps/tf/child_frame_id: fix
 * /mavros/fake_gps/tf/frame_id: map
 * /mavros/fake_gps/tf/listen: False
 * /mavros/fake_gps/tf/rate_limit: 10.0
 * /mavros/fake_gps/tf/send: False
 * /mavros/fake_gps/use_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: udp://:14540@loca...
 * /mavros/gcs_url: 
 * /mavros/global_position/child_frame_id: base_link
 * /mavros/global_position/frame_id: map
 * /mavros/global_position/rot_covariance: 99999.0
 * /mavros/global_position/tf/child_frame_id: base_link
 * /mavros/global_position/tf/frame_id: map
 * /mavros/global_position/tf/global_frame_id: earth
 * /mavros/global_position/tf/send: False
 * /mavros/global_position/use_relative_alt: True
 * /mavros/image/frame_id: px4flow
 * /mavros/imu/angular_velocity_stdev: 0.000349065850399
 * /mavros/imu/frame_id: base_link
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/local_position/frame_id: map
 * /mavros/local_position/tf/child_frame_id: base_link
 * /mavros/local_position/tf/frame_id: map
 * /mavros/local_position/tf/send: False
 * /mavros/local_position/tf/send_fcu: False
 * /mavros/mission/pull_after_gcs: True
 * /mavros/mocap/use_pose: True
 * /mavros/mocap/use_tf: False
 * /mavros/odometry/estimator_type: 3
 * /mavros/odometry/frame_tf/desired_frame: ned
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682389136
 * /mavros/px4flow/ranger_max_range: 5.0
 * /mavros/px4flow/ranger_min_range: 0.3
 * /mavros/safety_area/p1/x: 1.0
 * /mavros/safety_area/p1/y: 1.0
 * /mavros/safety_area/p1/z: 1.0
 * /mavros/safety_area/p2/x: -1.0
 * /mavros/safety_area/p2/y: -1.0
 * /mavros/safety_area/p2/z: -1.0
 * /mavros/setpoint_accel/send_force: False
 * /mavros/setpoint_attitude/reverse_thrust: False
 * /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
 * /mavros/setpoint_attitude/tf/frame_id: map
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 50.0
 * /mavros/setpoint_attitude/use_quaternion: False
 * /mavros/setpoint_position/mav_frame: LOCAL_NED
 * /mavros/setpoint_position/tf/child_frame_id: target_position
 * /mavros/setpoint_position/tf/frame_id: map
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/setpoint_velocity/mav_frame: LOCAL_NED
 * /mavros/startup_px4_usb_quirk: True
 * /mavros/sys/disable_diag: False
 * /mavros/sys/min_voltage: 10.0
 * /mavros/target_component_id: 1
 * /mavros/target_system_id: 1
 * /mavros/tdr_radio/low_rssi: 40
 * /mavros/time/time_ref_source: fcu
 * /mavros/time/timesync_avg_alpha: 0.6
 * /mavros/time/timesync_mode: MAVLINK
 * /mavros/vibration/frame_id: base_link
 * /mavros/vision_pose/tf/child_frame_id: vision_estimate
 * /mavros/vision_pose/tf/frame_id: map
 * /mavros/vision_pose/tf/listen: False
 * /mavros/vision_pose/tf/rate_limit: 10.0
 * /mavros/vision_speed/listen_twist: False
 * /rosdistro: kinetic
 * /rosversion: 1.12.13
 * /use_sim_time: True

NODES
  /
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    mavros (mavros/mavros_node)
    sitl (px4/px4)
    vehicle_spawn_ahrovan_12181_3129263265252446471 (gazebo_ros/spawn_model)

auto-starting new master
process[master]: started with pid [12191]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to f2110c6a-55af-11e8-a327-000c298cb19f
process[rosout-1]: started with pid [12204]
started core service [/rosout]
process[sitl-2]: started with pid [12229]
node name: sitl
data path: /home/ahrovan/src/Firmware
commands file: /home/ahrovan/src/Firmware/posix-configs/SITL/init/ekf2/iris
57 WARNING: setRealtimeSched failed (not run as root?)

______  __   __    ___ 
| ___ \ \ \ / /   /   |
| |_/ /  \ V /   / /| |
|  __/   /   \  / /_| |
| |     / /^\ \ \___  |
\_|     \/   \/     |_/

px4 starting.

process[gazebo-3]: started with pid [12237]
process[gazebo_gui-4]: started with pid [12242]
process[vehicle_spawn_ahrovan_12181_3129263265252446471-5]: started with pid [12247]
process[mavros-6]: started with pid [12248]
INFO  [dataman] Unknown restart, data manager file 'rootfs/fs/microsd/dataman' size is 11405132 bytes
INFO  [simulator] Waiting for initial data on UDP port 14574. Please start the flight simulator to proceed..
[ INFO] [1526107480.930085239]: FCU URL: udp://:14540@localhost:14557
[ INFO] [1526107480.931963026]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1526107480.932117363]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1526107480.932515358]: GCS bridge disabled
[ INFO] [1526107480.943249496]: Plugin 3dr_radio loaded
[ INFO] [1526107480.946415635]: Plugin 3dr_radio initialized
[ INFO] [1526107480.946582249]: Plugin actuator_control loaded
[ INFO] [1526107480.951669071]: Plugin actuator_control initialized
[ INFO] [1526107480.953945816]: Plugin adsb loaded
[ INFO] [1526107480.959253190]: Plugin adsb initialized
[ INFO] [1526107480.959469326]: Plugin altitude loaded
[ INFO] [1526107480.961399673]: Plugin altitude initialized
[ INFO] [1526107480.961541417]: Plugin cam_imu_sync loaded
[ INFO] [1526107480.962394597]: Plugin cam_imu_sync initialized
[ INFO] [1526107480.962635885]: Plugin command loaded
[ INFO] [1526107480.972912160]: Plugin command initialized
[ INFO] [1526107480.973080297]: Plugin debug_value loaded
[ INFO] [1526107480.980519701]: Plugin debug_value initialized
[ INFO] [1526107480.980583028]: Plugin distance_sensor blacklisted
[ INFO] [1526107480.980846787]: Plugin fake_gps loaded
[ INFO] [1526107481.005027694]: Plugin fake_gps initialized
[ INFO] [1526107481.005281012]: Plugin ftp loaded
[ INFO] [1526107481.016980835]: Plugin ftp initialized
[ INFO] [1526107481.017166492]: Plugin global_position loaded
[ INFO] [1526107481.043312639]: Plugin global_position initialized
[ INFO] [1526107481.043517714]: Plugin hil loaded
[ INFO] [1526107481.067909597]: Plugin hil initialized
[ INFO] [1526107481.068160444]: Plugin home_position loaded
[ INFO] [1526107481.073328197]: Plugin home_position initialized
[ INFO] [1526107481.073488136]: Plugin imu loaded
[ INFO] [1526107481.081993959]: Plugin imu initialized
[ INFO] [1526107481.082171999]: Plugin local_position loaded
[ INFO] [1526107481.089709455]: Plugin local_position initialized
[ INFO] [1526107481.089897499]: Plugin manual_control loaded
[ INFO] [1526107481.094289375]: Plugin manual_control initialized
[ INFO] [1526107481.094452727]: Plugin mocap_pose_estimate loaded
[ INFO] [1526107481.102714622]: Plugin mocap_pose_estimate initialized
[ INFO] [1526107481.102906526]: Plugin obstacle_distance loaded
[ INFO] [1526107481.106460409]: Plugin obstacle_distance initialized
[ INFO] [1526107481.106636000]: Plugin odom loaded
[ INFO] [1526107481.111949507]: Plugin odom initialized
[ INFO] [1526107481.112273686]: Plugin param loaded
[ INFO] [1526107481.116797967]: Plugin param initialized
[ INFO] [1526107481.117083329]: Plugin px4flow loaded
[ INFO] [1526107481.124784897]: Plugin px4flow initialized
[ INFO] [1526107481.124882877]: Plugin rangefinder blacklisted
[ INFO] [1526107481.125227634]: Plugin rc_io loaded
[ INFO] [1526107481.132719734]: Plugin rc_io initialized
[ INFO] [1526107481.132799668]: Plugin safety_area blacklisted
[ INFO] [1526107481.133054539]: Plugin setpoint_accel loaded
[ INFO] [1526107481.138685703]: Plugin setpoint_accel initialized
[ INFO] [1526107481.139006052]: Plugin setpoint_attitude loaded
[ INFO] [1526107481.153734278]: Plugin setpoint_attitude initialized
[ INFO] [1526107481.154088051]: Plugin setpoint_position loaded
[ INFO] [1526107481.175447857]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1526107481.176722339]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1526107481.189286046]: Plugin setpoint_position initialized
[ INFO] [1526107481.189519824]: Plugin setpoint_raw loaded
[ INFO] [1526107481.202875184]: Plugin setpoint_raw initialized
[ INFO] [1526107481.203109817]: Plugin setpoint_velocity loaded
[ INFO] [1526107481.211249135]: Plugin setpoint_velocity initialized
[ INFO] [1526107481.211534861]: Plugin sys_status loaded
[ INFO] [1526107481.219863591]: Plugin sys_status initialized
[ INFO] [1526107481.220113056]: Plugin sys_time loaded
[ INFO] [1526107481.224237240]: TM: Timesync mode: MAVLINK
[ INFO] [1526107481.225080615]: Plugin sys_time initialized
[ INFO] [1526107481.225253867]: Plugin vfr_hud loaded
[ INFO] [1526107481.226694497]: Plugin vfr_hud initialized
[ INFO] [1526107481.226743246]: Plugin vibration blacklisted
[ INFO] [1526107481.226871488]: Plugin vision_pose_estimate loaded
[ INFO] [1526107481.243332451]: Plugin vision_pose_estimate initialized
[ INFO] [1526107481.243621976]: Plugin vision_speed_estimate loaded
[ INFO] [1526107481.249078369]: Plugin vision_speed_estimate initialized
[ INFO] [1526107481.249329295]: Plugin waypoint loaded
[ INFO] [1526107481.256266640]: Plugin waypoint initialized
[ INFO] [1526107481.256348985]: Autostarting mavlink via USB on PX4
[ INFO] [1526107481.256596607]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1526107481.256629384]: Built-in MAVLink package version: 2018.2.2
[ INFO] [1526107481.256677748]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1526107481.256697184]: MAVROS started. MY ID 1.240, TARGET ID 1.1
SpawnModel script started
[INFO] [1526107481.461607, 0.000000]: Loading model XML from file
[INFO] [1526107481.461900, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
[ INFO] [1526107481.563165883, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1526107481.601273346, 0.056000000]: Physics dynamic reconfigure ready.
[INFO] [1526107481.764731, 0.204000]: Calling service /gazebo/spawn_sdf_model
[INFO] [1526107481.942997, 0.328000]: Spawn status: SpawnModel: Successfully spawned entity
Unhandled exception in thread started by 
sys.excepthook is missing
lost sys.stderr
[ INFO] [1526107482.123325896, 0.328000000]: Camera Plugin: Using the 'robotNamespace' param: '/'
[ INFO] [1526107482.127084937, 0.328000000]: Camera Plugin (ns = /)  <tf_prefix_>, set to ""
[vehicle_spawn_ahrovan_12181_3129263265252446471-5] process has finished cleanly
log file: /home/ahrovan/.ros/log/f2110c6a-55af-11e8-a327-000c298cb19f/vehicle_spawn_ahrovan_12181_3129263265252446471-5*.log

delete folder /.ros/rootfs, and try again
roslaunch px4 mavros_posix_sitl.launch
`
QGC connect to sitl_gazebo vehicle, Everything is ok.

What is the problem and does not each vehicle have a separate parameter folder for itself?

Tf tree mismatch between sdf and rqt_tf_tree

Hi!
I'm setting up the simulation for a uav equipped with a laser sensor. I'm experimenting with roslaunch px4 posix_sitl.launch vehicle:=iris_rplidar est:=lpe
So far the configuration steps included below allow me to launch gazebo showing both UAV and sensor.
In rviz, if I add the Laser Scan and switch the fixed frame to local_origin, I get

Transform [sender=unknown_publisher]
For frame [rplidar_link]: Frame [rplidar_link] does not exist

rviz

Why is the tree not showing the frames in the sitl_gazebo/models/iris_rplidar/iris_rplidar.sdf?
rqt_tf_tree

Thank you in advance.
Setup steps:

  1. make posix_sitl_default gazebo
  2. Kill process
  3. source /ros_ws/devel/setup.bash
  4. source Tools/setup_gazebo.bash /Firmware /Firmware/build/posix_sitl_default
  5. export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:/Firmware
  6. export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:/Firmware/Tools/sitl_gazebo
  7. roslaunch px4 posix_sitl.launch vehicle:=iris_rplidar est:=lpe

GStreamer Camera Plugin failed to enable

First enable in CMakelists
option(BUILD_GSTREAMER_PLUGIN "enable gstreamer plugin" "OFF")
Then edit typhoon_h480.sdf:

        <plugin name="cgo3_camera_controller" filename="libgazebo_ros_camera.so">
          <alwaysOn>true</alwaysOn>
          <updateRate>0.0</updateRate>
          <cameraName>cgo3_camera</cameraName>
          <imageTopicName>image_raw</imageTopicName>
          <cameraInfoTopicName>camera_info</cameraInfoTopicName>
          <frameName>cgo3_camera_optical_frame</frameName>
          <hackBaseline>0.0</hackBaseline>
          <distortionK1>0.0</distortionK1>
          <distortionK2>0.0</distortionK2>
          <distortionK3>0.0</distortionK3>
          <distortionT1>0.0</distortionT1>
          <distortionT2>0.0</distortionT2>
        </plugin>
        -->
        <!-- GStreamer camera plugin (needs a lot of CPU! Consider lowering the
             camera image size when enabling) -->
        <plugin name="GstCameraPlugin" filename="libgazebo_gst_camera_plugin.so">
            <robotNamespace></robotNamespace>
            <udpPort>5600</udpPort>
        </plugin>
        <plugin name="GeotaggedImagesPlugin" filename="libgazebo_geotagged_images_plugin.so">
            <robotNamespace></robotNamespace>
            <interval>1</interval>
            <width>3840</width>
            <height>2160</height>
        </plugin>

but got this problem
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_ros_camera.so: libCameraPlugin.so: cannot open shared object file: No such file or directory
image

libgazebo_ros_camera.so is in /opt/ros/kinetic/lib
libCameraPlugin.so is in /usr/lib/x86_64-linux-gnu/gazebo-7/plugins

add PATH in sh
# setup Gazebo env and update package path export GAZEBO_PLUGIN_PATH=/opt/ros/kinetic/lib:${GAZEBO_PLUGIN_PATH} export GAZEBO_PLUGIN_PATH=/usr/lib/x86_64-linux-gnu/gazebo-7/plugins:${GAZEBO_PLUGIN_PATH} export GAZEBO_PLUGIN_PATH=${BUILD_DIR}/build_gazebo:${GAZEBO_PLUGIN_PATH}
set this does not help

What's the problem?

Gimbal controller buggy

The gimbal controller has some odd behaviours at different compass headings. I added an angle wrap for the error calculation, and that helped some. Also the euler angles are assumed to be 321, but I'm creating a model of the tarot t4-3d, which has angles 312, so might need to think about how best to handle that.

CI sever needs some new packages

http://sitl01.dronetest.io/job/PX4%20Firmware%20POSIX%20SITL%20PRs/3050/console

-- GIT_TAG = v1.5.0-745-gacb48de
-- Configuring incomplete, errors occurred!
See also "/job/catkin/build/CMakeFiles/CMakeOutput.log".
See also "/job/catkin/build/CMakeFiles/CMakeError.log".
CMake Error: The following variables are used in this project, but they are set to NOTFOUND.
Please set them or make sure they are set and tested correctly in the CMake files:
GSTREAMER_LIBRARIES (ADVANCED)
    linked by target "gazebo_geotagged_images_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "gazebo_gst_camera_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_gimbal_controller_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "mav_msgs" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_wind_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_imu_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_mavlink_interface" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_controller_interface" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "gazebo_opticalFlow_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_motor_model" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "LiftDragPlugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "gazebo_lidar_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo
    linked by target "rotors_gazebo_multirotor_base_plugin" in directory /job/catkin/src/mavlink_sitl_gazebo

@dagar

Failed to call the plugin function from a xacro file.

Hi,
I used to use this package with a rotorcraft model of SDF, which worked well. But when I tried to add a fixed_wing plane model of xacro formation to the sitl_gazebo package, it kept reporting errors.

A specialist one is as follows(which was reported after I inserted the mavlink_interface_macro to my xacro model description file):

when processing file: ``/home/u23/WorkSpace/03.fixedwing_sim_pix/04.Firmware/Firmware/Tools/sitl_gazebo/models/techpod/techpod_base.xacro
unknown macro name: xacro:mavlink_interface_macro
when processing file: ``/home/u23/WorkSpace/03.fixedwing_sim_pix/04.Firmware/Firmware/Tools/sitl_gazebo/models/techpod/techpod_base.xacro
while processing ``/home/u23/WorkSpace/03.fixedwing_sim_pix/04.Firmware/Firmware/launch/spawn_fixed_wing.launch:
Invalid <param> tag: Cannot load command parameter [robot_description]: command [ /opt/ros/jade/share/xacro/xacro.py ``'/home/u23/WorkSpace/03.fixedwing_sim_pix/04.Firmware/Firmware/Tools/sitl_gazebo/models/techpod/techpod_base.xacro' enable_logging:=false enable_ground_truth:=true log_file:=techpod wait_to_record_bag:=false uav_name:=techpod namespace:=techpod] returned with code [2].

Param xml is <param command=" $(find xacro)/xacro.py '$(arg model)' enable_logging:=$(arg enable_logging) enable_ground_truth:=$(arg enable_ground_truth) log_file:=$(arg log_file) wait_to_record_bag:=$(arg wait_to_record_bag) uav_name:=$(arg uav_name) namespace:=$(arg namespace)" name="robot_description"/>
The traceback for the exception was written to the log file

I checked the whole process but had no idea where I did wrong.
I wonder, is it acceptable that I provide axacrosource file for the gazebo_mavlink_interface.cpp as the value of sdf::ElementPtr _sdf?

Gazebo 9 wind

I was using sit with Gazebo 7 without any problem.
Now I need to make use of wind functionality included in Gazebo 9.
Is it possible to do so? make posix_sitl_default gazebo throws a lot of errors with Gazebo 9 installed instead of Gazebo 7.

Typhoon H480 Oscillation

As soon as I remove the legs from the Typhoon H480 sdf model, the simulation oscillates a lot more. Here's a before and after:

Legs:
out2

No Legs:
out

SDF for reference:
hexa.sdf.txt

Any idea why? I'm using the Typhoon as the base for my hexacopter, but mine doesn't have legs or a gimbal. Thank you!

Coordinate frame of imu message & hil_sensor.

Hi,
I am doing a simulation of a fixed_wing plane model. I wrote a gazebo_malvink_interface plugin referring to this package. Connections between pixhawk and gazebo using both SITL and HIL loops worked successfully, but from QGC I find the altitude information was wrong. The z axis turned to be in the opposite direction.

I am thinking that the imu message gained from imu plugin should be in ENU body frame, but in piaxhawk(with px4 Firmware) the hil_sensor should be in NED body frame.

I want to know whether I should generate the function of coordinate system transformation into my interface plugin, and in the iris SITL simulation, who is doing this transformation work?

I would be really grateful if anyone could help.

ROS bulid failure

src/mavlink_sitl_gazebo/include/gazebo_geotagged_images_plugin.h:32:41: fatal error: mavlink/v2.0/common/mavlink.h: No such file or directory

Some include path issue, tracking it down now, wish we had CI on this.

Build and Load Gazebo Plugin Library Failed with Default CMakelist.txt

1. Motivation

I tried to add a steer control plugin for the vehicle Polaris in sitl_gazebo, then we could control the Polaris and Quadrotor in Gazebo simulation environment simultaneously.

2. Some Configuration

2.1 Plugin Standalone Testing

This plugin has been tested standalone (https://github.com/weiweikong/polaris_simulation_standalone/blob/master/polaris_simple_control_plugin/src/polaris_simple_control_plugin.cpp) with ROS Kinect and Gazebo 7.

2.2 Add the plugin codes in .sdf file

 <plugin name="polaris_simple_control_plugin" filename="libpolaris_simple_control_plugin.so">
      <alwaysOn>1</alwaysOn>
      <update>100</update>
      <updateRate>100.0</updateRate>
      <robotNamespace>polaris</robotNamespace>
      <leftJoint>rear_left_wheel_joint</leftJoint>
      <rightJoint>rear_right_wheel_joint</rightJoint>
      <leftsteerJoint>front_left_steering_joint</leftsteerJoint>
      <rightsteerJoint>front_right_steering_joint</rightsteerJoint>
      <wheelDistance>1.2</wheelDistance>
      <CarLength>1.88</CarLength>
      <wheelDiameter>0.32</wheelDiameter>
      <robotBaseFrame>base_link</robotBaseFrame>      
      <driveTorque>200</driveTorque>
      <steerTorque>200</steerTorque>
      <commandTopic>cmd_vel</commandTopic>      
      <broadcastTF>1</broadcastTF>
    </plugin>

2.3. Modify the ~/Firmware/Tools/sitl_gazebo/CMakeLists.txt with

add_library(polaris_simple_control_plugin SHARED src/polaris_simple_control_plugin.cpp)
target_link_libraries(polaris_simple_control_plugin ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(polaris_simple_control_plugin mav_msgs)

2.4 Setup a new launch file, polaris_empty.launch

<launch>
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="paused" value="false"/>
    <arg name="use_sim_time" value="true"/>
    <arg name="gui" value="true"/>
    <arg name="headless" value="false"/>
    <arg name="debug" value="false"/>
  </include>px4
  <param name="robot_polaris" textfile="$(find px4)/Tools/sitl_gazebo/models/polaris/model.sdf" />
    <node
      name="spawn_model2"
      pkg="gazebo_ros"
      type="spawn_model"
      args="-sdf -param robot_polaris -model polaris -x 5.0"
      output="screen">
    </node>
</launch>

3. Errors

After building the plugin in ~/Firmware/Tools/sitl_gazebo/Build

cmake .. && make

or in ``~/Fimware` with

make posix_gazebo_sitl gazebo

I tried to run the launch file

roslaunch px4 polaris_empty.launch

and get the erros

...
 INFO] [1514777410.939556647, 0.158000000]: AckermannPlugin::Load
gzserver: symbol lookup error: ~/Firmware/build/posix_sitl_default/build_gazebo/libpolaris_simple_control_plugin.so: undefined symbol: _ZN2tf20TransformBroadcasterC1Ev
...

It seems the plugin had been loaded at first then crashed. In searching the internet, some developers gussed it, the symbol _ZN2tf20TransformBroadcasterC1Ev, might be the version confliction.

4. Some testing

  • When I added the following codes in ../Firmware/Tools/sitl_gazebo/CMakeLists.txt
find_package(catkin REQUIRED COMPONENTS roscpp rospy angles std_srvs geometry_msgs sensor_msgs nav_msgs urdf tf dynamic_reconfigure)

and run

cmake .. && make

at ../Firmware/Tools/sitl_gazebo/Build
then I got the correct the library, though it located in ../Firmware/Tools/sitl_gazebo/Build/devel/lib. -

  • After copying the correct plugin, libpolaris_simple_control_plugin.so to the ~/Firmware/build/posix_sitl_default/build_gazebo, the code run correctly.
  • In my mind, it might be follow the catkin_make rules.

5. Questions

  • What is the _ZN2tf20TransformBroadcasterC1Ev meaning ?
  • What is the difference between the default CMakefiles.txt and the fixed one after add
find_package(catkin REQUIRED COMPONENTS roscpp rospy angles std_srvs geometry_msgs sensor_msgs nav_msgs urdf tf dynamic_reconfigure)
  • What is the correct one to build the catkin_make based plugin in sitl_gzebo correctly?
  • It seems that with the catkin, the libraries in ~/Tools/sitl_gazebo/Build/devel/lib is correct, and could we set the $GAZEBO_PLUGIN_PATH to this folder?

camera faces ground

@LorenzMeier Your last commit is not actually working for me
The output is:

[Err] [Camera.cc:1700] Unable to attach to visual with name[iris]

resp.

[Err] [Camera.cc:1700] Unable to attach to visual with name[iris_opt_flow]

iris_camera
iris_opt_flow_camera

Fix ROS support for gazebo_motor_failure_plugin

@TSC21 i have started working on gazebo_vision_plugin in a way we had previously discussed. However i found that with the current CMakeLists.txt it is impossible to build gazebo_motor_failure_plugin with the ROS support. Since the code to use ROS inside gazebo_vision_plugin would be conceptually the same it's better to fix gazebo_motor_failure_plugin before go on with the vision one. I pushed the branch that fixes some compile and build errors but the two problems remain:

  1. Undefined symbol _main for the ROS node inside gazebo_motor_failure_plugin
  2. All plugins are not being built if BUILD_ROS_INTERFACE is ON

Seems like the idea is taken from here.
If you have some time, could you please have a look on this issue especially with the CMakeLists problem one?

CI: XML schema validation

We should add a way of validating the SDF files XML schema. Two options:

  1. lxml
  2. xmllint - the quickest way, as it is can be installed as a deb package.

To be launched on a docker container.
@dagar what do you think?

MAVROS and GAZEBO - how to get actual position of the model

Hi developers,

I am running simulation using Gazebo, and I use MAVROS to interface between ROS and gazebo to do some offboard mission. I would like to ask if there is a way/plugin/message that I can use to acquire the actual position of the simulated IRIS? I can get EKF estimated position from the /mavros/local_position/pose topic, but would want to have the actual position of the drone in the simulated environment, to do some comparison.

Thanks!

Best Regards

Add Vision repo similar to OpticalFlow

There was discussion regarding addition of external vision lib similar to optical flow: #180
I've added branch which hasn't worked yet but shows pattern how it may look like.
The ultimate goal would be creation of PX4/Vision submodule (maybe) based on this implementation.
Quick search doesn't show notable restrictions regarding of such rpg_svo usage.
Currently such submodule would require some sort of maintenance because it is submodule of submodules.
Maybe it is possible to incorporate these libs in one single repo.
Any thoughts?

Documentation: What is the math behind the Motor Model?

Hi guys,

So here's the thing: I'm building a VTOL model similar to the standard VTOL which has some specifications in terms of motor setup: for example, the front motors have less torque than the back motors, which are more powerful in order to keep the vehicle balanced. The pusher motor is also different from those.

Having some time already working with Gazebo SITL, I found out that most of the vehicle models have the same motor models, pretty similar configurations and even weights. The thing is, if one wants to create his own vehicle model, with proper inertia matrix and weight, it also needs to have the motors model with the correct setup.

So after some research, and trying to figure out how to compute the different parameters that compose the motor model in the SDF config, I came up with the following math for those:

Ω or Max Rotational Velocity = Kv * Max Applied Voltage * Max Motor Efficiency * 2π / 60
Motor Constant = Thrust / (Ω) ²
Moment Constant = 60 / (2π * Kv)
Rotor Drag Coefficient = Thrust / (ρ * (Kv * Max Applied Voltage * Max Motor Efficiency / 60) ² * Propeller diameter ⁴)
Rolling Moment Coefficient = Using SST turbulence model from reference, and bent/round wings/propellers: ~0.0220 for angle of attack smaller than 16 degrees - I'm keeping this defaulted to 1E-06 for now.

where,
Kv [RPM/V]
Max Thrust [N]
Max Applied Voltage [V]
Ω Rotor angular velocity [rad/s]
ρ Air density at 20ºC: 1.2041 [kg/m³]

The Motor Time Constant is still something I don't know how to get it.

So what I ask is for help from someone that dedicated time writing the motor model plugin and that knows how's the math structured so to confirm or correct the math above. This will be helpful to everyone facing the same trouble when wanting to properly simulate their vehicle models, and not just copy paste from the existing models.

CMake fail, can not find _MAVLINK_INCLUDE_DIR

Hi

I am trying to build the drone model, but when I execute the cmake in sitl_gazebo/build, the following error occurs. It seems can not find mavlink package. How should I install it and set MAVLINK_INCLUDE_DIRS, thanks!

-- Could NOT find MAVLink (missing: MAVLINK_INCLUDE_DIRS) (found version "2.0")
-- catkin DISABLED
Gazebo version: 7.0
-- Boost version: 1.58.0
-- Found the following Boost libraries:
-- system
-- thread
-- timer
-- chrono
-- date_time
-- atomic
CMake Error: The following variables are used in this project, but they are set to NOTFOUND.
Please set them or make sure they are set and tested correctly in the CMake files:
_MAVLINK_INCLUDE_DIR

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.