Giter VIP home page Giter VIP logo

ardupilot_gazebo's Introduction

Ardupilot Gazebo Plugin & Models

Requirements :

Native Ubuntu Xenial(16.04 LTS) able to run full 3D graphics.

Note : Virtual Machine such as VMWare Player does not support full 3D graphics.

but, possible solution is here

Type follow in the terminal,

echo "export SVGA_VGPU10=0" >> ~/.bashrc
source ~/.bashrc

solution retreived from here http://answers.gazebosim.org/question/13214/virtual-machine-not-launching-gazebo/

Note : This just enables running gazebo in virtual machine, does not guarantee the performance and Gazebo require much of CPU & GPU processing power depending on what you are running the simulation.

ArduPilot setup for SITL launch Gazebo version 7 or later

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

Repository Structure :

models_gazebo : Gazebo Original models retrieved from OSRF bitbucket repository (you can find more in https://bitbucket.org/osrf/gazebo_models/src)

models : Ardupilot SITL compatible models.

worlds : Ardupilot SITL example worlds.

src : source files for Gazebo - ArduPilot Plugin

include : header files for Gazebo - ArduPilot Plugin

Getting Started :

How to Install :

I assume you already have Gazebo 7+ installed with ROS (or without).
If you don't have it yet, install ROS with sudo apt install ros-kinetic-desktop-full (follow instruction here http://wiki.ros.org/kinetic/Installation/Ubuntu).

Or install directly gazebo8 from http://gazebosim.org/tutorials?tut=install_ubuntu

libgazebo7-dev or libgazebo8-dev must be installed.

For Gazebo 7

sudo apt-get install libgazebo7-dev

OR

For Gazebo 8

sudo apt-get install libgazebo8-dev

OR

For Gazebo 9

sudo apt-get install libgazebo9-dev

Common :

git clone https://github.com/SwiftGust/ardupilot_gazebo
cd ardupilot_gazebo
mkdir build
cd build
cmake ..
make -j4
sudo make install

Set Path of Gazebo Models / Worlds... Open up .bashrc

sudo gedit ~/.bashrc

Copy & Paste Followings at the end of .bashrc file

source /usr/share/gazebo/setup.sh

export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models:${GAZEBO_MODEL_PATH}
export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models_gazebo:${GAZEBO_MODEL_PATH}
export GAZEBO_RESOURCE_PATH=~/ardupilot_gazebo/worlds:${GAZEBO_RESOURCE_PATH}
export GAZEBO_PLUGIN_PATH=~/ardupilot_gazebo/build:${GAZEBO_PLUGIN_PATH}

Install is complete

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

On 1st Terminal(Launch ArduRover SITL)

sim_vehicle.py -v APMrover2 -f gazebo-rover  -m --mav10 --map --console -I1

On 2nd Termianal(Launch Gazebo with differential drive Rover model, Retrieved from Husky Model)

gazebo --verbose rover_ardupilot.world

COPTER (3DR IRIS) On 1st Terminal(Launch ArduCopter SITL)

sim_vehicle.py -v ArduCopter -f gazebo-iris  -m --mav10 --map --console -I0

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

gazebo --verbose iris_ardupilot.world

PLANE On 1st Terminal(Launch ArduPlane SITL)

sim_vehicle.py -v ArduPlane -f gazebo-zephyr  -m --mav10 --map --console -I0

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

gazebo --verbose zephyr_ardupilot_demo.world

In addition, you can use any GCS that can connect to the Ardupilot locally or remotely(will require connection setup). If MAVProxy Developer GCS is uncomfortable. Omit --map --console arguments out of SITL launch.

And use APMPlanner2 or QGroundControl instead. (Possibly MissionPlanner but require Windows PC)

Local connection with APMPlanner2/QGroundControl is automatic, and easier to use.

For APMPlanner2

Download it from here http://firmware.eu.ardupilot.org/Tools/APMPlanner/ and launch it in terminal or run executable

apmplanner2

For QGroundControl

Download it from here and follow the installation guide.

https://donlakeflyer.gitbooks.io/qgroundcontrol-user-guide/en/download_and_install.html

Multi-Vehicle simulation

This section explains how to connect any combination of multi-vehicles of ArduPilot

For the multi-vehicle connection, port number is increased by 10 per instance(#) In SITL launch argument -I # of sim_vehicle.py

-I 0 has FDM in/out ports of 9002/9003 / GCS connection UDP:14550

-I 1 has FDM in/out ports of 9012/9013 / GCS connection UDP:14560

-I 2 has FDM in/out ports of 9022/9023 / GCS connection UDP:14570

and so on...

You will need to edit your world for any combination of Rover, Plane, Copter, etc...

Additional Note for GCS Connection You will also need to edit ArduPilot Parameter SYSID_THISMAV to be unique from one another for the GCS connection

Example

Look simulation of 3 IRIS quadcopter at once from Jonathan Lopes Florêncio https://www.youtube.com/watch?v=3c7EhVMaqKY&feature=youtu.be

Troubleshooting

Missing libArduPilotPlugin

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 Gazebo's glitch. It only happens with Gazebo version 7.

ardupilot_gazebo's People

Contributors

johncarl81 avatar khancyr avatar shovan777 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  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

Plugin issues with Gazebo 11

On following the steps with arducopter, the gazebo world opens up with out a drone in it.
On ardurover the rover does load in the gazebo world but, I receive this:

[Err] [Plugin.hh:178] Failed to load plugin libhusky_gazebo_plugins.so: libhusky_gazebo_plugins.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:178] Failed to load plugin /home/icefire/Drone/ardupilot_gazebo/build/libArduPilotPlugin.so: libgazebo_sensors.so.9: cannot open shared object file: No such file or directory

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

Plane does not move in gazebo

Hi! I pluged in gazebo and ardupilot then connected to sitl. When i send a command like arm throttle or takeoff nothing happens to fixed-wing plane in gazebo. I also tried to connect mission planner to sitl and gave the commands from mission planner but again nothing happened to plane in gazebo.

parse as sdf version 1.7 failed with Gazbo11

When running gazebo --verbose zephyr_ardupilot_demo.world I get the following error:

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 10.109.41.239
Error [parser.cc:525] parse as sdf version 1.7 failed, should try to parse as old deprecated format
Error Code 4 Msg: Required attribute[xmlns:xacro] in element[sdf] is not specified in SDF.
Error Code 8 Msg: Unable to parse sdf element[sdf]
[Msg] Loading world file [/home/hermamr1/ardupilot_gazebo/worlds/zephyr_ardupilot_demo.world]
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 10.109.41.239

When running gazebo --verbose /usr/share/gazebo-11/worlds/zephyr_demo.world I do not get a similar error.

I start with a fresh Ubuntu 20.04 install, and added the ros package list and installed gazebo11 via

sudo apt install gazebo11
sudo apt install gazebo11-dev

I followed the install instructions on this git's readme installing/making from master. During the cmake step I do get this warning (not sure if relevent):

-- Looking for ignition-common3 -- found version 3.14.0
-- Looking for ignition-math6 -- found version 6.9.2
-- Looking for ignition-msgs5 -- found version 5.8.1
Gazebo version: 11.9
-- Configuring done
WARNING: Target "ArduCopterPlugin" requests linking to directory "/home/hermamr1/ardupilot_gazebo/build".  Targets may link only to libraries.  CMake is dropping the item.
WARNING: Target "ArduPilotPlugin" requests linking to directory "/home/hermamr1/ardupilot_gazebo/build".  Targets may link only to libraries.  CMake is dropping the item.
WARNING: Target "ArduCopterIRLockPlugin" requests linking to directory "/home/hermamr1/ardupilot_gazebo/build".  Targets may link only to libraries.  CMake is dropping the item.
-- Generating done
-- Build files have been written to: /home/hermamr1/ardupilot_gazebo/build

Not sure if there is a missing step in the install instructions where I need to resolve these.

When doing the above but with Gazebo9 (don't need to add the ros package as gazebo9 in the default ubuntu package manager) I do not get the sdf parse error and things run as expected.

How to use ardupilot_gazebo with ROS

Hai,

first of all Awesome work!

I have a doubt, here we are opening ardupilot_gazebo plugin without ROS. Can we actually open ardupilot_gazebo inside ROS so that I can run my autonomous control ros node and see the simulation ?

Thanks in advance!

Rotate Gimbal

Thanks for your repo
I have a question about control gimbal
How can I rotate gimbal based on dronekit?
Can you help me?

libWindPlugin.so

Hey,

I'm trying to figure out the WindPlugin specifically the one that defined at X2_ardupilot_wind.world
I did a walkthrough on WindPlugin.cc but honestly I didn't understand the mathematics behind it at all..
Moreover, when running with the wind configuration defined in X2_ardupilot_wind.world I do get some wind but it's weird and I can't figure it out.
It also seems that the parameters don't seem to do something in this configuration.
If someone have an experience with this plugin I would be glad to hear about it.

Thanks, Gal.

Deltawing crashes at takeoff

Hi,
I am trying to make the Delta Wing fly with SITL and Gazebo. I installed Ardupilot 4.0.9 and Gazebo 9. I installed the ardupilot gazebo plugin at the branch "gazebo 9". I can start SITL and Gazebo without problems. After everything starts, I give the mission "CMAC-circuit.txt", then I set in AUTO mode and I arm the throttle. The Delta Wing starts, it reaches a couple of meters altitude, then turns at 180° roll and falls on the ground. No error is printed on screen. I had a look at all the parameters but I found nothing that could cause the problem. Did I miss something or did I do something wrong?

how sikorsky-X2 hover?

Dear
when I test sikorsky-X2 hover,fly away and crash.
I type mode guided, arm throttle ,takeoff 2.

Standard VTOL SITL Gazebo9

Hi there,

Im trying to use the ardupilot_gazebo plugin from this repo and having no success.

On master there is a model called "standard_vtol" , and when I download the master branch, when compiling the "cmake -j4 " several erros apear. The solution is "git checkout gazebo9" witch forces me to use the gazebo9 branch.

On the gazebo9 branch, there is no "standard_vtol" model, so I have added the one from master.

After all of this, when trying to use SITL simulation with ardupilot and gazebo, with the commands:

For ardupilot:

sim_vehicle.py -v ArduPlane -f quadplane -m --mav10 --map --console -I0

For gazebo, I have created one new world where I spawn the standard_vtol frame and type this on the command line:

gazebo --verbose vtol.world

The world was created by copying the "iris_ardupilot.world" and replacing on the last lines for standard_vtol when necessary.

Now, the problem:

  • Both ardupilot console and QGroundControl recognize the commands and everything is working
  • Gazebo launches the correct world and model.

However, the model does not move anything, like there is no link between ardupilot and gazebo.
Can anyone help on that?

Thanks :)


CONSOLE MESSAGE FROM GAZEBO LAUNCH

Gazebo multi-robot simulator, version 9.11.0
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.11.0
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: 172.18.131.46
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 172.18.131.46
[Msg] Home latitude is set to 41.186098.
[Msg] Home longitude is set to -8.705933.
[Msg] Home altitude is set to 3.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::rotor_0_joint] found for channel[0] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::rotor_1_joint] found for channel[1] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::rotor_2_joint] found for channel[2] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::rotor_3_joint] found for channel[3] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::rotor_puller_joint] found for channel[4] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::left_elevon_joint] found for channel[5] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::right_elevon_joint] found for channel[6] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:129] joint [standard_vtol::elevator_joint] found for channel[7] joint control active for this channel.
[Msg] Connecting to PX4 SITL using UDP
[Msg] Lockstep is disabled
[Msg] Using MAVLink protocol v2.0
[Err] [InsertModelWidget.cc:433] Missing model.config for model "/home/rui/ardupilot_gazebo/gazebo_models/.hg"
[Wrn] [Event.cc:61] Warning: Deleting a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
[Wrn] [Publisher.cc:141] Queue limit reached for topic /gazebo/default/user_camera/pose, deleting message. This warning is printed only once.


