Code Monkey home page Code Monkey logo

ardupilot_gazebo's Introduction

Ardupilot Gazebo plugin

Requirements :

Native Ubuntu able to run full 3D graphics. Gazebo version 8.x or greater The dev branch will works on gazebo >= 8.x
For Gazebo 7 use branch gazebo7

Disclamer :

This is a playground until I get some time to push the correct patch to gazebo master (I got hard time to work with mercurial..)!
So you can expect things to not be up-to-date.
This assume that your are using Ubuntu 16.04 or Ubuntu 18.04

Usage :

I assume you already have Gazebo installed with ROS (or without).
If you don't have it yet, install ROS with sudo apt install ros-melodic-desktop-full (follow instruction here http://wiki.ros.org/melodic/Installation/Ubuntu).
Due to a bug in current gazebo release from ROS, please update gazebo with OSRF version from http://gazebosim.org/tutorials?tut=install_ubuntu

libgazeboX-dev must be installed, X be your gazebo version (9 on ROS melodic).

For Gazebo X

sudo apt-get install libgazeboX-dev
git clone https://github.com/khancyr/ardupilot_gazebo
cd ardupilot_gazebo
mkdir build
cd build
cmake ..
make -j4
sudo make install
echo 'source /usr/share/gazebo/setup.sh' >> ~/.bashrc

Set Path of Gazebo Models (Adapt the path to where to clone the repo)

echo 'export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models' >> ~/.bashrc

Set Path of Gazebo Worlds (Adapt the path to where to clone the repo)

echo 'export GAZEBO_RESOURCE_PATH=~/ardupilot_gazebo/worlds:${GAZEBO_RESOURCE_PATH}' >> ~/.bashrc
source ~/.bashrc

DONE !

Now launch a world file with a copter/rover/plane and ardupilot plugin, and it should work! (I will try to add some world file and model later)

HELP

How to Launch :
Launch Ardupilot Software In the Loop Simulation for each vehicle. On new terminal, launch Gazebo with basic demo world.

#####ROVER (no model provided for now)

On 1st Terminal (Launch Ardupilot SITL)

sim_vehicle.py -v APMrover2 -f gazebo-rover --map --console

On 2nd Terminal (Launch Gazebo with demo Rover model)

gazebo --verbose worlds/ (Please Add if there is one.)
COPTER

On 1st Terminal (Launch Ardupilot SITL)

sim_vehicle.py -v ArduCopter -f gazebo-iris --map --console

On 2nd Terminal (Launch Gazebo with demo 3DR Iris model)

gazebo --verbose worlds/iris_arducopter_runway.world
PLANE

On 1st Terminal (Launch Ardupilot SITL)

sim_vehicle.py -v ArduPlane -f gazebo-zephyr --map --console

On 2nd Terminal (Launch Gazebo with demo Zephyr flying wing model)

gazebo --verbose worlds/zephyr_ardupilot_demo.world

In addition, you can use any GCS of Ardupilot locally or remotely (will require connection setup). If MAVProxy Developer GCS is uncomportable. Omit --map --console arguments out of SITL launch and use APMPlanner 2 or QGroundControl instead. Local connection with APMPlanner2/QGroundControl is automatic, and recommended.

Troubleshooting

### Missing libArduPilotPlugin.so... etc

In case you see this message when you launch gazebo with demo worlds, check you have no error after sudo make install.
If no error use "ls" on the install path given to see if the plugin is really here.
If this is correct, check with cat /usr/share/gazebo/setup.sh the variable GAZEBO_PLUGIN_PATH. It should be the same as the install path. If not use cp to copy the lib to right path.

For Example

sudo cp -a /usr/lib/x86_64-linux-gnu/gazebo-7.0/plugins/ /usr/lib/x86_64-linux-gnu/gazebo-7/

path mismatch is confirmed as ROS's glitch. It will be fixed.

Future(not activated yet)

To use Gazebo gps, you must offset the heading of +90° as gazebo gps is NWU and ardupilot is NED (I don't use GPS altitude for now)
example : for SITL default location

    <spherical_coordinates>
      <surface_model>EARTH_WGS84</surface_model>
      <latitude_deg>-35.363261</latitude_deg>
      <longitude_deg>149.165230</longitude_deg>
      <elevation>584</elevation>
      <heading_deg>87</heading_deg>
    </spherical_coordinates>

Rangefinder

ardupilot_gazebo's People

Contributors

acxz avatar ericjohnson97 avatar kant avatar khancyr avatar stokekld avatar swiftgust 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

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

ardupilot_gazebo's Issues

make -j4 error

Hello, after building i run this command make -j4 and get this one errors
image

And i think think this is the reason why not creating directory ardupilot_gazebo/ArduCopter

Scanning dependencies of target ArduPilotPlugin
Scanning dependencies of target ArduCopterIRLockPlugin
[ 25%] Building CXX object CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o
[ 50%] Building CXX object CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o
/home/focal/ardupilot_gazebo/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control]’:
/usr/include/c++/9/bits/alloc_traits.h:483:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_vector.h:1189:30:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/focal/ardupilot_gazebo/src/ArduPilotPlugin.cc:625:46:   required from here
/home/focal/ardupilot_gazebo/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/focal/ardupilot_gazebo/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/x86_64-linux-gnu/c++/9/bits/c++allocator.h:33,
                 from /usr/include/c++/9/bits/allocator.h:46,
                 from /usr/include/c++/9/string:41,
                 from /usr/include/c++/9/stdexcept:39,
                 from /usr/include/c++/9/array:39,
                 from /usr/include/c++/9/tuple:39,
                 from /usr/include/c++/9/functional:54,
                 from /home/focal/ardupilot_gazebo/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9/ext/new_allocator.h:146:4: note: synthesized method ‘Control::Control(const Control&)’ first required here
  146 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

Thnak you

CMake to find a package configuration file provided by "gazebo", but CMake did not find one.

Hi, I try build this plugin but I get this error after run sudo cmake ..
I use fedora35 so I cant run apt-get install libgazeboX-dev
what can I do for this problem ?

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

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

    gazeboConfig.cmake
    gazebo-config.cmake

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

