Skip to content
This repository has been archived by the owner on Aug 5, 2024. It is now read-only.

Added Sikorsky X-2 Coaxial Compound Helicopter Model & More... #6

Open
wants to merge 62 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
62 commits
Select commit Hold shift + click to select a range
14e3e0e
Add Support for ArduCopter
SwiftGust Apr 20, 2017
2f5c8ca
Update README.md
SwiftGust Apr 20, 2017
2874fcc
Add Example Models & Worlds
SwiftGust Apr 21, 2017
4ae3d2e
Merge pull request #1 from SwiftGust/swiftgust-patch
SwiftGust Apr 21, 2017
b96a330
Missing ArduCopter Plugin in the CMakeLists fix
SwiftGust Apr 21, 2017
9991bd0
Update CMakeLists.txt
SwiftGust Apr 21, 2017
1a4aeb0
Update model.sdf
SwiftGust Apr 21, 2017
fac18f3
Merge branch 'master' of https://github.com/swiftgust/ardupilot_gazebo
SwiftGust Apr 21, 2017
3a22295
Update README.md
SwiftGust Apr 21, 2017
d2de597
Update README.md
SwiftGust Apr 21, 2017
48e49df
Update README.md
SwiftGust Apr 21, 2017
44b8f23
Update README.md
SwiftGust Apr 21, 2017
db2a8b4
Update README.md
SwiftGust Apr 21, 2017
39e7a6e
Create License.md
SwiftGust Apr 24, 2017
e8cc7ab
Delete License.md
SwiftGust Apr 24, 2017
25a65ad
Camera Position & Model Glitch fix
SwiftGust Apr 24, 2017
333dc6a
Update delta_wing.sdf
SwiftGust Apr 24, 2017
b8bc328
Update README.md
SwiftGust Apr 25, 2017
d07b8a8
Update README.md
SwiftGust Apr 25, 2017
7a63db3
Update README.md
SwiftGust Apr 25, 2017
c676f63
Update README.md
SwiftGust Apr 27, 2017
7722703
add ZED stereovision camera
SwiftGust May 1, 2017
d2631cf
Update README.md
SwiftGust May 5, 2017
616f97d
Update README.md
SwiftGust May 5, 2017
5d09fb2
Added Sikorsky-X2 model and ardupilot demo world
SwiftGust May 19, 2017
781a50f
Update README.md
SwiftGust May 19, 2017
d729d53
Merge remote-tracking branch 'origin/master'
SwiftGust May 19, 2017
cda0cab
Update README.md
SwiftGust May 19, 2017
250dcde
Update README.md
SwiftGust May 22, 2017
ee22c6b
Parameter Modification
SwiftGust Feb 14, 2018
21d2b56
Parameter Modification
SwiftGust Jul 9, 2018
9f3ff95
Update README.md
SwiftGust Jul 26, 2018
4434f9f
Re-organization, addition of models and update readme
SwiftGust Nov 8, 2018
7f49a89
Re-organize, addition of models and update Readme
SwiftGust Nov 8, 2018
d7598d5
Update README.md
SwiftGust Nov 8, 2018
17e2a83
Update README.md
SwiftGust Nov 8, 2018
3c48f0a
Update README.md
SwiftGust Nov 8, 2018
e495e8f
Delete eeprom.bin
SwiftGust Nov 8, 2018
0c8f500
Delete mav.parm
SwiftGust Nov 8, 2018
fdb0e5b
Delete mav.tlog
SwiftGust Nov 8, 2018
3d3a94c
Delete mav.tlog.raw
SwiftGust Nov 8, 2018
7bf0dea
Delete .tags
SwiftGust Nov 8, 2018
bd24e1a
Compile Error Fix on IRLock Plugin
SwiftGust Nov 18, 2018
eaf45c0
Update README.md
SwiftGust Nov 25, 2018
a2cd619
Removed mercurial configuration directory
johncarl81 Jan 6, 2019
7da690d
Update README.md
SwiftGust Jan 9, 2019
ec1a3ac
Add support for Gazebo 9+
SwiftGust Jul 15, 2020
4aec440
Make standard vtol world file.
shovan777 Aug 30, 2020
ff5adb5
Remove unneeded model.
shovan777 Aug 31, 2020
ccdeb8f
Increase Cp parameter.
shovan777 Sep 1, 2020
3eee7b4
Delete unnecessary files.
shovan777 Sep 1, 2020
e711f84
Clean up for PR #27.
shovan777 Sep 2, 2020
dd958be
Merge pull request #27 from prokuranepal/vtol
SwiftGust Sep 11, 2020
982a833
Add BSD-3 License to Sikorsky X-2 model
SwiftGust Oct 21, 2020
cd39184
Delete LICENSE
SwiftGust Oct 21, 2020
4f00755
Add BSD-3 License to Sikorsky-X2 models only
SwiftGust Oct 21, 2020
cac7138
Merge pull request #10 from johncarl81/remove_hg_dir
SwiftGust Feb 3, 2021
6534024
Change incompatible type in getSDFParam call.
Mar 11, 2021
a1b2f50
Merge pull request #34 from BV-OpenSource/sdformat9.4Compatibility
SwiftGust Mar 26, 2021
5ce7980
Zephyr Flip Left & Right Elevon Channel Mapping
SwiftGust Dec 3, 2021
d07c8ee
Delete LiftDragPlugin.hh
SwiftGust Apr 22, 2022
51907b9
Delete LiftDragPlugin.cc
SwiftGust Apr 22, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
The table of contents is too big for display.
Diff view
Diff view
  •  
  •  
  •  