My own vtol.world file

quick 100 1.0 0.0 0.9 0.1 0.0 0 0.0025
  <include>
  <uri>model://sun</uri>
</include>

<model name="ground_plane">
  <static>true</static>
  <link name="link">
    <collision name="collision">
      <geometry>
        <plane>
          <normal>0 0 1</normal>
          <size>5000 5000</size>
        </plane>
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>1</mu>
            <mu2>1</mu2>
          </ode>
        </friction>
      </surface>
    </collision>
    <visual name="runway">
      <pose>000 0 0.005 0 0 -1.5707</pose>
      <cast_shadows>false</cast_shadows>
      <geometry>
        <plane>
          <normal>0 0 1</normal>
          <size>1829 45</size>
        </plane>
      </geometry>
      <material>
        <script>
          <uri>file://media/materials/scripts/gazebo.material</uri>
          <name>Gazebo/Runway</name>
        </script>
      </material>
    </visual>

    <visual name="grass">
      <pose>0 0 -0.1 0 0 0</pose>
      <cast_shadows>false</cast_shadows>
      <geometry>
        <plane>
          <normal>0 0 1</normal>
          <size>5000 5000</size>
        </plane>
      </geometry>
      <material>
        <script>
          <uri>file://media/materials/scripts/gazebo.material</uri>
          <name>Gazebo/Grass</name>
        </script>
      </material>
    </visual>

  </link>
