All Projects → gsilano → Crazys

gsilano / Crazys

Licence: apache-2.0
CrazyS is an extension of the ROS package RotorS, aimed to modeling, developing and integrating the Crazyflie 2.0

Labels

Projects that are alternatives of or similar to Crazys

Rostensorflow
TensorFlow ImageNet demo using ROS sensor_msgs/Image
Stars: ✭ 59 (-20.27%)
Mutual labels:  ros
Mrs uav system
The entry point to the MRS UAV system.
Stars: ✭ 64 (-13.51%)
Mutual labels:  ros
Sweep Ros
Scanse Sweep ROS Driver and Node
Stars: ✭ 67 (-9.46%)
Mutual labels:  ros
Robots
Collection of quadrupedal robots configured to work in CHAMP development framework
Stars: ✭ 59 (-20.27%)
Mutual labels:  ros
Drivebot
tensorflow deep RL for driving a rover around
Stars: ✭ 62 (-16.22%)
Mutual labels:  ros
Get Started Ros2
書籍「ROS2ではじめよう 次世代ロボットプログラミング」オンラインリソース
Stars: ✭ 65 (-12.16%)
Mutual labels:  ros
Eyantra drone
Metapackage to control the edrone via services and topics -https://www.youtube.com/watch?v=M-RYyMyRl9g
Stars: ✭ 57 (-22.97%)
Mutual labels:  ros
Icse Seip 2020 Replication Package
Replication package of the paper titled "How do you Architect your Robots? State of the Practice and Guidelines for ROS-based Systems" published at ICSE-SEIP 2020
Stars: ✭ 68 (-8.11%)
Mutual labels:  ros
Eskf
ROS Error-State Kalman Filter based on PX4/ecl. Performs GPS/Magnetometer/Vision Pose/Optical Flow/RangeFinder fusion with IMU
Stars: ✭ 63 (-14.86%)
Mutual labels:  ros
Autonomous driving
Ros package for basic autonomous lane tracking and object detection
Stars: ✭ 67 (-9.46%)
Mutual labels:  ros
Ros2 java
Java and Android bindings for ROS2
Stars: ✭ 60 (-18.92%)
Mutual labels:  ros
Hrim
An information model for robot hardware. Facilitates interoperability across modules from different robot manufacturers. Built around ROS 2.0
Stars: ✭ 61 (-17.57%)
Mutual labels:  ros
Lego Loam
LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain
Stars: ✭ 1,138 (+1437.84%)
Mutual labels:  ros
Darknet ros
YOLO ROS: Real-Time Object Detection for ROS
Stars: ✭ 1,101 (+1387.84%)
Mutual labels:  ros
Panther
🐆 Panther is an Open Robotic AGV platform ROS based for Outdoor and Indoor enviroments.
Stars: ✭ 67 (-9.46%)
Mutual labels:  ros
Realm Sync Samples
Code samples showing how to work with Realm Sync
Stars: ✭ 58 (-21.62%)
Mutual labels:  ros
Loam velodyne
Laser Odometry and Mapping (Loam) is a realtime method for state estimation and mapping using a 3D lidar.
Stars: ✭ 1,135 (+1433.78%)
Mutual labels:  ros
Docker
Docker containers for OpenCog - Robot Operating System (ROS)
Stars: ✭ 72 (-2.7%)
Mutual labels:  ros
Didi challenge ros
Roslaunch to visualize a rosbag file from Udacity (DiDi Challenge)
Stars: ✭ 69 (-6.76%)
Mutual labels:  ros
Grid map
Universal grid map library for mobile robotic mapping
Stars: ✭ 1,135 (+1433.78%)
Mutual labels:  ros

Build Status License PRs Welcome first-timers-only

CrazyS

CrazyS is an extension of the ROS package RotorS, aimed to modeling, developing and integrating the Crazyflie 2.0 nano-quadcopter in the physics based simulation environment Gazebo. The contribution can be also considered as a reference guide for expanding the RotorS functionalities in the Unmanned Aerial Vehicles (UAVs) field, by facilitating the integration of new aircraft.