camera topic not publishing

I created a new launch file and changed world argument to iris_arducopter_runway.world and named iris.launch

I run roslaunch gazebo_ros iris.launch everything loads(world,drone etc) but when i rostopic echo i can see default rostopics and something related to gazebo, e.g. /gazebo/link_states

but there is no topic publishing for camera feed. I want camera/color/image_raw topic. What could I be doing wrong? May I have forgotten something to install?

I have 18.04 Ubuntu, ROS Kinetic, Gazebo9.

Thanks.

EDIT: I didnt update world file so thats why no topic publishing. That is not a issue

Here full iris_irlock_demo.world file:

iris.txt

Do not replace this file with your world file. This file is .txt.

Cmake error

Hello, I'm trying to use the ardupilot_gazebo plugin on Ubuntu 18.04 and Gazebo 9, However after making the build directory and attempting to do: cmake .. it gives this error:

-- Checking for module 'bullet>=2.82'
-- No package 'bullet' found
-- Checking for module 'bullet2.82>=2.82'
-- No package 'bullet2.82' found
CMake Error at /usr/lib/x86_64-linux-gnu/cmake/gazebo/gazebo-config.cmake:102 (message):
Error: Bullet > 2.82 not found, please install libbullet2.82-dev.
Call Stack (most recent call first):
CMakeLists.txt:11 (find_package)

-- Configuring incomplete, errors occurred!

Arducopter crashes regularly

Hey,
So I arm and take off the drone. But it goes above the given setpoint and crashes. Even if it doesn't it keeps oscillating (+/-2 m) and is very unstable. Is there any way to correct this. Also for thrust input of 0.5 from setpoint_raw/attitude the drone moves sideways even though I dont give roll or yaw. Is there any way to correct this

sim_vehicle.py: command not found

hi, i recently followed the tutorial given to run simulation on gazebo. everything went smoothly without error until the following section

COPTER
On 1st Terminal(Launch Ardupilot SITL)

sim_vehicle.py -v ArduCopter -f gazebo-iris --map --console
On 2nd Terminal(Launch Gazebo with demo 3DR Iris model)

gazebo --verbose worlds/iris_arducopter_runway.world

I tried to run the code on the first terminal and it returned sim_vehicle.py: command not found. can you help clarify on this? thank you so much. Im new to this and would like to learn.

Ubuntu 18.04
ROS Melodic
Gazebo 9

Error Using ArduPilotPlugin With URDF Models

I am currently working on getting the ardupilot plugin to work with multiple UAVs that are launched via URDF files. I was able to transition the SDF models to URDFs that spawn correctly and output all of the expected topics (imu topic, camera topic). The models make a connection with the ardupilot side and all of the SITL consoles launch appropriately without error. However, I cannot successfully get the UAV to arm and then takeoff. With the SDF models it works.
One difference I see between the two cases, SDF and URDF, is that in the console for URDF ardupilot this error is constantly output "APM: PreArm: Accels inconsistent".
Another difference is that when I send an "arm throttle" it shows "Got MAVLink msg: COMMAND_ACK {command : 400, result : 4}" instead of "Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}".
Any tips or examples on how to resolve this issue and get the URDF models to fly appropriately?

make -j4 warnings and cannot launch worlds[Ubuntu 20.04, Gazebo 11.2]

I have the following warnings

berkeyvx@berkeyvx-desktop:~/ardupilot_gazebo/build$ make -j4
Scanning dependencies of target ArduPilotPlugin
Scanning dependencies of target ArduCopterIRLockPlugin
[ 25%] Building CXX object CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o
[ 50%] Building CXX object CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o
/home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control]’:
/usr/include/c++/9/bits/alloc_traits.h:484:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_vector.h:1189:30:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:622:46:   required from here
/home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/x86_64-linux-gnu/c++/9/bits/c++allocator.h:33,
                 from /usr/include/c++/9/bits/allocator.h:46,
                 from /usr/include/c++/9/string:41,
                 from /usr/include/c++/9/stdexcept:39,
                 from /usr/include/c++/9/array:39,
                 from /usr/include/c++/9/tuple:39,
                 from /usr/include/c++/9/functional:54,
                 from /home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9/ext/new_allocator.h:147:4: note: synthesized method ‘Control::Control(const Control&)’ first required here
  147 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {Control}; _Tp = Control]’:
/usr/include/c++/9/bits/alloc_traits.h:484:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {Control}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_uninitialized.h:912:26:   required from ‘void std::__relocate_object_a(_Tp*, _Up*, _Allocator&) [with _Tp = Control; _Up = Control; _Allocator = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_uninitialized.h:950:26:   required from ‘_ForwardIterator std::__relocate_a_1(_InputIterator, _InputIterator, _ForwardIterator, _Allocator&) [with _InputIterator = Control*; _ForwardIterator = Control*; _Allocator = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_uninitialized.h:964:28:   required from ‘_ForwardIterator std::__relocate_a(_InputIterator, _InputIterator, _ForwardIterator, _Allocator&) [with _InputIterator = Control*; _ForwardIterator = Control*; _Allocator = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_vector.h:453:26:   required from ‘static std::vector<_Tp, _Alloc>::pointer std::vector<_Tp, _Alloc>::_S_do_relocate(std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::_Tp_alloc_type&, std::true_type) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::pointer = Control*; std::vector<_Tp, _Alloc>::_Tp_alloc_type = std::allocator<Control>; std::true_type = std::integral_constant<bool, true>]’
/usr/include/c++/9/bits/stl_vector.h:466:23:   required from ‘static std::vector<_Tp, _Alloc>::pointer std::vector<_Tp, _Alloc>::_S_relocate(std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::_Tp_alloc_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::pointer = Control*; std::vector<_Tp, _Alloc>::_Tp_alloc_type = std::allocator<Control>]’
/usr/include/c++/9/bits/vector.tcc:461:34:   required from ‘void std::vector<_Tp, _Alloc>::_M_realloc_insert(std::vector<_Tp, _Alloc>::iterator, _Args&& ...) [with _Args = {const Control&}; _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::iterator = __gnu_cxx::__normal_iterator<Control*, std::vector<Control> >; typename std::_Vector_base<_Tp, _Alloc>::pointer = Control*]’
/usr/include/c++/9/bits/stl_vector.h:1195:4:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:622:46:   required from here
/home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/x86_64-linux-gnu/c++/9/bits/c++allocator.h:33,
                 from /usr/include/c++/9/bits/allocator.h:46,
                 from /usr/include/c++/9/string:41,
                 from /usr/include/c++/9/stdexcept:39,
                 from /usr/include/c++/9/array:39,
                 from /usr/include/c++/9/tuple:39,
                 from /usr/include/c++/9/functional:54,
                 from /home/berkeyvx/ardupilot_gazebo/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9/ext/new_allocator.h:147:4: note: synthesized method ‘Control::Control(Control&&)’ first required here
  147 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
[ 75%] Linking CXX shared library libArduPilotPlugin.so
[ 75%] Built target ArduPilotPlugin
[100%] Linking CXX shared library libArduCopterIRLockPlugin.so
[100%] Built target ArduCopterIRLockPlugin

after that, i keep following the documentation. But i am not be able to run worlds. I did sudo apt update and sudo apt upgrade btw.

Custom copter with hexa frame

Hello,
currently I am trying to create a custom copter with a hexagonal frame. But right now it is always slightly shaking during the flight. However since I am new in gazebo and ardupilot what are the key features I have to take care about? So far I tried to follow iris_with_ardupilot example. This is what I have changed so far:

  • In the model.sdf I simply added two rotors

  • In the iris_with_ardupilot I added the blades and the control channels for the two rotors

  • I have the following rotor configuration:

          2     0   
           \ ^ /
        5 - | | - 4
           /   \
          1     3
    

, where the rotor number coincides with the control channel number. Rotor 0 is turning clockwise and neighboring rotors have of course opposite turning directions. If desired I can also post the corresponding .sdf file.

Finally I also changed the gazebo-iris.parm file to:

FRAME_CLASS 2
FRAME_TYPE 1
RC8_OPTION 39
PLND_ENABLED 1
PLND_TYPE 3
SIM_SONAR_SCALE 10
RNGFND1_TYPE 1
RNGFND1_SCALING 10
RNGFND1_PIN 0
RNGFND1_MAX_CM 5000

How do I handle with the control channels in the ardupilot plugin?

Error with using Dronekit Sitl

I tried dronekit sitl rather than sim_vehicle.py. I ran dronekit sitl in another computer in same network.
With this command i could connect sitl to qgroundcontrol:

mavproxy.py --master tcp:192.168.1.37:5760 --out udp:127.0.0.1:14550 --out tcpin:127.0.0.1:9002

However for gazebo it didn't work. Some errors happened:
gazebo error

Error 2 with make -j4 [Ubuntu 20.04, Gazebo 11.3]

When running make -j4, I get the following errors and warnings.

chris@Ubuntuchris:~/ardupilot_gazebo/build$ make -j4
[ 25%] Building CXX object CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o
[ 25%] Built target ArduCopterIRLockPlugin
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control]’:
/usr/include/c++/9/bits/alloc_traits.h:484:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_vector.h:1189:30:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:622:46:   required from here
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/x86_64-linux-gnu/c++/9/bits/c++allocator.h:33,
                 from /usr/include/c++/9/bits/allocator.h:46,
                 from /usr/include/c++/9/string:41,
                 from /usr/include/c++/9/stdexcept:39,
                 from /usr/include/c++/9/array:39,
                 from /usr/include/c++/9/tuple:39,
                 from /usr/include/c++/9/functional:54,
                 from /home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9/ext/new_allocator.h:147:4: note: synthesized method ‘Control::Control(const Control&)’ first required here
  147 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/sdformat-9.5/sdf/Param.hh:30,
                 from /usr/include/sdformat-9.5/sdf/Element.hh:28,
                 from /usr/include/sdformat-9.5/sdf/Actor.hh:25,
                 from /usr/include/sdformat-9.5/sdf/sdf.hh:2,
                 from /home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:41:
/usr/include/c++/9/variant: In instantiation of ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’:
/usr/include/sdformat-9.5/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.5/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9/variant:1125:42: error: static assertion failed: T should occur for exactly once in alternatives
 1125 |       static_assert(__detail::__variant::__exactly_once<_Tp, _Types...>,
      |                     ~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/include/c++/9/variant: In instantiation of ‘struct std::variant_alternative<1, std::variant<ignition::math::v6::Pose3<double> > >’:
/usr/include/c++/9/variant:100:12:   recursively required from ‘struct std::variant_alternative<15, std::variant<char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >’
/usr/include/c++/9/variant:100:12:   required from ‘struct std::variant_alternative<16, std::variant<bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >’
/usr/include/c++/9/variant:1110:5:   required by substitution of ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<const typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(const std::variant<_Types ...>*) [with long unsigned int _Np = 16; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}]’
/usr/include/c++/9/variant:1128:76:   required from ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’
/usr/include/sdformat-9.5/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.5/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9/variant:100:12: error: invalid use of incomplete type ‘struct std::variant_alternative<0, std::variant<> >’
  100 |     struct variant_alternative<_Np, variant<_First, _Rest...>>
      |            ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/include/c++/9/variant:97:12: note: declaration of ‘struct std::variant_alternative<0, std::variant<> >’
   97 |     struct variant_alternative;
      |            ^~~~~~~~~~~~~~~~~~~
/usr/include/c++/9/variant: In instantiation of ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’:
/usr/include/sdformat-9.5/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.5/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9/variant:1128:76: error: no matching function for call to ‘get_if<std::__detail::__variant::__index_of_v<short unsigned int, bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >(std::variant<bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> >*&)’
 1128 |       return std::get_if<__detail::__variant::__index_of_v<_Tp, _Types...>>(
      |              ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^
 1129 |    __ptr);
      |    ~~~~~~                                                                   
/usr/include/c++/9/variant:1096:5: note: candidate: ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(std::variant<_Types ...>*)’
 1096 |     get_if(variant<_Types...>* __ptr) noexcept
      |     ^~~~~~
/usr/include/c++/9/variant:1096:5: note:   template argument deduction/substitution failed:
/usr/include/c++/9/variant: In substitution of ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(std::variant<_Types ...>*) [with long unsigned int _Np = 16; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}]’:
/usr/include/c++/9/variant:1128:76:   required from ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’
/usr/include/sdformat-9.5/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.5/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9/variant:1096:5: error: no type named ‘type’ in ‘struct std::variant_alternative<16, std::variant<bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >’
/usr/include/c++/9/variant: In instantiation of ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’:
/usr/include/sdformat-9.5/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.5/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9/variant:1110:5: note: candidate: ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<const typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(const std::variant<_Types ...>*)’
 1110 |     get_if(const variant<_Types...>* __ptr) noexcept
      |     ^~~~~~