</model>

<model name="standard_vtol">
  <pose> 0 0 0 0 0 0 </pose>
  <include>
    <uri>model://standard_vtol</uri>
     <pose> 0 0 0 0 0 0 </pose>
  </include>
</model>

Compilation error on Gazebo 9

Hello,

Trying to build the project on gazebo-9, 'make' gave me the following error:

In file included from /usr/include/boost/variant.hpp:22:0,
                 from /usr/include/sdformat-6.1/sdf/Param.hh:24,
                 from /usr/include/sdformat-6.1/sdf/Element.hh:25,
                 from /usr/include/sdformat-6.1/sdf/sdf.hh:4,
                 from /home/j/ardupilot_gazebo/src/ArduCopterPlugin.cc:27:
/usr/include/boost/variant/get.hpp: In instantiation of ‘typename boost::add_reference<T>::type boost::strict_get(boost::variant<T0, TN ...>&) [with U = short unsigned int; T0 = bool; TN = {char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::Time, ignition::math::v4::Color, ignition::math::v4::Vector2<int>, ignition::math::v4::Vector2<double>, ignition::math::v4::Vector3<double>, ignition::math::v4::Quaternion<double>, ignition::math::v4::Pose3<double>}; typename boost::add_reference<T>::type = short unsigned int&]’:
/usr/include/boost/variant/get.hpp:284:25:   required from ‘typename boost::add_reference<T>::type boost::get(boost::variant<T0, TN ...>&) [with U = short unsigned int; T0 = bool; TN = {char, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, long unsigned int, unsigned int, double, float, sdf::Time, ignition::math::v4::Color, ignition::math::v4::Vector2<int>, ignition::math::v4::Vector2<double>, ignition::math::v4::Vector3<double>, ignition::math::v4::Quaternion<double>, ignition::math::v4::Pose3<double>}; typename boost::add_reference<T>::type = short unsigned int&]’
/usr/include/sdformat-6.1/sdf/Param.hh:296:31:   required from ‘bool sdf::Param::Get(T&) const [with T = short unsigned int]’
/usr/include/sdformat-6.1/sdf/Element.hh:454:7:   required from ‘std::pair<T, bool> sdf::Element::Get(const string&, const T&) const [with T = short unsigned int; std::__cxx11::string = std::__cxx11::basic_string<char>]’
/usr/include/sdformat-6.1/sdf/Element.hh:429:55:   required from ‘T sdf::Element::Get(const string&) const [with T = short unsigned int; std::__cxx11::string = std::__cxx11::basic_string<char>]’
/home/j/ardupilot_gazebo/src/ArduCopterPlugin.cc:55:12:   required from ‘bool getSdfParam(sdf::ElementPtr, const string&, T&, const T&, const bool&) [with T = short unsigned int; sdf::ElementPtr = std::shared_ptr<sdf::Element>; std::__cxx11::string = std::__cxx11::basic_string<char>]’
/home/j/ardupilot_gazebo/src/ArduCopterPlugin.cc:590:45:   required from here
/usr/include/boost/variant/get.hpp:212:5: error: static assertion failed: boost::variant does not contain specified type U, call to boost::get<U>(boost::variant<T...>&) will always throw boost::bad_get exception
     BOOST_STATIC_ASSERT_MSG(
     ^

Not to mention that the problem is located here:

template <class T>
bool getSdfParam(sdf::ElementPtr _sdf, const std::string &_name,
  T &_param, const T &_defaultValue, const bool &_verbose = false)

On both ArduCopterPlugin and ArduPilotPlugin files.

Problem with Irlock world

Hi,

I'm trying to simulate the iris_irlock_demo world to test the irlock in action. I’ve installed ubuntu 18.04 with all prerequisite that ardupilot needs. I’ve followed ardupilot instructions to work with gazebo and I’ve installed this repo.

I run gazebo(9) with the next line:
gazebo --verbose gazebo_worlds/iris_irlock_demo.world

And ardupilot with the next line from the ArduCopter directory:
…/Tools/autotest/sim_vehicle.py -f gazebo-iris --console --map

In the simulation I takeoff the drone and change to mode land but the drone never achieve to see the beacon and lands in other position.

this is the output from gazebo:

Gazebo multi-robot simulator, version 9.16.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

Gazebo multi-robot simulator, version 9.16.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.72
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.72
[Msg] Loading world file [/home/jesus/Documents/SkySolutions/ardupilot_gazebo/worlds/iris_irlock_demo.world]
[Err] [InsertModelWidget.cc:426] Missing model.config for model "/home/jesus/Documents/SkySolutions/ardupilot_gazebo/models/.hg"

am I working in the rigth way?

How were the aerodynamic parameters for the Iris model obtained?

      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>0 0 1</upward>

I'm a member of a university team where we build our own drones from scratch, and our engineering team is stuck on how to calculate some of these coefficients. The parameters as specified by http://gazebosim.org/tutorials?tut=aerodynamics&cat=plugins seem to be better suited to a fixed-wing aircraft rather than a quadcopter.

Build error during "make" step

Hi,

I was just trying to build this on a new computer and ran into an issue while running the make -j4 command.

My error resulted in:

:~/ardupilot_gazebo/build$ make -j4
[ 12%] Building CXX object CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o
[ 37%] Built target GimbalSmall2dPlugin
[ 87%] Built target ArduCopterPlugin
[ 87%] Built target ArduPilotPlugin
/home/s/ardupilot_gazebo/src/ArduCopterIRLockPlugin.cc: In member function ‘virtual void gazebo::ArduCopterIRLockPlugin::Publish(const string&, unsigned int, unsigned int)’:
/home/s/ardupilot_gazebo/src/ArduCopterIRLockPlugin.cc:296:32: error: ‘_fiducial’ was not declared in this scope
std::cerr << "fiducial '" << _fiducial << "':" << _x << ", " << _y
^
CMakeFiles/ArduCopterIRLockPlugin.dir/build.make:62: recipe for target 'CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o' failed
make[2]: *** [CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o] Error 1
CMakeFiles/Makefile2:67: recipe for target 'CMakeFiles/ArduCopterIRLockPlugin.dir/all' failed
make[1]: *** [CMakeFiles/ArduCopterIRLockPlugin.dir/all] Error 2
Makefile:127: recipe for target 'all' failed
make: *** [all] Error 2

I referenced an older version of the code I had on another computer from 4 months ago and noticed that the lines in question were commented out previously. I proceeded to comment out the lines (296-297) in ArduCopterIRLockPlugin.cc and ran the make command again with no errors.

Not sure if this needs to be addressed or not?

Thanks,
-s

QuadPlane Rotors Spinning up during Initialisation

I have made a simple Quadplane model and have configured the channels in the ArduPilot correctly for my model.

I have noticed when the ArduPilot SITL is initialising all my rotors spin up. This wouldn't be an issue, however once initialisation has finished the rotors are still spinning. I was able to rectify the motors spining after initialisation by using the offset Param, but this offset actually adds onto that initial motor spin up and causes the QuadPlane to takeoff.

Does anyone know anything about this?

Is it a Parameter setting in ArduPlane or is it a plugin thing?

Ardupilot SITL not working with Gazebo-11

I'm trying to use Ardupilot plugin with gazebo-11. I can send commands and takeoff in console but in Gazebo nothing happens. In console it says height: 30, height:45 etc. but it looks like gazebo doesn't respond.

Heres my drone.urdf file:

drone.txt

sim_vehicle.py: command not found

Hi! I have installed this code with gazebo7 as instructed. But when i run the command sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 --map --console -I0 (for any robot) I get the error sim_vehicle.py: command not found

I ran this command in the ardupilot_gazebo folder.

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.

AttributeError in waypoint module when running sim_vehicle.py with Gazebo

Bug Report: AttributeError in waypoint module when using sim_vehicle.py with Gazebo

Describe the bug
When attempting to run sim_vehicle.py with the Gazebo model for APMrover2, the process fails, and MAVProxy exits unexpectedly. The error log indicates an AttributeError in the waypoint module.

To Reproduce
Steps to reproduce the behavior:

  1. Run the following command:
    sim_vehicle.py -v APMrover2 -f gazebo-rover -m --mav10 --map --console -I1

Error Log
Build commands will be stored in build/sitl/compile_commands.json
'build' finished successfully (3.372s)
SIM_VEHICLE: Using defaults from (ardupilot/Tools/autotest/default_params/gazebo-zephyr.parm)
SIM_VEHICLE: Run ArduPlane
SIM_VEHICLE: "/home/haris/ardupilot/Tools/autotest/run_in_terminal_window.sh" "ArduPlane" "/home/haris/ardupilot/build/sitl/bin/arduplane" "-S" "--model" "gazebo-zephyr" "--speedup" "1" "--slave" "0" "--defaults" "ardupilot/Tools/autotest/default_params/gazebo-zephyr.parm" "--sim-address=127.0.0.1" "-I0"
SIM_VEHICLE: Run MavProxy
SIM_VEHICLE: "mavproxy.py" "--out" "127.0.0.1:14550" "--master" "tcp:127.0.0.1:5760" "--sitl" "127.0.0.1:5501" "--mav10" "--map" "--console"
RiTW: Starting ArduPlane : /home/haris/ardupilot/build/sitl/bin/arduplane -S --model gazebo-zephyr --speedup 1 --slave 0 --defaults ardupilot/Tools/autotest/default_params/gazebo-zephyr.parm --sim-address=127.0.0.1 -I0
Connect tcp:127.0.0.1:5760 source_system=255
waypoint module not available; use old compat modules
Traceback (most recent call last):
File "/home/haris/.local/bin/mavproxy.py", line 1466, in
mpstate.load_module(m, quiet=True)
File "/home/haris/.local/bin/mavproxy.py", line 374, in load_module
module = m.init(mpstate, **kwargs)
File "/home/haris/.local/lib/python3.10/site-packages/MAVProxy/modules/mavproxy_wp.py", line 576, in init
return WPModule(mpstate)
File "/home/haris/.local/lib/python3.10/site-packages/MAVProxy/modules/mavproxy_wp.py", line 19, in init
super(WPModule, self).init(mpstate, "wp", "waypoint handling", public=True)
File "/home/haris/.local/lib/python3.10/site-packages/MAVProxy/modules/lib/mission_item_protocol.py", line 35, in init
self.completions())
File "/home/haris/.local/lib/python3.10/site-packages/MAVProxy/modules/lib/mission_item_protocol.py", line 106, in completions
cs = self.commands()
File "/home/haris/.local/lib/python3.10/site-packages/MAVProxy/modules/mavproxy_wp.py", line 161, in commands
ret.update({
AttributeError: 'NoneType' object has no attribute 'update'
SIM_VEHICLE: MAVProxy exited
SIM_VEHICLE: Killing tasks

System Details:

  • OS: Ubuntu 20.04
  • Python Version: 3.10
  • MAVProxy Version: 1.8.70

How to simulate a custom tilt rotor with Gazebo

I've created a custom tilt rotor model in gazebo and can successfully link it with the gazebo SITL. The model is a quadplane (which will have a wing in the future) and each motor arm is able to tilt forwards to transition to fixed wing flight.

In the model SDF file, how do I tell Gazebo to take the PWM command from Ardupilot SITL and turn it into motor arm angular position? (eg 0 degrees is when the motor arm is vertical and 90 degrees is when the motor arm is tilted forward for fixed wing flight).

Thanks in advance!

Low real time factor with gazebo 11.12

Hello,
I am doing a project where I am training an UAV controller. I am using ardupilot, SITL, gazebo 11.12, and ROS. The problem is I have to run several simulations and I need to make my simulation faster.

My simulation is running with a real time factor (gazebo) of 0.6 to 1. I already changed real time update rate to 0, and SIM_SPEEDUP to more than 1, but it still remains around 0.6-1. I found that if I use the iris vehicle with ardupilot plugin in an empty world I get 0.6 RTF. If I use iris model without ardupilot plugin, I get around 6 RTF, which would be very good.

Any suggestions on how to increase speed would be much appreciated.
Thank you!

Multiple UAVs in One Simulation Environment

Hi.
How can i simulate multiple copter of plane in one simulation environment?
In SITL part i can do this:

sim_vehicle.py -v ArduPlane -f gazebo-zephyr -I0
sim_vehicle.py -v ArduPlane -f gazebo-zephyr -I1

What should i do in the world file?
Thanks...

Crash with gazebo9

Hey there,

I'm having trouble running ardupilot_gazebo (master branch) with gazebo 9.
gazebo standalone works fine but when running with "gazebo --verbose iris_ardupilot.world" I don't get any errors but the gazebo wont start.

What could be the issue?

Thanks, Gal.

ubuntu@ubuntu-VirtualBox:~/sim/ardupilot_gazebo/build$ gazebo --verbose iris_ardupilot.world
Gazebo multi-robot simulator, version 9.16.0
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.16.0
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: 10.0.2.15
Warning [parser.cc:759] XML Attribute[xmlns:xacro] in element[sdf] not defined in SDF, ignoring.
[Msg] Loading world file [/home/ubuntu/sim/ardupilot_gazebo/worlds/iris_ardupilot.world]
[Wrn] [Event.cc:61] Warning: Deleting a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
[Msg] [ArduPilotPlugin] Model :iris
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::base_link
[Msg] [ArduPilotPlugin] Model :    base_link_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/ground_truth/odometry_sensorgt_link
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/imu_link
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_0
[Msg] [ArduPilotPlugin] Model :    rotor_0_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_1
[Msg] [ArduPilotPlugin] Model :    rotor_1_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_2
[Msg] [ArduPilotPlugin] Model :    rotor_2_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_3
[Msg] [ArduPilotPlugin] Model :    rotor_3_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::cam_link
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/ground_truth/odometry_sensorgt_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/imu_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_0_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_1_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_2_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_3_joint
ubuntu@ubuntu-VirtualBox:~/sim/ardupilot_gazebo/build$

Ardurover Ardupilot interface issue

Hi,

I'm trying to interface Ardupilot and Husky rover in Gazebo. While running the commands given I always get the following error
Failed to load plugin libhusky_gazebo_plugins.so: libhusky_gazebo_plugins.so: cannot open shared object file: No such file or directory
and also
Conversion of sensor type[imu] not suppported
I tried ignoring the above errors and continue running the program. However when moving from one point to another the rover doesn't move in a straight line but rather very strangely. I have attached a link to a video of the motion.

https://drive.google.com/open?id=1F4ZfQmBAp3rbz9X7IEO-gn158GszYUQl

Thanks

Ardupilot_gazebo with ArduPlane not working

Hello,

i am try to get this plugin running with gazebo9 and ArduPlane4.0. But when i follow the instructions it is giving me always the same mistake:
[Err] [ArduPilotPlugin.cc:682] [zephyr_delta_wing_demo] imu_sensor [zephyr_delta_wing_demo::zephyr_delta_wing::zephyr/imu_link::imu_sensor] not found, abort ArduPilot plugin. What is the problem here? Am i the only one? With ArduCopter and the iris model it is working fine, but i need ArduPlane.

Iris gimbal mount

Hello,

In the model 'iris with standoffs demo' sdf file, gimbal model should included as:
0 -0.01 0.070 1.57 0 1.57 and not as 0 -0.01 0.070 1.57 0 -1.57. Otherwise the
frames of the camera are in a contrary way with respect of the head of the drone.

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 khancyr's plugin.

Error Using ArduPilotPlugin Iris URDF

I am currently trying to convert the Iris model.sdf to an urdf so that I can get RViz depth cloud visualizations when I add a depth camera. I was able to successfully convert the model.sdf to and urdf to get the correct collisions, visuals and inertias.
image

However I'm having trouble with the ardupilot plugin. I am able to establish a connection but sending takeoff commands does not work. The command is acknowledge but nothing happens in Gazebo.
image

This the current urdf:
model.txt

Failed on retrieving camera data from gazebo to ros

First of all it's more of a question on development instead of an issue. I am sorry if misplaced my question here as I think this is the closest I can get to source for asking this.

I was trying to retrieve the image data on iris quad copter so I can process it in ROS and return the command through mavros for simulation in gazebo. The topic seems to be publishing in gazebo topic but not in rostopic. I would think that the image topic would magically appear in rostopic so I can used it directly with ROS but it doesn't. On the ardupilot doc it is stated that I need ros_gazebo_camera package however I couldn't find it anywhere.

I try to use gazebo_ros_camera plugin by compiling it and add it to .world file but no luck. I haven't try to dig in much deeper as I am an absolute beginner in gazebo plugin.
image
The closes I can get is to manually grab the gazebo topic data and try to convert it to cv matrix but it's not really effective and laggy.

#include <gazebo/transport/transport.hh>
#include <gazebo/msgs/msgs.hh>
#include <gazebo/gazebo_client.hh>

#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>

#include <iostream>

/////////////////////////////////////////////////
// Function is called everytime a message is received.

    int width;
    int height;
    char *data;
    bool execute_once = false;
    cv::Mat A;

void cb(ConstImageStampedPtr &msg)
{
  if (execute_once == false){
    width = (int) msg->image().width();
    height = (int) msg->image().height();
    //+1 for null terminate
    execute_once = true;
  }

    data = new char[msg->image().data().length() + 1];
    memcpy(data, msg->image().data().c_str(), msg->image().data().length());
    cv::Mat image(height, width, CV_8UC3, data);
    cv::resize(image, A, cv::Size(320, 240), 0, 0, cv::INTER_AREA);


    cv::imshow("camera", A);
    cv::waitKey(1);
    delete data;  // DO NOT FORGET TO DELETE THIS, 
                  // ELSE GAZEBO WILL TAKE ALL YOUR MEMORY
}

/////////////////////////////////////////////////
int main(int _argc, char **_argv)
{
  // Load gazebo
  gazebo::client::setup(_argc, _argv);

  // Create our node for communication
  gazebo::transport::NodePtr node(new gazebo::transport::Node());
  node->Init();

  // Listen to Gazebo world_stats topic
  gazebo::transport::SubscriberPtr sub = node->Subscribe("~/iris_demo/iris_demo/gimbal_small_2d/tilt_link/camera/image", cb);

  // Busy wait loop...replace with your own code as needed.
  while (true)
    gazebo::common::Time::MSleep(10);

  // Make sure to shut everything down.
  gazebo::client::shutdown();
}

I also found this repository that has plugin to publish the camera data designed for ardupilot iris but it seems to be outdated as the last push has been 4 years ago and it seems that some files are missing when I try to compile it. Is there any work around so I can get the image data on rostopic? Any help would be much appreciated. Thank you

Boat simulation in ardupilot SITL with gazebo

Since model or world for boat is not available in this directory. I have the required model and world but don't know where to copy it ardupilot_gazebo and then how to run it in a way such that SITL movements are reflected in gazebo. I am quite new to this and would really appreciate any help possible.

First Command :
sim_vehicle.py -v APMrover2 -f sailboat -m --mav10 --map --console

Problem with setting up Gazebo 9 with SITL and Ardurover

Hi,
While starting Sitl for APMrover2 with a world file in gazebo 9 , The rover starts moving in a specific direction even without setting up any script file. I'm only using the file, sim_vehicle.py to start the simulation.

Could you tell me what is causing this issue? When I set the mass of the rover close to zero, it moves along one of the horizontal axes.

GPS Glitch APM: EKF variance

link 1 down
APM: Calibrating barometer
link 1 OK
online system 1
Mode STABILIZE
APM: Barometer 1 calibration complete
Init Gyro*APM: ArduCopter V3.7.0-dev (5ffb8bb5)
APM: da48596a14e544a1a480f59eb25918ae
APM: Frame: QUAD
**

Ready to FLY APM: GPS 1: detected as u-blox at 115200 baud
APM: EKF3 waiting for GPS config data
APM: EKF3 IMU0 buffers, IMU=11, OBS=4, OF=10, dt=0.0120
APM: EKF3 IMU1 buffers, IMU=11, OBS=4, OF=10, dt=0.0120
APM: EKF3 IMU0 initialised
APM: EKF3 IMU1 initialised
APM: EKF3 IMU1 initial yaw alignment complete
APM: EKF3 IMU0 initial yaw alignment complete
APM: EKF3 IMU1 tilt alignment complete
APM: EKF3 IMU0 tilt alignment complete
APM: ArduCopter V3.7.0-dev (5ffb8bb5)
APM: da48596a14e544a1a480f59eb25918ae
APM: Frame: QUAD
Got MAVLink msg: COMMAND_ACK {command : 520, result : 0}
APM: EKF3 IMU0 Origin set to GPS
APM: EKF3 IMU1 Origin set to GPS
Flight battery 100 percent
APM: EKF3 IMU0 is using GPS
APM: EKF3 IMU1 is using GPS
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
APM: Arming motors
Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}
ARMED
Mode GUIDED
Arming checks disabled
Got MAVLink msg: COMMAND_ACK {command : 22, result : 0}
APM: EKF3 IMU0 in-flight yaw alignment complete
APM: EKF3 IMU1 in-flight yaw alignment complete
Got MAVLink msg: COMMAND_ACK {command : 178, result : 0}
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 0, type : 0}
height 10
APM: EKF variance
Mode LAND
APM: GPS Glitch
APM: GPS Glitch cleared

Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 0, type : 1}
Got MAVLink msg: COMMAND_ACK {command : 178, result : 0}
APM: GPS Glitch
height 0
APM: Crash: Disarming
APM: Disarming motors
DISARMED
Flight battery 90 percent
APM: GPS Glitch cleared
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
Mode RTL