Such simulation platform allows to understand quickly the behavior of the flight control system by comparing and evaluating different indoor and outdoor scenarios, with a details level quite close to reality. The proposed extension expands RotorS capabilities by considering the Crazyflie 2.0 physical model and its flight control system, as well (the 2018.01.1 firmware release).

A simple case study is considered (crazyflie2_hovering_example.launch) in order to show how the package works and the validity of the employed dynamical model together the control architecture of the quadrotor.

The code is released under Apache license, thus making it available for scientific and educational activities.

The platform was developed using Ubuntu 16.04 and the Kinetic Kame version of ROS, but it is also fully compatible with Ubuntu 18.04 and the Melodic Morenia distribution of ROS. Although backwards compatibility is guarantee, i.e., the platform is fully compatible with Indigo Igloo version of ROS and Ubuntu 14.04, such configuration is not recommended since the ROS support is expected to be closed in April 2019.

Below we provide the instructions necessary for getting started. See CrazyS' wiki for more instructions and examples.

f you are using this simulator for research purposes especially for your publication, please take a look at the Publications page. The page contains the core papers and all related works (using the platform).

To facilitate the use of the repository, in addition to the installation instructions, the following are links to two virtual machines created using Oracle VirtualBox.

Ubuntu 16.04 with ROS Kinetic and Gazebo 7

Ubuntu 16.04 with ROS Kinetic and Gazebo 9

USER: user
PASS: password
Keyboard layout: Italian
Language: English

Installation Instructions - Ubuntu 18.04 with ROS Melodic and Gazebo 9

To use the code developed and stored in this repository some preliminary actions are needed. They are listed below.

  1. Install and initialize ROS Melodic desktop full, additional ROS packages, catkin-tools, and wstool:
$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
$ sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
$ sudo apt update
$ sudo apt install ros-melodic-desktop-full ros-melodic-joy ros-melodic-octomap-ros ros-melodic-mavlink ros-melodic-octomap-mapping
$ sudo apt install python-wstool python-catkin-tools protobuf-compiler libgoogle-glog-dev ros-melodic-control-toolbox
$ sudo rosdep init
$ rosdep update
$ echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
$ source ~/.bashrc
$ sudo apt install python-rosinstall python-rosinstall-generator build-essential
  1. If you don't have ROS workspace yet you can do so by
$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace  # initialize your catkin workspace
$ cd ~/catkin_ws/
$ catkin init
$ cd ~/catkin_ws/src
$ git clone -b dev/ros-melodic https://github.com/gsilano/CrazyS.git
$ git clone -b med18_gazebo9 https://github.com/gsilano/mav_comm.git
$ cd ~/catkin_ws
  1. Build your workspace with python_catkin_tools (therefore you need python_catkin_tools)
$ rosdep install --from-paths src -i
$ sudo apt install ros-melodic-rqt-rotors ros-melodic-rotors-comm ros-melodic-mav-msgs ros-melodic-rotors-control
$ sudo apt install ros-melodic-rotors-gazebo ros-melodic-rotors-evaluation ros-melodic-rotors-joy-interface
$ sudo apt install ros-melodic-rotors-gazebo-plugins ros-melodic-mav-planning-msgs ros-melodic-rotors-description ros-melodic-rotors-hil-interface
$ rosdep update
$ catkin build
  1. Add sourcing to your .bashrc file
$ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
$ source ~/.bashrc
  1. Update the pre-installed Gazebo version. This fix the issue with the error in REST request for accessing api.ignition.org
$ sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
$ wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
$ sudo apt update
$ sudo apt install gazebo9 gazebo9-* ros-melodic-gazebo-*
$ sudo apt upgrade

In the event that the simulation does not start, the problem may be related to Gazebo and missing packages. Therefore, run the following commands. More details are reported in #25.