/usr/include/c++/9/variant:1110:5: note:   substitution of deduced template arguments resulted in errors seen above
/usr/include/c++/9/variant:1123:5: note: candidate: ‘template<class _Tp, class ... _Types> constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*)’
 1123 |     get_if(variant<_Types...>* __ptr) noexcept
      |     ^~~~~~
/usr/include/c++/9/variant:1123:5: note:   template argument deduction/substitution failed:
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {Control}; _Tp = Control]’:
/usr/include/c++/9/bits/alloc_traits.h:484:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {Control}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_uninitialized.h:912:26:   required from ‘void std::__relocate_object_a(_Tp*, _Up*, _Allocator&) [with _Tp = Control; _Up = Control; _Allocator = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_uninitialized.h:950:26:   required from ‘_ForwardIterator std::__relocate_a_1(_InputIterator, _InputIterator, _ForwardIterator, _Allocator&) [with _InputIterator = Control*; _ForwardIterator = Control*; _Allocator = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_uninitialized.h:964:28:   required from ‘_ForwardIterator std::__relocate_a(_InputIterator, _InputIterator, _ForwardIterator, _Allocator&) [with _InputIterator = Control*; _ForwardIterator = Control*; _Allocator = std::allocator<Control>]’
/usr/include/c++/9/bits/stl_vector.h:453:26:   required from ‘static std::vector<_Tp, _Alloc>::pointer std::vector<_Tp, _Alloc>::_S_do_relocate(std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::_Tp_alloc_type&, std::true_type) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::pointer = Control*; std::vector<_Tp, _Alloc>::_Tp_alloc_type = std::allocator<Control>; std::true_type = std::integral_constant<bool, true>]’
/usr/include/c++/9/bits/stl_vector.h:466:23:   required from ‘static std::vector<_Tp, _Alloc>::pointer std::vector<_Tp, _Alloc>::_S_relocate(std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::_Tp_alloc_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::pointer = Control*; std::vector<_Tp, _Alloc>::_Tp_alloc_type = std::allocator<Control>]’
/usr/include/c++/9/bits/vector.tcc:461:34:   required from ‘void std::vector<_Tp, _Alloc>::_M_realloc_insert(std::vector<_Tp, _Alloc>::iterator, _Args&& ...) [with _Args = {const Control&}; _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::iterator = __gnu_cxx::__normal_iterator<Control*, std::vector<Control> >; typename std::_Vector_base<_Tp, _Alloc>::pointer = Control*]’
/usr/include/c++/9/bits/stl_vector.h:1195:4:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:622:46:   required from here
/home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/x86_64-linux-gnu/c++/9/bits/c++allocator.h:33,
                 from /usr/include/c++/9/bits/allocator.h:46,
                 from /usr/include/c++/9/string:41,
                 from /usr/include/c++/9/stdexcept:39,
                 from /usr/include/c++/9/array:39,
                 from /usr/include/c++/9/tuple:39,
                 from /usr/include/c++/9/functional:54,
                 from /home/chris/ardupilot_gazebo/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9/ext/new_allocator.h:147:4: note: synthesized method ‘Control::Control(Control&&)’ first required here
  147 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
make[2]: *** [CMakeFiles/ArduPilotPlugin.dir/build.make:63: CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:78: CMakeFiles/ArduPilotPlugin.dir/all] Error 2
make: *** [Makefile:130: all] Error 2
chris@Ubuntuchris:~/ardupilot_gazebo/build$ 

Support for a new airframe

Hi, I am trying to get a hexacopter model working with APM sim. I've swapped out the iris model with my own, and I am running APM SITL with hexacopter and all of my airframe parameters. The trouble I am having is getting the thing to takeoff! I don't really understand what the multiplier is doing in this code here:

      <control channel="0">
        <type>VELOCITY</type>
        <offset>0</offset>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>2.5</cmd_max>
        <cmd_min>-2.5</cmd_min>          
        <jointName>m600::rotor_4_joint</jointName>
        <multiplier>-838</multiplier>
        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
      </control>

I've checked my motor channel outputs and ensured they match the correct layout for a hexacopter. I am seeing all the motors begin spinning as soon as APM SITL connects . I hacked in some code into the ardupilot_gazebo plug to print out the motor cmd values.

      gzwarn << "[APM_GZ_PLUGIN] Motor 1:  " << this->dataPtr->controls[0].cmd << "\n";
      gzwarn << "[APM_GZ_PLUGIN] Motor 2:  " << this->dataPtr->controls[1].cmd << "\n";
      gzwarn << "[APM_GZ_PLUGIN] Motor 3:  " << this->dataPtr->controls[2].cmd << "\n";
      gzwarn << "[APM_GZ_PLUGIN] Motor 4:  " << this->dataPtr->controls[3].cmd << "\n";
      gzwarn << "[APM_GZ_PLUGIN] Motor 5:  " << this->dataPtr->controls[4].cmd << "\n";
      gzwarn << "[APM_GZ_PLUGIN] Motor 6:  " << this->dataPtr->controls[5].cmd << "\n";

idle

[Wrn] [ArduPilotPlugin.cc:1112] [APM_GZ_PLUGIN] Motor 1:  -83.8
[Wrn] [ArduPilotPlugin.cc:1113] [APM_GZ_PLUGIN] Motor 2:  83.8
[Wrn] [ArduPilotPlugin.cc:1114] [APM_GZ_PLUGIN] Motor 3:  -83.8
[Wrn] [ArduPilotPlugin.cc:1115] [APM_GZ_PLUGIN] Motor 4:  83.8
[Wrn] [ArduPilotPlugin.cc:1116] [APM_GZ_PLUGIN] Motor 5:  83.8
[Wrn] [ArduPilotPlugin.cc:1117] [APM_GZ_PLUGIN] Motor 6:  -83.8
[Wrn] [ArduPilotPlugin.cc:1112] [APM_GZ_PLUGIN] Motor 1:  -83.8
[Wrn] [ArduPilotPlugin.cc:1113] [APM_GZ_PLUGIN] Motor 2:  83.8
[Wrn] [ArduPilotPlugin.cc:1114] [APM_GZ_PLUGIN] Motor 3:  -83.8
[Wrn] [ArduPilotPlugin.cc:1115] [APM_GZ_PLUGIN] Motor 4:  83.8
[Wrn] [ArduPilotPlugin.cc:1116] [APM_GZ_PLUGIN] Motor 5:  83.8
[Wrn] [ArduPilotPlugin.cc:1117] [APM_GZ_PLUGIN] Motor 6:  -83.8

takeoff

[Wrn] [ArduPilotPlugin.cc:1112] [APM_GZ_PLUGIN] Motor 1:  -642.746
[Wrn] [ArduPilotPlugin.cc:1113] [APM_GZ_PLUGIN] Motor 2:  577.382
[Wrn] [ArduPilotPlugin.cc:1114] [APM_GZ_PLUGIN] Motor 3:  -499.448
[Wrn] [ArduPilotPlugin.cc:1115] [APM_GZ_PLUGIN] Motor 4:  720.68
[Wrn] [ArduPilotPlugin.cc:1116] [APM_GZ_PLUGIN] Motor 5:  522.912
[Wrn] [ArduPilotPlugin.cc:1117] [APM_GZ_PLUGIN] Motor 6:  -697.216

In both of these cases the vehicle just sits on the ground and the props appear to spin at the same rate as they were before the takeoff command. I am not sure what those units are supposed to be. When running the iris example, I am seeing zeroes while idle and around 500 when hovering. Any help would be greatly appreciated!!

Thanks!
Jake

cmake error

Hi, I am using gazebo 7 as it's the version that is supported by ROS kinetic. I had a problem on "cmake .." step. It's written that I need 7.X.Y version while I already had 7.14.0 version. Is there any way to fix it?

error

Quadplane simulation in gazebo

Hi!! I would like to run the standard vtol model to simulate the quadplane with ardupilot. I have tried to make it work. Would it be possible to add this feature in this repo?

Arduplane

there is no plane model in the workspace. There was but now is not. Can you add it?

cmake error

Hi i am new here.Sorry to ask some question.
i come across some mistake,like:
CMake Error at /home/w210/anaconda3/lib/x86_64-linux-gnu/cmake/gazebo/gazebo-config.cmake:96 (message):
Library 'gazebo_math' in package GAZEBO is not installed properly
Call Stack (most recent call first):
CMakeLists.txt:11 (find_package)

i dont know how to deal with it.can you give me some advice?
i am using gazebo9

Assertion Build Error

[ 25%] Building CXX object CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o
In file included from /usr/include/gazebo-11/gazebo/transport/Connection.hh:20,
                 from /usr/include/gazebo-11/gazebo/transport/transport.hh:3,
                 from /home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:47:
/usr/include/tbb/task.h:21:139: note: #pragma message: TBB Warning: tbb/task.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.
   21 | #pragma message("TBB Warning: tbb/task.h is deprecated. For details, please see Deprecated Features appendix in the TBB reference manual.")
      |                                                                                                                                           ^
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control]’:
/usr/include/c++/9.3.0/bits/alloc_traits.h:484:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {const Control&}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9.3.0/bits/stl_vector.h:1189:30:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:622:46:   required from here
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/c++/9.3.0/x86_64-pc-linux-gnu/bits/c++allocator.h:33,
                 from /usr/include/c++/9.3.0/bits/allocator.h:46,
                 from /usr/include/c++/9.3.0/string:41,
                 from /usr/include/c++/9.3.0/stdexcept:39,
                 from /usr/include/c++/9.3.0/array:39,
                 from /usr/include/c++/9.3.0/tuple:39,
                 from /usr/include/c++/9.3.0/functional:54,
                 from /home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9.3.0/ext/new_allocator.h:147:4: note: synthesized method ‘Control::Control(const Control&)’ first required here
  147 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/sdformat-9.2/sdf/Param.hh:30,
                 from /usr/include/sdformat-9.2/sdf/Element.hh:28,
                 from /usr/include/sdformat-9.2/sdf/Actor.hh:25,
                 from /usr/include/sdformat-9.2/sdf/sdf.hh:2,
                 from /home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:41:
/usr/include/c++/9.3.0/variant: In instantiation of ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’:
/usr/include/sdformat-9.2/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.2/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9.3.0/variant:1124:42: error: static assertion failed: T should occur for exactly once in alternatives
 1124 |       static_assert(__detail::__variant::__exactly_once<_Tp, _Types...>,
      |                     ~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/include/c++/9.3.0/variant: In instantiation of ‘struct std::variant_alternative<1, std::variant<ignition::math::v6::Pose3<double> > >’:
/usr/include/c++/9.3.0/variant:100:12:   recursively required from ‘struct std::variant_alternative<15, std::variant<char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >’
/usr/include/c++/9.3.0/variant:100:12:   required from ‘struct std::variant_alternative<16, std::variant<bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >’
/usr/include/c++/9.3.0/variant:1109:5:   required by substitution of ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<const typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(const std::variant<_Types ...>*) [with long unsigned int _Np = 16; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}]’
/usr/include/c++/9.3.0/variant:1127:76:   required from ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’
/usr/include/sdformat-9.2/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.2/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9.3.0/variant:100:12: error: invalid use of incomplete type ‘struct std::variant_alternative<0, std::variant<> >’
  100 |     struct variant_alternative<_Np, variant<_First, _Rest...>>
      |            ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/include/c++/9.3.0/variant:97:12: note: declaration of ‘struct std::variant_alternative<0, std::variant<> >’
   97 |     struct variant_alternative;
      |            ^~~~~~~~~~~~~~~~~~~