can you tell me why GPS Glitch

commonder is

On 1st Terminal(Launch Ardupilot SITL)
sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 --map --console -I0

On 2nd Terminal(Launch Gazebo with demo 3DR Iris model)
gazebo --verbose iris_ardupilot.world

Link 1 Down

When I try to run ardupilot SITL with gazebo9 using zephyr plane get a console message link 1 down. I can run SITL normally without gazebo9 using plane. Not sure what is wrong.

Multi-Vehicle Simulation (iris and zephyr)

Hello Dear @SwiftGust
I want to simulate an iris and a zephyr in the same world and control them with ardupilot flight-stack. So I copied the iris model into zephyr demo world. After that in two separated clone of ardupilot I ran bellow commands:

sim_vehicle.py -v ArduPlane -f gazebo-zephyr -m --mav10 --console -I0
sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 --console -I1

then I ran the gazebo with the changed world file, but the the iris quadrotor can't connect to it's SITL instance. In iris console, the message "link 1 down" is printed and in the terminal where gazebo is running, bellow line is printed:

[Err] [ArduPilotPlugin.cc:962] [iris] failed to bind with 127.0.0.1:9002 aborting plugin.

so could you please help me to find out where I is my fault and how I can connect each UAV to its SITL simulation?

Ardupilot plugin aborted with ArduPlane