$ sudo apt-get remove ros-melodic-gazebo* gazebo*
$ sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
$ wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
$ sudo apt-get update
$ sudo apt-get install gazebo9 gazebo9-* ros-melodic-gazebo-*
$ sudo apt upgrade

Installation Instructions - Ubuntu 16.04 with ROS Kinetic and Gazebo 7

  1. Install and initialize ROS kinetic desktop full, additional ROS packages, catkin-tools, and wstool:
$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
$ sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
$ sudo apt-get update
$ sudo apt-get install ros-kinetic-desktop-full ros-kinetic-joy ros-kinetic-octomap-ros ros-kinetic-mavlink python-catkin-tools protobuf-compiler libgoogle-glog-dev ros-kinetic-control-toolbox ros-kinetic-octomap-mapping
$ sudo rosdep init
$ rosdep update
$ echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
$ source ~/.bashrc
$ sudo apt-get install python-rosinstall python-rosinstall-generator python-wstool build-essential
  1. If you don't have ROS workspace yet you can do so by
$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace  # initialize your catkin workspace
$ cd ~/catkin_ws/
$ catkin init
$ cd ~/catkin_ws/src
$ git clone https://github.com/gsilano/CrazyS.git
$ git clone -b crazys https://github.com/gsilano/mav_comm.git
$ cd ~/catkin_ws
$ rosdep install --from-paths src -i
$ catkin build

Note On OS X you need to install yaml-cpp using Homebrew brew install yaml-cpp.

  1. Build your workspace with python_catkin_tools (therefore you need python_catkin_tools)
$ cd ~/catkin_ws/
$ catkin build
  1. Add sourcing to your .bashrc file
$ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
$ source ~/.bashrc

Installation Instructions - Ubuntu 16.04 with ROS Kinetic and Gazebo 9

To use the code developed and stored in this repository with ROS Kinetic and Gazebo 9, first follow what is reported in the previous section. Then, use the instruction below.

  1. Remove Gazebo 7 and all related packages, and then install Gazebo 9:
$ sudo apt-get remove ros-kinetic-gazebo* gazebo*
$ sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
$ wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
$ sudo apt-get update
$ sudo apt-get install gazebo9 gazebo9-* ros-kinetic-gazebo9-*
$ sudo apt upgrade

Note Remove ros-kinetic-gazebo9-* from the command sudo apt-get install gazebo9 gazebo9-* ros-kinetic-gazebo9-* if fetch problems should appear during the installation.

  1. Additional packages are required to build the package.
$ sudo apt-get install libeigen3-dev ros-kinetic-image-view ros-kinetic-parrot-arsdk libprotobuf-dev libprotoc-dev ros-kinetic-joy-teleop ros-kinetic-nav-msgs ros-kinetic-mav-msgs libyaml-cpp-dev ros-kinetic-nodelet ros-kinetic-mav-planning-msgs ros-kinetic-urdf ros-kinetic-image-transport ros-kinetic-roslint ros-kinetic-angles ros-kinetic-cv-bridge ros-kinetic-tf2-geometry-msgs ros-kinetic-xacro ffmpeg libavcodec-dev libavformat-dev libavutil-dev libswscale-dev ros-kinetic-camera-info-manager ros-kinetic-cmake-modules ros-kinetic-gazebo-msgs ros-kinetic-mavros-msgs ros-kinetic-control-toolbox ros-kinetic-mav-msgs ros-kinetic-libmavconn ros-kinetic-mavros ros-kinetic-octomap-msgs ros-kinetic-geographic-msgs ros-kinetic-mavlink ros-kinetic-mavros-extras ros-kinetic-mav-planning-msgs ros-kinetic-joy

Note Missing packages can be found and then installed by using the command rosdep check --from-paths src into the catkin_ws folder.

  1. Make Gazebo 9 compatible with ROS Kinetic Kame