3 changes: 3 additions & 0 deletions .gitignore
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -95,3 +95,6 @@ cmake-build-debug

# Catkin custom files
CATKIN_IGNORE

# Ignore mercurial config directory
.hg
10 changes: 8 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ link_directories(
set (plugins_single_header
ArduPilotPlugin
ArduCopterIRLockPlugin
GimbalSmall2dPlugin
ArduCopterPlugin
# GimbalSmall2dPlugin
# WindPlugin
)

add_library(ArduCopterIRLockPlugin SHARED src/ArduCopterIRLockPlugin.cc)
Expand All @@ -48,11 +50,15 @@ target_link_libraries(ArduCopterIRLockPlugin ${GAZEBO_LIBRARIES})
add_library(ArduPilotPlugin SHARED src/ArduPilotPlugin.cc)
target_link_libraries(ArduPilotPlugin ${GAZEBO_LIBRARIES})

add_library(ArduCopterPlugin SHARED src/ArduCopterPlugin.cc)
target_link_libraries(ArduCopterPlugin ${GAZEBO_LIBRARIES})

if("${GAZEBO_VERSION}" VERSION_LESS "8.0")
add_library(GimbalSmall2dPlugin SHARED src/GimbalSmall2dPlugin.cc)
target_link_libraries(GimbalSmall2dPlugin ${GAZEBO_LIBRARIES})
install(TARGETS GimbalSmall2dPlugin DESTINATION ${GAZEBO_PLUGIN_PATH})
endif()

install(TARGETS ArduCopterIRLockPlugin DESTINATION ${GAZEBO_PLUGIN_PATH})
install(TARGETS ArduPilotPlugin DESTINATION ${GAZEBO_PLUGIN_PATH})
install(TARGETS ArduPilotPlugin DESTINATION ${GAZEBO_PLUGIN_PATH})
install(TARGETS ArduCopterPlugin DESTINATION ${GAZEBO_PLUGIN_PATH})
197 changes: 165 additions & 32 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,73 +1,206 @@
# Ardupilot Gazebo plugin
# Ardupilot Gazebo Plugin & Models
- [Ardupilot Gazebo Plugin & Models](#ardupilot-gazebo-plugin--models)
- [Requirements :](#requirements-)
- [Disclamer :](#disclamer-)
- [Repository Structure :](#repository-structure-)
- [Getting Started :](#getting-started-)
- [How to Install :](#how-to-install-)
- [HELP](#help)
- [How to Launch :](#how-to-launch-)
- [Multi-Vehicle simulation](#multi-vehicle-simulation)
- [Example](#example)
- [Troubleshooting](#troubleshooting)
- [Missing libArduPilotPlugin](#missing-libardupilotplugin)

## Requirements :
Gazebo version 7.x or 8.x
The dev branch will works on gazebo >= 9.x
Native Ubuntu Xenial(16.04 LTS) able to run full 3D graphics.

## Disclamer :
**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

## 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-kinetic-desktop-full (follow instruction here http://wiki.ros.org/kinetic/Installation/Ubuntu).
## 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
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/khancyr/ardupilot_gazebo
git clone https://github.com/SwiftGust/ardupilot_gazebo
cd ardupilot_gazebo
mkdir build
cd build
cmake ..
make -j4
sudo make install
````
DONE !
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!
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
## HELP

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

**ROVER**


launch cmd :
ROVER
On 1st Terminal(Launch ArduRover SITL)
````
sim_vehicle.py -v APMrover2 -f gazebo-rover -m --mav10 --map --console -I0
sim_vehicle.py -v APMrover2 -f gazebo-rover -m --mav10 --map --console -I1
````
COPTER
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
````
PLANE
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
````

### Missing libArduPilotPlugin.so
In case you see this message, check you have no error after sudo make install.
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. (example : cp /usr/lib/x86_64-linux-gnu/gazebo-7/plugins/libArduPilotPlugin.so /usr/lib/x86_64-linux-gnu/gazebo-7.0/plugins/ ).
I don't know why it can have path mistmatch ... but it could append if you install gazebo from sasc-gazebo-sitl .
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**

### 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>
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.
Empty file modified include/ArduCopterIRLockPlugin.hh
100755 → 100644
Empty file.
85 changes: 85 additions & 0 deletions include/ArduCopterPlugin.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
/*
* Copyright (C) 2016 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef GAZEBO_PLUGINS_ARDUCOPTERPLUGIN_HH_
#define GAZEBO_PLUGINS_ARDUCOPTERPLUGIN_HH_

#include <sdf/sdf.hh>
#include <gazebo/common/common.hh>
#include <gazebo/physics/physics.hh>


namespace gazebo
{
// Forward declare private data class
class ArduCopterSocketPrivate;
class ArduCopterPluginPrivate;

/// \brief Interface ArduCopter from ardupilot stack
/// modeled after SITL/SIM_*
///
/// The plugin requires the following parameters:
/// <rotor> rotor description block
/// id attribute rotor id
/// <vel_p_gain> velocity pid p gain
/// <vel_i_gain> velocity pid i gain
/// <vel_d_gain> velocity pid d gain
/// <vel_i_max> velocity pid max integral correction
/// <vel_i_min> velocity pid min integral correction
/// <vel_cmd_max> velocity pid max command torque
/// <vel_cmd_min> velocity pid min command torque
/// <jointName> rotor motor joint, torque applied here
/// <turningDirection> turning direction, 'cw' or 'ccw'
/// <rotorVelocitySlowdownSim> experimental, not needed
/// <imuName> scoped name for the imu sensor
/// <connectionTimeoutMaxCount> timeout before giving up on
/// controller synchronization
class GAZEBO_VISIBLE ArduCopterPlugin : public ModelPlugin
{
/// \brief Constructor.
public: ArduCopterPlugin();

/// \brief Destructor.
public: ~ArduCopterPlugin();

// Documentation Inherited.
public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);

/// \brief Update the control surfaces controllers.
/// \param[in] _info Update information provided by the server.
private: void OnUpdate();

/// \brief Update PID Joint controllers.
/// \param[in] _dt time step size since last update.
private: void ApplyMotorForces(const double _dt);

/// \brief Reset PID Joint controllers.
private: void ResetPIDs();

/// \brief Receive motor commands from ArduCopter
private: void ReceiveMotorCommand();

/// \brief Send state to ArduCopter
private: void SendState() const;

/// \brief Init ardupilot socket
private: bool InitArduCopterSockets(sdf::ElementPtr _sdf) const;

/// \brief Private data pointer.
private: std::unique_ptr<ArduCopterPluginPrivate> dataPtr;
};
}
#endif
Empty file modified include/ArduPilotPlugin.hh
100755 → 100644
Empty file.
Loading