I am getting the next issues when following the instructions to run the simulation of ArduPlane in Gazebo:

[Wrn] [ArduPilotPlugin.cc:741] [zephyr_delta_wing_demo] imu_sensor scoped name [zephyr_delta_wing_demo::zephyr_delta_wing::zephyr/imu_link::imu_sensor] not found, trying unscoped name.

[Err] [ArduPilotPlugin.cc:753] [zephyr_delta_wing_demo] imu_sensor [zephyr_delta_wing_demo::zephyr_delta_wing::zephyr/imu_link::imu_sensor] not found, abort ArduPilot plugin.

Failed to Bind

When trying to open iris_autopilot.world I get the error failed to bind with 127.0.0.1:9002 aborting plugin. Not sure what the issue is.

Terminal output

me@computer:~/Documents/ardupilot/ardupilot_gazebo/worlds$ gazebo --verbose iris_ardupilot.world
Gazebo multi-robot simulator, version 9.19.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

Gazebo multi-robot simulator, version 9.19.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: my_ip_address
[Msg] Publicized address: my_ip_address
Warning [parser.cc:759] XML Attribute[xmlns:xacro] in element[sdf] not defined in SDF, ignoring.
[Msg] Loading world file [/home/jonathan/Documents/ardupilot/ardupilot_gazebo/worlds/iris_ardupilot.world]
[Msg] [ArduPilotPlugin] Model :iris
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::base_link
[Msg] [ArduPilotPlugin] Model :    base_link_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/ground_truth/odometry_sensorgt_link
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/imu_link
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_0
[Msg] [ArduPilotPlugin] Model :    rotor_0_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_1
[Msg] [ArduPilotPlugin] Model :    rotor_1_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_2
[Msg] [ArduPilotPlugin] Model :    rotor_2_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_3
[Msg] [ArduPilotPlugin] Model :    rotor_3_collision
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::gimbal_small_2d::base_link
[Msg] [ArduPilotPlugin] Model :    base_col
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::gimbal_small_2d::tilt_link
[Msg] [ArduPilotPlugin] Model :    tilt_col
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :    camera_col
[Msg] [ArduPilotPlugin] Model :      
[Msg] [ArduPilotPlugin] Model :  iris_demo::cam_link
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/ground_truth/odometry_sensorgt_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::iris/imu_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_0_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_1_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_2_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris::rotor_3_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::gimbal_small_2d::tilt_joint
[Msg] [ArduPilotPlugin] Model :  iris_demo::iris_gimbal_mount
[Msg] [ArduPilotPlugin] Model :  iris_demo::camera_mount
[Err] [ArduPilotPlugin.cc:962] [iris] failed to bind with 127.0.0.1:9002 aborting plugin.
[Wrn] [Publisher.cc:185] Queue limit reached for topic /gazebo/default/pose/local/info, deleting message. This warning is printed only once.