$ cd ~
$ mkdir -p ros-kinetic-gazebo9-pkgs
$ cd ros-kinetic-gazebo9-pkgs
$ git clone -b feature/ros-kinetic-gazebo9-pkgs https://github.com/gsilano/BebopS.git
$ cd BebopS
$ chmod 777 gazebo9.sh
$ ./gazebo9.sh
$ cd ~
$ sudo rm -rf ros-kinetic-gazebo9-pkgs # delete the folder after the installation
  1. Clean the workspace and compile again the code
$ cd ~/catkin_ws
$ catkin clean # digit y when required
$ cd ~/catkin_ws/src/CrazyS
$ git checkout dev/gazebo9
$ cd ~/catkin_ws/src/mav_comm
$ git checkout med18_gazebo9
$ cd ~/catkin_ws
$ catkin build
$ source ~/.bashrc

Note In case the ERROR[rotors_gazebo_plugins] error is displayed, run the following commands

$ sudo apt-get install ros-kinetic-gazebo9-plugins
$ sudo apt-get install apt ros-kinetic-gazebo9-ros
$ sudo apt-get install apt ros-kinetic-gazebo9-dev

This guide can be used a basis for fixing what has been discussed in ethz-asl/rotors_simulator#506.

Installation Instructions - Ubuntu 14.04 with ROS Indigo

  1. Install and initialize ROS indigo desktop full, additional ROS packages, catkin-tools, and wstool:
$ sudo sh -c ’echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list’
$ sudo apt-key adv --keyserver hkp://ha.pool.skskeyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116
$ sudo apt-get update
$ sudo apt-get install ros-indigo-desktop-full ros-indigo-joy ros-indigo-octomap-ros python-wstool python-catkin-tools protobuf compiler libgoogle-glog-dev
$ sudo rosdep init
$ rosdep update
$ echo "source /opt/ros/indigo/setup.bash" >> ~/.bashrc
$ source ~/.bashrc
$ sudo apt-get install python-rosinstall
  1. If you don't have ROS workspace yet you can do so by
$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace  # initialize your catkin workspace
$ catkin init

Note for setups with multiple workspaces please refer to the official documentation by replacing rosws by wstool.

  1. Get the simulator and additional dependencies
$ cd ~/catkin_ws/src
$ git clone https://github.com/gsilano/CrazyS.git
$ git clone -b crazys https://github.com/gsilano/mav_comm.git
$ cd ~/catkin_ws
$ rosdep install --from-paths src -i

Note On OS X you need to install yaml-cpp using Homebrew brew install yaml-cpp.

Note if you want to use wstool you can replace the above commands with console wstool set --git local_repo_name [email protected]:organization/repo_name.git Note if you want to build and use the gazebo_mavlink_interface plugin you have to get MAVROS as an additional dependency from link below. Follow the installation instructions provided there and build all of its packages prior to building the rest of your workspace. https://github.com/mavlink/mavros

  1. Build your workspace with python_catkin_tools (therefore you need python_catkin_tools)
$ cd ~/catkin_ws/
$ catkin init  # If you haven't done this before.
$ catkin build

Note if you are getting errors related to "future" package, you may need python future: console sudo apt-get install python-pip pip install --upgrade pip pip install future

  1. Add sourcing to your .bashrc file
$ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
$ source ~/.bashrc

Basic Usage

Launching the simulation is quite simple, so as customizing it: it is enough to run in a terminal the command

$ roslaunch rotors_gazebo crazyflie2_hovering_example.launch

Note The first run of gazebo might take considerably long, as it will download some models from an online database. To avoid any problems when starting the simulation for the first time, you may run the gazebo command in the terminal line.

By default the state estimator is disabled since on-board Crazyflie's sensors are replaced by the odometry one. For running the simulation by taking into account the Crazyflie's IMU and the complementary filter, it is enough to give a command that turns on the flag enable state estimator:

$ roslaunch rotors_gazebo crazyflie2_hovering_example.launch enable_state_estimator:=true