/usr/include/c++/9.3.0/variant: In instantiation of ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’:
/usr/include/sdformat-9.2/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.2/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9.3.0/variant:1127:76: error: no matching function for call to ‘get_if<std::__detail::__variant::__index_of_v<short unsigned int, bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >(std::variant<bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> >*&)’
 1127 |       return std::get_if<__detail::__variant::__index_of_v<_Tp, _Types...>>(
      |              ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^
 1128 |    __ptr);
      |    ~~~~~~                                                                   
/usr/include/c++/9.3.0/variant:1095:5: note: candidate: ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(std::variant<_Types ...>*)’
 1095 |     get_if(variant<_Types...>* __ptr) noexcept
      |     ^~~~~~
/usr/include/c++/9.3.0/variant:1095:5: note:   template argument deduction/substitution failed:
/usr/include/c++/9.3.0/variant: In substitution of ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(std::variant<_Types ...>*) [with long unsigned int _Np = 16; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}]’:
/usr/include/c++/9.3.0/variant:1127:76:   required from ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’
/usr/include/sdformat-9.2/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.2/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9.3.0/variant:1095:5: error: no type named ‘type’ in ‘struct std::variant_alternative<16, std::variant<bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double> > >’
/usr/include/c++/9.3.0/variant: In instantiation of ‘constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*) [with _Tp = short unsigned int; _Types = {bool, char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::v9::Time, ignition::math::v6::Angle, ignition::math::v6::Color, ignition::math::v6::Vector2<int>, ignition::math::v6::Vector2<double>, ignition::math::v6::Vector3<double>, ignition::math::v6::Quaternion<double>, ignition::math::v6::Pose3<double>}; std::add_pointer_t<_Tp> = short unsigned int*]’:
/usr/include/sdformat-9.2/sdf/Param.hh:318:34:   required from ‘bool sdf::v9::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-9.2/sdf/Element.hh:511:7:   required from ‘std::pair<T, bool> sdf::v9::Element::Get(const string&, const T&) const [with T = short unsigned int; std::string = std::__cxx11::basic_string<char>]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:879:57:   required from here
/usr/include/c++/9.3.0/variant:1109:5: note: candidate: ‘template<long unsigned int _Np, class ... _Types> constexpr std::add_pointer_t<const typename std::variant_alternative<_Np, std::variant<_Types ...> >::type> std::get_if(const std::variant<_Types ...>*)’
 1109 |     get_if(const variant<_Types...>* __ptr) noexcept
      |     ^~~~~~
/usr/include/c++/9.3.0/variant:1109:5: note:   substitution of deduced template arguments resulted in errors seen above
/usr/include/c++/9.3.0/variant:1122:5: note: candidate: ‘template<class _Tp, class ... _Types> constexpr std::add_pointer_t<_Tp> std::get_if(std::variant<_Types ...>*)’
 1122 |     get_if(variant<_Types...>* __ptr) noexcept
      |     ^~~~~~
/usr/include/c++/9.3.0/variant:1122:5: note:   template argument deduction/substitution failed:
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = Control; _Args = {Control}; _Tp = Control]’:
/usr/include/c++/9.3.0/bits/alloc_traits.h:484:4:   required from ‘static void std::allocator_traits<std::allocator<_CharT> >::construct(std::allocator_traits<std::allocator<_CharT> >::allocator_type&, _Up*, _Args&& ...) [with _Up = Control; _Args = {Control}; _Tp = Control; std::allocator_traits<std::allocator<_CharT> >::allocator_type = std::allocator<Control>]’
/usr/include/c++/9.3.0/bits/stl_uninitialized.h:912:26:   required from ‘void std::__relocate_object_a(_Tp*, _Up*, _Allocator&) [with _Tp = Control; _Up = Control; _Allocator = std::allocator<Control>]’
/usr/include/c++/9.3.0/bits/stl_uninitialized.h:950:26:   required from ‘_ForwardIterator std::__relocate_a_1(_InputIterator, _InputIterator, _ForwardIterator, _Allocator&) [with _InputIterator = Control*; _ForwardIterator = Control*; _Allocator = std::allocator<Control>]’
/usr/include/c++/9.3.0/bits/stl_uninitialized.h:964:28:   required from ‘_ForwardIterator std::__relocate_a(_InputIterator, _InputIterator, _ForwardIterator, _Allocator&) [with _InputIterator = Control*; _ForwardIterator = Control*; _Allocator = std::allocator<Control>]’
/usr/include/c++/9.3.0/bits/stl_vector.h:453:26:   required from ‘static std::vector<_Tp, _Alloc>::pointer std::vector<_Tp, _Alloc>::_S_do_relocate(std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::_Tp_alloc_type&, std::true_type) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::pointer = Control*; std::vector<_Tp, _Alloc>::_Tp_alloc_type = std::allocator<Control>; std::true_type = std::integral_constant<bool, true>]’
/usr/include/c++/9.3.0/bits/stl_vector.h:466:23:   required from ‘static std::vector<_Tp, _Alloc>::pointer std::vector<_Tp, _Alloc>::_S_relocate(std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::pointer, std::vector<_Tp, _Alloc>::_Tp_alloc_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::pointer = Control*; std::vector<_Tp, _Alloc>::_Tp_alloc_type = std::allocator<Control>]’
/usr/include/c++/9.3.0/bits/vector.tcc:461:34:   required from ‘void std::vector<_Tp, _Alloc>::_M_realloc_insert(std::vector<_Tp, _Alloc>::iterator, _Args&& ...) [with _Args = {const Control&}; _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::iterator = __gnu_cxx::__normal_iterator<Control*, std::vector<Control> >; typename std::_Vector_base<_Tp, _Alloc>::pointer = Control*]’
/usr/include/c++/9.3.0/bits/stl_vector.h:1195:4:   required from ‘void std::vector<_Tp, _Alloc>::push_back(const value_type&) [with _Tp = Control; _Alloc = std::allocator<Control>; std::vector<_Tp, _Alloc>::value_type = Control]’
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:622:46:   required from here
/home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:109:7: warning: implicitly-declared ‘constexpr gazebo::common::PID::PID(const gazebo::common::PID&)’ is deprecated [-Wdeprecated-copy]
  109 | class Control
      |       ^~~~~~~