Installing the Environment with Gazebo 9

Hi.
At the make -j4 command i get the following error:

Scanning dependencies of target ArduCopterIRLockPlugin
Scanning dependencies of target ArduCopterPlugin
Scanning dependencies of target ArduPilotPlugin
[ 16%] Building CXX object CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o
[ 33%] Building CXX object CMakeFiles/ArduCopterPlugin.dir/src/ArduCopterPlugin.cc.o
[ 50%] Building CXX object CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc: In member function ‘void gazebo::ArduPilotPlugin::OnUpdate()’:
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc:914:39: error: ‘class gazebo::physics::World’ has no member named ‘GetSimTime’; did you mean ‘SetSimTime’?
     this->dataPtr->model->GetWorld()->GetSimTime();
                                       ^~~~~~~~~~
                                       SetSimTime
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc: In member function ‘void gazebo::ArduPilotPlugin::ApplyMotorForces(double)’:
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc:999:62: error: ‘class gazebo::physics::Joint’ has no member named ‘GetAngle’; did you mean ‘GetChild’?
         const double pos = this->dataPtr->controls[i].joint->GetAngle(0).Radian();
                                                              ^~~~~~~~
                                                              GetChild
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc: In member function ‘void gazebo::ArduPilotPlugin::SendState() const’:
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc:1195:53: error: ‘class gazebo::physics::World’ has no member named ‘GetSimTime’; did you mean ‘SetSimTime’?
   pkt.timestamp = this->dataPtr->model->GetWorld()->GetSimTime().Double();
                                                     ^~~~~~~~~~
                                                     SetSimTime
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc:1245:27: error: ‘class gazebo::physics::Model’ has no member named ‘GetWorldPose’; did you mean ‘SetWorldPose’?
     this->dataPtr->model->GetWorldPose().Ign();
                           ^~~~~~~~~~~~
                           SetWorldPose