The visual outcome will see the nano-quadcopter taking off after 5s (time after which the hovering example node publishes the trajectory to follow) and flying one meter above the ground, at the same time keeping near to zero the position components along x and y-axis.

The whole process is the following: the desired trajectory coordinates (x_r, y_r, z_r and \psi_r) are published by the hovering_example node on the topic command/trajectory, to whom the position_controller node (i.e., the Crazyflie controller) is subscribed. The drone state (odometry_sensor1/odometry topic) and the references are used to run the control strategy designed for the position tracking. The outputs of the control algorithm consist into the actuation commands (\omega_1, \omega_2, \omega_3 and \omega_4) sent to Gazebo (command/motor_speed) for the physical simulation and the corresponding graphical rendering, so to visually update the aircraft position and orientation. When the state estimator is turned off, the drone orientation (\phi_k, \theta_k and \psi_k) and angular velocities (p_k, q_k and r_k) published on the topic odometry are replaced by the ideal values coming from the odometry sensor.

There are some basic launch files where you can load the different multicopters with additional sensors. They can all be found in ~/catkin_ws/src/CrazyS/rotors_gazebo/launch. Such scenarios are better explained in the RotorS repository.

The world_name argument looks for a .world file with a corresponding name in ~/catkin_ws/src/CrazyS/rotors_gazebo/worlds. By default, all launch files, with the exception of those that have the world name explicitly included in the file name, use the empty world described in basic.world.

Using the csvFilesStoring variable is possible to enable (true) or disable (false) the data storage. The log files are saved in the home directory (the path can be easily changed modifying the position_controller.cpp file). The recording time can be set via the csvFilesStoringTime while the user account can be set via the user_account variable. Of course, the log features can be used with and without the complementary filter.

$ roslaunch rotors_gazebo crazyflie2_hovering_example.launch csvFilesStoring:=true

An alternative controller is available on the repository. For running the simulation by using the Internal Model Control as described in #27, #28, #29, and #48 simply run

$ roslaunch rotors_gazebo crazyflie2_internal_model_controller.launch

or

$ roslaunch rotors_gazebo crazyflie2_internal_model_controller_vi_sensor.launch

while a simple swarm example is available at

$ roslaunch rotors_gazebo crazyflie2_swarm_hovering_example.launch

Note There is also a draft of the Mellinger's controller implementation in the package. This is a NOT WORKING example. As soon as the problems are resolved, a working version will be made available.

The package also provides a launch file for piloting the Crazyflie using a PC joystick. To run the simulation simple copy and paste the command in the following in a terminal window

$ roslaunch rotors_gazebo crazyflie2_with_joy.launch

Gazebo Version

At a minimum, Gazebo v2.x is required (which is installed by default with ROS Indigo). However, it is recommended to install at least Gazebo v5.x for full functionality, although the platform is fully compatible with the Gazebo 9. Before running the script, consider the following limitations:

  1. iris.sdf can only be generated with Gazebo >= v3.0, as it requires use of the gz sdf ... tool. If this requirement is not met, you will not be able to use the Iris MAV in any of the simulations.
  2. The Gazebo plugins GazeboGeotaggedImagesPlugin, LidarPlugin and the LiftDragPlugin all require Gazebo >= v5.0, and will not be built if this requirement is not met.

Bugs & Feature Requests

Please report bugs and request features by using the Issue Tracker. Furthermore, please see the Contributing.md file if you plan to help us to improve CrazyS features.

YouTube videos

In this section a video providing the effectiveness of the platform and how it works is reported. Further videos can be found in the related YouTube channel. Have fun! :)

CrazyS, an extension of the ROS package RotorS aimed to modeling, developing and integrating the Crazyflie 2.0 nano-quadcopter

Note that the project description data, including the texts, logos, images, and/or trademarks, for each open source project belongs to its rightful owner. If you wish to add or remove any projects, please contact us at [email protected].