In file included from /usr/include/gazebo-11/gazebo/physics/JointController.hh:25,
                 from /usr/include/gazebo-11/gazebo/physics/physics.hh:23,
                 from /usr/include/gazebo-11/gazebo/sensors/WirelessTransmitter.hh:22,
                 from /usr/include/gazebo-11/gazebo/sensors/sensors.hh:27,
                 from /home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:46:
/usr/include/gazebo-11/gazebo/common/PID.hh:157:20: note: because ‘gazebo::common::PID’ has user-provided ‘gazebo::common::PID& gazebo::common::PID::operator=(const gazebo::common::PID&)’
  157 |       public: PID &operator=(const PID &_p)
      |                    ^~~~~~~~
In file included from /usr/include/c++/9.3.0/x86_64-pc-linux-gnu/bits/c++allocator.h:33,
                 from /usr/include/c++/9.3.0/bits/allocator.h:46,
                 from /usr/include/c++/9.3.0/string:41,
                 from /usr/include/c++/9.3.0/stdexcept:39,
                 from /usr/include/c++/9.3.0/array:39,
                 from /usr/include/c++/9.3.0/tuple:39,
                 from /usr/include/c++/9.3.0/functional:54,
                 from /home/acxz/vcs/git/github/acxz/pkgbuilds/ardupilot-gazebo-sitl-git/src/ardupilot-gazebo-stil/src/ArduPilotPlugin.cc:17:
/usr/include/c++/9.3.0/ext/new_allocator.h:147:4: note: synthesized method ‘Control::Control(Control&&)’ first required here
  147 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
      |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
make[2]: *** [CMakeFiles/ArduPilotPlugin.dir/build.make:83: CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:98: CMakeFiles/ArduPilotPlugin.dir/all] Error 2
make: *** [Makefile:150: all] Error 2

OS: ArchLinux
GCC: 9.3.0
Gazebo: 11.0.0
ardupilot_gazebo: latest head at time of posting

OSX make error:

Hi there,

Thanks for making this project, I am trying to compile it on my Mac laptop,
and got errors as below, please help if any library I need to add to this project.
Mac Pro of Mojave
Gazebo 9.5.0
cmake 3.13.0
make 3.81

Thanks a lot

Mac:build sun$ make
[ 16%] Building CXX object CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o
/Users/sun/Desktop/OpenAI/ardupilot_gazebo-master/src/ArduPilotPlugin.cc:914:39: error: no member named 'GetSimTime' in 'gazebo::physics::World';
did you mean 'SimTime'?
this->dataPtr->model->GetWorld()->GetSimTime();
^~~~~~~~~~
SimTime
/usr/local/Cellar/gazebo9/9.5.0/include/gazebo-9/gazebo/physics/World.hh:219:28: note: 'SimTime' declared here
public: common::Time SimTime() const;
^
/Users/sun/Desktop/OpenAI/ardupilot_gazebo-master/src/ArduPilotPlugin.cc:999:62: error: no member named 'GetAngle' in 'gazebo::physics::Joint'
const double pos = this->dataPtr->controls[i].joint->GetAngle(0).Radian();
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ ^
/Users/sun/Desktop/OpenAI/ardupilot_gazebo-master/src/ArduPilotPlugin.cc:1195:53: error: no member named 'GetSimTime' in 'gazebo::physics::World';
did you mean 'SimTime'?
pkt.timestamp = this->dataPtr->model->GetWorld()->GetSimTime().Double();
^~~~~~~~~~
SimTime
/usr/local/Cellar/gazebo9/9.5.0/include/gazebo-9/gazebo/physics/World.hh:219:28: note: 'SimTime' declared here
public: common::Time SimTime() const;
^
/Users/sun/Desktop/OpenAI/ardupilot_gazebo-master/src/ArduPilotPlugin.cc:1245:27: error: no member named 'GetWorldPose' in
'gazebo::physics::Model'
this->dataPtr->model->GetWorldPose().Ign();
~~~~~~~~~~~~~~~~~~~~ ^
/Users/sun/Desktop/OpenAI/ardupilot_gazebo-master/src/ArduPilotPlugin.cc:1278:38: error: no member named 'GetWorldLinearVel' in
'gazebo::physics::Link'
this->dataPtr->model->GetLink()->GetWorldLinearVel().Ign();
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ ^
5 errors generated.
make[2]: *** [CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o] Error 1
make[1]: *** [CMakeFiles/ArduPilotPlugin.dir/all] Error 2
make: *** [all] Error 2

VERSION_GREATER_EQUAL is not implemented until CMake 3.7

CMake VERSION_GREATER_EQUAL macro is not implemented until CMake 3.7, so this line cause a problem (default CMake version on Ubuntu 16.04 is 3.5.1).

Change minimum required CMake version to 3.7, or change the condition to "${GAZEBO_VERSION}" VERSION_GREATER "8" OR "${GAZEBO_VERSION}" VERSION_EQUAL "8" should fix the issue.

Simulating a larger motor