/home/m/ardupilot_gazebo/src/ArduPilotPlugin.cc:1278:38: error: ‘class gazebo::physics::Link’ has no member named ‘GetWorldLinearVel’; did you mean ‘WorldLinearVel’?
     this->dataPtr->model->GetLink()->GetWorldLinearVel().Ign();
                                      ^~~~~~~~~~~~~~~~~
                                      WorldLinearVel
/home/m/ardupilot_gazebo/src/ArduCopterPlugin.cc: In member function ‘void gazebo::ArduCopterPlugin::OnUpdate()’:
/home/m/ardupilot_gazebo/src/ArduCopterPlugin.cc:565:68: error: ‘class gazebo::physics::World’ has no member named ‘GetSimTime’; did you mean ‘SetSimTime’?
   gazebo::common::Time curTime = this->dataPtr->model->GetWorld()->GetSimTime();
                                                                    ^~~~~~~~~~
                                                                    SetSimTime
/home/m/ardupilot_gazebo/src/ArduCopterPlugin.cc: In member function ‘void gazebo::ArduCopterPlugin::SendState() const’:
/home/m/ardupilot_gazebo/src/ArduCopterPlugin.cc:752:53: error: ‘class gazebo::physics::World’ has no member named ‘GetSimTime’; did you mean ‘SetSimTime’?
   pkt.timestamp = this->dataPtr->model->GetWorld()->GetSimTime().Double();
                                                     ^~~~~~~~~~
                                                     SetSimTime