Hi, I am having a hard time understanding how to adjust the libArduPilotPlugin to spec a larger motor. I have done this in PX4 using their plugin that allows you to specify all of the motor constants, but I am unsure how to do this for APM. Could you provide some detail on how these parameters are intended to be used? I would greatly appreciate it!

        <type>VELOCITY</type>
        <offset>0</offset>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>2.5</cmd_max>
        <cmd_min>-2.5</cmd_min>
        <jointName>iris::rotor_0_joint</jointName>
        <multiplier>838</multiplier>
        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

Rover model and wolrd file

Hey @khancyr,
I have seen your video on your video with rover and copter.
I want to use rover world file of gazebo.
And also its a long time you had done this work around 3.5 year ago, why it is not there in your repo?(any specific reason)

cmake error

Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'

CMake Error at /usr/share/cmake-3.5/Modules/FindPackageHandleStandardArgs.cmake:148 (message):
Could NOT find ZeroMQ (missing: ZeroMQ_FOUND) (Required is at least version
"4")
can you find what is wrong?

IRLOCK Implementation

Hello,

I have a question regarding the IRLOCK implementation on Gazebo .

I am interested in discovering the accuracy of the IRLOCK in Gazebo compares to another sensor.

I have already implemented the functionality of 'the other sensor' but I am quite sure that the implementation of the IRLOCK in Gazebo is not the 'real' one (is it just a mocap?). In other words, it does not run the real functionality of the sensor.

Am i wrong ? Excuse me for the question, but I need to be a hundred percent sure, due to the fact that the simulation I am interested in must be as close to real as possible.

If I am right i would glad to work on it.

Best regards.

Unable to find uri[model://iris_with_ardupilot]

Hi,

After running gazebo --verbose worlds/iris_arducopter_runway.world
it tells:
Gazebo multi-robot simulator, version 9.13.1
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
Gazebo multi-robot simulator, version 9.13.1
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.122.1
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.122.1
[Wrn] [ModelDatabase.cc:340] Getting models from[http://models.gazebosim.org/]. This may take a few seconds.
[Wrn] [FuelModelDatabase.cc:248] URI not supported by Fuel [model://iris_with_ardupilot]
[Wrn] [SystemPaths.cc:464] File or path does not exist [""] [model://iris_with_ardupilot]
Error Code 11 Msg: Unable to find uri[model://iris_with_ardupilot]
[Wrn] [Publisher.cc:135] Queue limit reached for topic /gazebo/default/physics/contacts, deleting message. This warning is printed only once.

I have the folder /usr/share/gazebo-9/models/iris_with_ardupilot with the .config and .sdf file in it ..

drone is not displayed

In a terminal, I started Gazebo by gazebo --verbose worlds/iris_arducopter_runway.world and in another terminal I started SITL simulation by cd ~/ardupilot/ArduCopter
../Tools/autotest/sim_vehicle.py -f gazebo-iris --console --map
However, the drone is not displayed. How should I fix this issue? Thanks!
image

Channel in Control Bracket

What does the "channel" inside the control bracket represents?
It is the connection you would do in the real world or a channel of an rc input?

Error start stil simulation

Hi ,

i enter this command but i have error message shown below,

what can be problem, i am new gazebo, ros and ardupilot

thank you for your support

…/Tools/autotest/sim_vehicle.py -f gazebo-iris --console --map

SIM_VEHICLE: Start
Traceback (most recent call last):
File “…/Tools/autotest/sim_vehicle.py”, line 796, in
frame_infos = options_for_frame(cmd_opts.frame, cmd_opts.vehicle, cmd_opts)
File “…/Tools/autotest/sim_vehicle.py”, line 506, in options_for_frame
ret = _options_for_frame[p]
KeyError: ‘gazebo’
SIM_VEHICLE: Killing tasks

takeoff zaphyr_ardupilot_demo

Can you explain how did you takeoff the plane? in my case the plane moves with a constant speed and nothing changes when I send 'takeoff' command. I also writes a few WP and send Mission Start command using APMPlanner but nothing changes.

Multi-Vehicle(zephyr and iris) ardupilot gazebo simulation: Going to different points in Gazebo simulation for the same 'lat lon alt'

Hello dear contributors of this repository

I want to simulate a zephyr fixed-wing and an iris copter in one gazebo simulation using the forked version of this repository, SwiftGust/ardupilot_gazebo repository.

So What I have done is, I have opened the zephyr demo world in gazebo and inserted an iris model into the environment and finally saved that file as another file. after that I run SITL simulation for both iris and zephyr in the same location through -L option in sim_vehicle.py command. So I can assume when I give a guided lat lon alt command with the same arguments to both drones, the drones move toward a same location in the gazebo simulation, but each of them goes to a different place.

I have also set the same location in the <spherical_coordinate> tag in the world file but it did not help.

Sincerely!

APM: EKF2 IMU0 ground mag anomaly, yaw re-aligned when run with gazebo_ros

Hello,
Until 2 weeks ago the setup that I was using with Arducopter 3.6.7, Gazebo 9 and ROS was working fine. But from then the drone, after giving a takeoff command, takes off with a tilt, gives the following errors,

ARMED
Got COMMAND_ACK: NAV_TAKEOFF: ACCEPTED
APM: EKF2 IMU0 ground mag anomaly, yaw re-aligned
APM: EKF2 IMU1 ground mag anomaly, yaw re-aligned
APM: GPS Glitch
APM: EKF variance
LAND> Mode LAND

and flips in air and crashes.
Screenshot from 2020-11-27 11-46-54

This seems to be a ROS specific problem because the same world when run without ROS behaves normally. This problem happens when I run with gazebo_ros node. I don't understand how this could be interfering with Gazebo's IMU. I'm getting the same problem with SwiftGust's plugin.

Model not provided in repository

In line 9 of the model.sdf file of iris_with_ardupilot

<include>
      <uri>model://gimbal_small_2d</uri>
      <pose>0 -0.01 0.070 1.57 0 1.57</pose>
</include>

However, no model with the name of gimbal_small_2d is provided in the entire repository, nor there is any direction on how and where to obtain that model.

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.