/home/m/ardupilot_gazebo/src/ArduCopterPlugin.cc:802:27: error: ‘class gazebo::physics::Model’ has no member named ‘GetWorldPose’; did you mean ‘SetWorldPose’?
     this->dataPtr->model->GetWorldPose().Ign();
                           ^~~~~~~~~~~~
                           SetWorldPose
/home/m/ardupilot_gazebo/src/ArduCopterPlugin.cc:833:38: error: ‘class gazebo::physics::Link’ has no member named ‘GetWorldLinearVel’; did you mean ‘WorldLinearVel’?
     this->dataPtr->model->GetLink()->GetWorldLinearVel().Ign();
                                      ^~~~~~~~~~~~~~~~~
                                      WorldLinearVel
/home/m/ardupilot_gazebo/src/ArduCopterIRLockPlugin.cc: In member function ‘virtual void gazebo::ArduCopterIRLockPlugin::OnNewFrame(const unsigned char*, unsigned int, unsigned int, unsigned int, const string&)’:
/home/m/ardupilot_gazebo/src/ArduCopterIRLockPlugin.cc:237:14: error: ‘using element_type = class gazebo::rendering::Visual {aka class gazebo::rendering::Visual}’ has no member named ‘GetWorldPose’; did you mean ‘SetWorldPose’?
         vis->GetWorldPose().pos.Ign(), camera);
              ^~~~~~~~~~~~
              SetWorldPose
/home/m/ardupilot_gazebo/src/ArduCopterIRLockPlugin.cc:262:26: error: ‘using element_type = class gazebo::rendering::Visual {aka class gazebo::rendering::Visual}’ has no member named ‘GetName’; did you mean ‘SetName’?
       this->Publish(vis->GetName(), pt.X(), pt.Y());
                          ^~~~~~~
                          SetName
CMakeFiles/ArduPilotPlugin.dir/build.make:62: recipe for target 'CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o' failed
make[2]: *** [CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o] Error 1
CMakeFiles/Makefile2:67: recipe for target 'CMakeFiles/ArduPilotPlugin.dir/all' failed
make[1]: *** [CMakeFiles/ArduPilotPlugin.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
CMakeFiles/ArduCopterPlugin.dir/build.make:62: recipe for target 'CMakeFiles/ArduCopterPlugin.dir/src/ArduCopterPlugin.cc.o' failed
make[2]: *** [CMakeFiles/ArduCopterPlugin.dir/src/ArduCopterPlugin.cc.o] Error 1
CMakeFiles/Makefile2:141: recipe for target 'CMakeFiles/ArduCopterPlugin.dir/all' failed
make[1]: *** [CMakeFiles/ArduCopterPlugin.dir/all] Error 2
CMakeFiles/ArduCopterIRLockPlugin.dir/build.make:62: recipe for target 'CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o' failed
make[2]: *** [CMakeFiles/ArduCopterIRLockPlugin.dir/src/ArduCopterIRLockPlugin.cc.o] Error 1
CMakeFiles/Makefile2:104: recipe for target 'CMakeFiles/ArduCopterIRLockPlugin.dir/all' failed
make[1]: *** [CMakeFiles/ArduCopterIRLockPlugin.dir/all] Error 2
Makefile:129: recipe for target 'all' failed
make: *** [all] Error 2

How can i solve this?
Thanks...

Request detail on how to get LiftDragPlugin values

Hello, I'm attempting to build a gazebo model using the Typhoon as an example.

My model has 7Kg of mass in total (oposite of the 2Kg from the Typhoon), so I cant get my model to fly.

I have narrowed it down to the liftDragPlugin usage.

Any idea how I can get the values for my UAV? The propeller is an 18 inch.

NOTE: I have already read the tutorial on gazebo sim for the Lift Drag plugin but with no result (http://gazebosim.org/tutorials?tut=aerodynamics&cat=physics)

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.