From 6715e6c8489ed0d293d960d3dafc8009819ffb3f Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 18:45:41 +0100 Subject: [PATCH 01/18] First draft updated README.md file First draft of the update README.md file with the instructions to use the package with the Melodic distro of ROS --- README.md | 176 +++++++++++++++++++++++++++++++++++------------------- 1 file changed, 113 insertions(+), 63 deletions(-) diff --git a/README.md b/README.md index e67989c..5ebbd21 100644 --- a/README.md +++ b/README.md @@ -5,74 +5,117 @@ # BebopS -BebopS is an extension of the ROS package [RotorS](https://github.com/ethz-asl/rotors_simulator), aimed to modeling, developing and integrating the [Parrot Bebop 2](https://www.parrot.com/us/drones/parrot-bebop-2) 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 UAVs filed and for simulating in a way rather close to reality the real aircraft behavior. +BebopS is an extension of the ROS package [RotorS](https://github.com/ethz-asl/rotors_simulator), aimed to modeling, developing and integrating the [Parrot Bebop 2](https://www.parrot.com/us/drones/parrot-bebop-2) 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) filed and for simulating in a way rather close to reality the real aircraft behavior. -The repository was made for designing complex control systems for the Parrot Bebop, but it can also used for any other aircraft. Indeed, the controller implementation is a not easy process and having a complete software platform for simulating the multirotor behavior, considering also its on-board sensors, could give advantages in terms of coding and deployment of the controller software. +The repository was made for designing complex control systems for the Parrot Bebop 2, but it can also be used as a basis for any other aircraft with the aim of helping in the controller implementation. Indeed, implementing the own control algorithm is a not easy process and having a complete software platform for simulating the multirotor behavior, considering also its on-board sensors and the secondary effects, could give advantages in terms of coding and deployment of the controller software. -Moreover, the software platform allows to detect and manage instabilities of the Parrot Bebop 2 that otherwise might not arise when considering only its Matlab/Simulink simulations. Finally, implementation details synchronization, overflow or any other software realted issue, can be isolated when looking at the Matlab/Simulink platform only, but their effects can be investigated by considering the proposed repository. +Finally, the software platform allows to detect and manage instabilities of the Parrot Bebop 2 that otherwise might not arise when considering only its Matlab/Simulink simulations. Moreover, implementation details such as synchronization, overflow or any other software related issue, can be isolated when looking at the Matlab/Simulink platform only, but their effects can be investigated by considering the proposed repository. -Simple cases study are considered (`task1_world.launch` and `task2_world.launch`) in order to show how the package works and the validity of the employed dynamical model together the control architecture of the quadcopter. +Simple cases study are considered (`task1_world.launch` and `task2_world.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 has been developed by using Ubuntu 16.04 and the Kinetic Kame version of ROS. Although 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. +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 [BebopS' wiki](https://github.com/gsilano/BebopS/wiki) for more instructions and examples. -If you are using this simulator within the research for your publication, please take a look at the [Publications page](https://github.com/gsilano/BebopS/wiki/Publications). The page contains core papers and all linked works (using the platform). +If you are using this simulator for research purposes especially for your publication, please take a look at the [Publications page](https://github.com/gsilano/BebopS/wiki/Publications). The page contains the core papers and all related works (using the platform). -The authors are grateful to the [LARICS Lab](https://larics.fer.hr/larics) of the University of Zagreb that created the basis for the ROS package through the [sofware repositry](https://github.com/larics/mmuav_gazebo). In fact, the platform is an extract of the work carried out for the industrial challenge of the 26th Mediterranean Conference on Control and Automation (MED’18) in which the authors took part ([here the link](https://ieeexplore.ieee.org/document/8667511) to the conference report). +The authors are grateful to the [LARICS Lab](https://larics.fer.hr/larics), University of Zagreb, for the initial work done to make the platform compatible with the latest changes to the RotorS package. Here the link to them [sofware repositry](https://github.com/larics/mmuav_gazebo). The software platform is an extract of the work carried out for the industrial challenge of the 26th Mediterranean Conference on Control and Automation (MED’18) in which the authors took part ([here the link](https://ieeexplore.ieee.org/document/8667511) to the conference report). -Installation Instructions - Ubuntu 16.04 with ROS Kinetic +Installation Instructions - Ubuntu 18.04 with ROS Melodic --------------------------------------------------------- To use the code developed and stored in this repository some preliminary actions are needed. They are listed below. - 1. Install and initialize ROS kinetic desktop full, additional ROS packages, catkin-tools, and wstool: +1. Install and initialize ROS Melodic desktop full, additional ROS packages, catkin-tools, and wstool: + +```console +$ 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-fulll ros-melodic-joy ros-melodic-octomap-ros ros-melodic-mavlink +$ 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 python-wstool build-essential +``` +2. If you don't have ROS workspace yet you can do so by + +```console +$ 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 med18_gazebo9 https://github.com/gsilano/rotors_simulator.git +$ git clone -b med18_gazebo9 https://github.com/gsilano/mav_comm +$ git clone -b gazebo9 https://github.com/gsilano/BebopS.git +$ git clone https://github.com/AutonomyLab/bebop_autonomy.git +$ cd ~/catkin_ws +``` + +3. Build your workspace with `python_catkin_tools` (therefore you need `python_catkin_tools`) + +```console +$ rosdep install --from-paths src -i +$ catkin build +``` + +4. Add sourcing to your `.bashrc` file + +```console +$ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc +$ source ~/.bashrc +``` + +Installation Instructions - Ubuntu 16.04 with ROS Kinetic +--------------------------------------------------------- +To use the code developed and stored in this repository some preliminary actions are needed. They are listed below. + + 1. Install and initialize ROS Kinetic desktop full, additional ROS packages, catkin-tools, and wstool: + + ```console +$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main" > /etc/apt/sources.list.d/ros-latest.list' +$ wget http://packages.ros.org/ros.key -O - | sudo apt-key add - +$ sudo apt-get update +$ sudo apt-get install ros-kinetic-desktop-full ros-kinetic-joy ros-kinetic-octomap-ros ros-kinetic-mavlink +$ sudo apt-get install python-wstool python-catkin-tools protobuf-compiler libgoogle-glog-dev ros-kinetic-control-toolbox +$ 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 ``` - $ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main" - > /etc/apt/sources.list.d/ros-latest.list' - $ wget http://packages.ros.org/ros.key -O - | sudo apt-key add - - $ sudo apt-get update - $ sudo apt-get install ros-kinetic-desktop-full ros-kinetic-joy ros-kinetic-octomap-ros ros-kinetic-mavlink - $ sudo apt-get install python-wstool python-catkin-tools protobuf-compiler libgoogle-glog-dev ros-kinetic-control-toolbox - $ 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 - ``` + 2. 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/rotors_simulator.git - $ git clone https://github.com/gsilano/mav_comm - $ git clone https://github.com/gsilano/BebopS.git - $ git clone https://github.com/AutonomyLab/bebop_autonomy.git - $ cd ~/catkin_ws/src/rotors_simulator - $ git checkout med18 - $ cd ~/catkin_ws/src/mav_comm - $ git checkout med18 - $ cd ~/catkin_ws - $ rosdep update + ```console +$ 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 med18 https://github.com/gsilano/rotors_simulator.git +$ git clone -b med18 https://github.com/gsilano/mav_comm +$ git clone https://github.com/gsilano/BebopS.git +$ git clone https://github.com/AutonomyLab/bebop_autonomy.git ``` 3. Build your workspace with `python_catkin_tools` (therefore you need `python_catkin_tools`) - ``` - $ rosdep install --from-paths src -i - $ catkin build - ``` +```console +$ rosdep install --from-paths src -i +$ catkin build +``` 4. Add sourcing to your `.bashrc` file - ``` + ```console $ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc $ source ~/.bashrc ``` @@ -82,42 +125,51 @@ Basic Usage Launching the simulation is quite simple, so as customizing it: it is enough to run in a terminal the command - ``` + ```console $ roslaunch bebop_simulator bebop_without_controller.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. -The `bebop_without_controller.launch` file lets simulate the Parrot Bebop dynamics when no controllers are in the loop. Therefore, the drone pose can be modified by publishing the propellers angular velocity on the `/gazebo/command/motor_speed` topic. Moreover, external disturbances can also be simulated by varying the contents of the variables: `wind_force` (it represents the wind force expressed in Newton), `wind_start` (it indicates the time in seconds after which external forces will begin to act), `wind_duration` (the inveral time), `wind_direction` (the wind direction along the x, y and z-axis, its values are bounded between [-1, 1]). +> **Note** The first run of gazebo might take considerably long, as it will download some models from an on-line database. To avoid any problems when starting the simulation for the first time, you may run the `gazebo` command in the terminal line. -To let the multicopter fly you need to generate thrust with the rotors, this is achieved by sending commands to the multicopter, which make the rotors spin. +The `bebop_without_controller.launch` file simulates the Parrot Bebop dynamics when any controller is in the loop. Therefore, the drone pose can be modified by publishing the propellers angular velocity on the `/gazebo/command/motor_speed` topic. - ``` - $ rostopic pub /gazebo/command/motor_speed mav_msgs/Actuators '{angular_velocities: [1000, 1000, 1000, 1000]}' - ``` +> **Note** If you use the version compatible with ROS Melodic, `/command/motor_speed` is the topic to consider. + +Moreover, external disturbances can also be simulated by varying the contents of the variables: `wind_force` (it represents the wind force expressed in Newton), `wind_start` (it indicates the time in seconds after which external forces will begin to act), `wind_duration` (the interval time), `wind_direction` (the wind direction along the x, y and z-axis, its values are bounded between [-1, 1]). + +To fly the multirotor, it is necessary to generate thrust with the rotors, this is achieved by sending commands to the quadrotor that make the rotors spin. + + ```console +$ rostopic pub /gazebo/command/motor_speed mav_msgs/Actuators '{angular_velocities: [1000, 1000, 1000, 1000]}' +``` + +> **Note** If you use the ROS Melodic version of the code, the command to consider is +```console +$ rostopic pub /command/motor_speed mav_msgs/Actuators '{angular_velocities: [1000, 1000, 1000, 1000]}' +``` -To speed up the simulation, a certain set of sensors can be included when simulating the drone dynamics by varying the flags: `enable_odometry_sensor_with_noise`/`disable_odometry_sensor_with_noise` (it includes the odometry sensor with bias and noise terms), `enable_ground_truth_sensor` (it enables the ground truth sensor), `enable_wind_plugin` (even external disturbances will be simulated) and `enable_laser1D` (it enables the 1-D laser scanner). +To speed up the simulation, a certain set of sensors can be included when simulating the drone dynamics by varying the flags: `enable_odometry_sensor_with_noise`/`disable_odometry_sensor_with_noise` (it includes the odometry sensor with bias and noise terms), `enable_ground_truth_sensor` (it enables the ground truth sensor), `enable_wind_plugin` (even external disturbances will be simulated), `enable_laser1D` (it enables the RotorS default IMU, i.e., the ADIS16448 IMU) and `enable_laser1D` (it enables the 1-D laser scanner). These value can be modified before simulating the drone behavior acting on the launch file or at runtime by running on the terminal: - ``` + ```console $ roslaunch bebop_simulator bebop_without_controller.launch enable_odometry_sensor_with_noise:=true ``` - + Finally, the waypoint and Kalman filters, as well as the data storage, can be enabled/disabled by using the variables: `csvFilesStoring`, `csvFilesStoringTime` (simulation time after which the data will be saved), `user_account` (required to define the storage path), `waypoint_filter` and `EKFActive`. While, running in a terminal the command - ``` + ```console $ roslaunch bebop_simulator task1_world.launch ``` - -the Parrot Bebop takes off from the ground and keeps indefinitely the hovering position subjected to wind gusts (up to 0.5 N) for a minute. Conversely, - ``` +the Parrot Bebop takes off from the ground and keeps indefinitely the hovering position subjected to wind gusts (up to 0.5 N) for a minute. Conversely, + + ```console $ roslaunch bebop_simulator task2_world.launch ``` - + the drone starts to follow the trajectory expressed as a sequence of waypoints (x_r, y_r, z_r and \psi_r) published at a settled time (t_0, t_1, t_3, etc.), as described in `waypoint.txt` file. To avoid system instabilities, a waypoint filter is employed to smooth the trajectory. Gazebo Version @@ -130,14 +182,14 @@ At a minimum, Gazebo `v2.x` is required (which is installed by default with ROS ROS Kinetic installs Gazebo 7 by default so it is recommended to remove the previous installation. Proceeded to the installation section if installing for the first time. -``` +```console $ sudo apt-get remove ros-kinetic-gazebo* $ sudo apt-get upgrade ``` Install the core of the ROS and rest of the packages can be added manually -``` +```console $ sudo apt-get install ros-kinetic-gazebo9-ros-pkgs ros-kinetic-gazebo9-ros-control ros-kinetic-gazebo9* (for Gazebo 9) ``` @@ -151,5 +203,3 @@ YouTube video A YouTube video showing the Parrot Bebop during the trajectory tracking is reported. The trajectory, described using waypoints, is shown in the `waypoint.txt` file. [![MED18_Industrial_Challenge, BebopS](https://github.com/gsilano/BebopS/wiki/images/Video_Miniature_YouTube_SMC19.png)](https://youtu.be/ERkgSCoM6OI "MED18_Industrial_Challenge, BebopS") - - From 234bb303820cb240807cb087937fa645f606b884 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 19:09:35 +0100 Subject: [PATCH 02/18] Synch with the master --- CHANGELOG.rst | 5 +++++ launch/bebop_without_controller.launch | 2 ++ launch/spawn_bebop.launch | 2 ++ launch/task1_world.launch | 18 ++++++++++++++++++ launch/task2_world.launch | 2 ++ urdf/bebop.urdf.xacro | 24 ++++++++++++++++++++++++ 6 files changed, 53 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index d001f71..8fdf99d 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package BebopS ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.2 (2019-12-26) +------------------ +* Inserted the default RotorS IMU (ADIS16448 IMU) in the list of the available sensors when running the simulation +* Contributors: Giuseppe Silano + 0.2.1 (2019-04-04) ------------------ * The namespace was modified considering the ROS rules (only lowercase letters) diff --git a/launch/bebop_without_controller.launch b/launch/bebop_without_controller.launch index 88e47ac..e8d588f 100644 --- a/launch/bebop_without_controller.launch +++ b/launch/bebop_without_controller.launch @@ -21,6 +21,7 @@ + @@ -47,6 +48,7 @@ + diff --git a/launch/spawn_bebop.launch b/launch/spawn_bebop.launch index fa1c99b..8a40a1f 100644 --- a/launch/spawn_bebop.launch +++ b/launch/spawn_bebop.launch @@ -18,6 +18,7 @@ + @@ -29,6 +30,7 @@ enable_ground_truth_sensor:='$(arg enable_ground_truth_sensor)' enable_wind_plugin:='$(arg enable_wind_plugin)' enable_laser1D:='$(arg enable_laser1D)' + enable_imu:='$(arg enable_imu)' namespace:=$(arg name) wind_force:=$(arg wind_force) wind_start:=$(arg wind_start) diff --git a/launch/task1_world.launch b/launch/task1_world.launch index cf43be9..3a5f6c1 100644 --- a/launch/task1_world.launch +++ b/launch/task1_world.launch @@ -17,6 +17,16 @@ + + + + + + + + + @@ -36,6 +46,14 @@ + + + + + + + diff --git a/launch/task2_world.launch b/launch/task2_world.launch index 1a9e397..cbde155 100644 --- a/launch/task2_world.launch +++ b/launch/task2_world.launch @@ -25,6 +25,7 @@ + @@ -52,6 +53,7 @@ + diff --git a/urdf/bebop.urdf.xacro b/urdf/bebop.urdf.xacro index 70b0aa1..d934206 100644 --- a/urdf/bebop.urdf.xacro +++ b/urdf/bebop.urdf.xacro @@ -51,6 +51,30 @@ + + + + + + + + + Date: Thu, 26 Dec 2019 19:29:08 +0100 Subject: [PATCH 03/18] Insert the instruction for Ubuntu 18.04, ROS Melodic and Gazebo 9 --- CHANGELOG.rst | 1 + README.md | 58 ++++++++++++++++++++++++--------------------------- 2 files changed, 28 insertions(+), 31 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 8fdf99d..5857368 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -5,6 +5,7 @@ Changelog for package BebopS 0.2.2 (2019-12-26) ------------------ * Inserted the default RotorS IMU (ADIS16448 IMU) in the list of the available sensors when running the simulation +* Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 * Contributors: Giuseppe Silano 0.2.1 (2019-04-04) diff --git a/README.md b/README.md index 5ebbd21..ab851ee 100644 --- a/README.md +++ b/README.md @@ -23,7 +23,7 @@ If you are using this simulator for research purposes especially for your public The authors are grateful to the [LARICS Lab](https://larics.fer.hr/larics), University of Zagreb, for the initial work done to make the platform compatible with the latest changes to the RotorS package. Here the link to them [sofware repositry](https://github.com/larics/mmuav_gazebo). The software platform is an extract of the work carried out for the industrial challenge of the 26th Mediterranean Conference on Control and Automation (MED’18) in which the authors took part ([here the link](https://ieeexplore.ieee.org/document/8667511) to the conference report). -Installation Instructions - Ubuntu 18.04 with ROS Melodic +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. @@ -72,7 +72,16 @@ $ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc $ source ~/.bashrc ``` -Installation Instructions - Ubuntu 16.04 with ROS Kinetic +5. Update the pre-installed Gazebo version. This fix the issue with the `error in REST request for accessing api.ignition.org` + +```console +$ 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-get install gazebo9 +``` + +Installation Instructions - Ubuntu 16.04 with ROS Kinetic and Gazebo 7 --------------------------------------------------------- To use the code developed and stored in this repository some preliminary actions are needed. They are listed below. @@ -115,10 +124,10 @@ $ catkin build 4. Add sourcing to your `.bashrc` file - ```console - $ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc - $ source ~/.bashrc - ``` +```console +$ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc +$ source ~/.bashrc +``` Basic Usage --------------------------------------------------------- @@ -152,47 +161,34 @@ To speed up the simulation, a certain set of sensors can be included when simula These value can be modified before simulating the drone behavior acting on the launch file or at runtime by running on the terminal: - ```console - $ roslaunch bebop_simulator bebop_without_controller.launch enable_odometry_sensor_with_noise:=true - ``` + ```console +$ roslaunch bebop_simulator bebop_without_controller.launch enable_odometry_sensor_with_noise:=true +``` -Finally, the waypoint and Kalman filters, as well as the data storage, can be enabled/disabled by using the variables: `csvFilesStoring`, `csvFilesStoringTime` (simulation time after which the data will be saved), `user_account` (required to define the storage path), `waypoint_filter` and `EKFActive`. +Finally, the waypoint and the Kalman filters, as well as the data storage (file used as log), can be enabled/disabled by using the variables: `csvFilesStoring`, `csvFilesStoringTime` (simulation time after which the data will be saved), `user_account` (required to define the storage path), `waypoint_filter` and `EKFActive`. While, running in a terminal the command - ```console - $ roslaunch bebop_simulator task1_world.launch - ``` +```console +$ roslaunch bebop_simulator task1_world.launch +``` the Parrot Bebop takes off from the ground and keeps indefinitely the hovering position subjected to wind gusts (up to 0.5 N) for a minute. Conversely, - ```console - $ roslaunch bebop_simulator task2_world.launch - ``` +```console +$ roslaunch bebop_simulator task2_world.launch +``` -the drone starts to follow the trajectory expressed as a sequence of waypoints (x_r, y_r, z_r and \psi_r) published at a settled time (t_0, t_1, t_3, etc.), as described in `waypoint.txt` file. To avoid system instabilities, a waypoint filter is employed to smooth the trajectory. +the drone starts to follow the trajectory expressed as a sequence of waypoints (```math x_r, y_r, z_r``` and ```math \psi_r```) published at a settled time (```math t_0, t_1, t_3```, etc.), as described in `waypoint.txt` file. To avoid system instabilities, a waypoint filter is employed to smooth the trajectory. 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 functionlity, although the platform is fully compatible with the Gazebo 9. Before running the script, consider the following limitations: +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. -ROS Kinetic installs Gazebo 7 by default so it is recommended to remove the previous installation. Proceeded to the installation section if installing for the first time. - -```console -$ sudo apt-get remove ros-kinetic-gazebo* -$ sudo apt-get upgrade -``` - -Install the core of the ROS and rest of the packages can be added manually - -```console -$ sudo apt-get install ros-kinetic-gazebo9-ros-pkgs ros-kinetic-gazebo9-ros-control ros-kinetic-gazebo9* (for Gazebo 9) -``` - Bugs & Feature Requests -------------------------- From 11a1e109fa876cdba2224016e15b26964c073bdc Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 19:38:42 +0100 Subject: [PATCH 04/18] Update CHANGELOG.md file --- CHANGELOG.rst | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 5857368..876b1ac 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,10 +2,14 @@ Changelog for package BebopS ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.0.1 (2019-12-26) +------------------ +* Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 +* Contributors: Giuseppe Silano + 0.2.2 (2019-12-26) ------------------ * Inserted the default RotorS IMU (ADIS16448 IMU) in the list of the available sensors when running the simulation -* Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 * Contributors: Giuseppe Silano 0.2.1 (2019-04-04) From be2908d24e53232bb1427872b36219d10407a4be Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 19:46:58 +0100 Subject: [PATCH 05/18] Update README.md Fix typo --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index ab851ee..1c15f92 100644 --- a/README.md +++ b/README.md @@ -39,7 +39,7 @@ $ sudo rosdep init $ rosdep update $ echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc $ source ~/.bashrc -$ sudo apt install python-rosinstall python-rosinstall-generator python-wstool build-essential +$ sudo apt install python-rosinstall python-rosinstall-generator build-essential ``` 2. If you don't have ROS workspace yet you can do so by @@ -97,7 +97,7 @@ $ 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 +$ sudo apt-get install python-rosinstall python-rosinstall-generator build-essential ``` 2. If you don't have ROS workspace yet you can do so by From 1bf20dcf218fa17f0869219fd1422791145ef0be Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 19:47:56 +0100 Subject: [PATCH 06/18] First draft .travis.yml file --- .travis.yml | 23 +++++++++++++++-------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/.travis.yml b/.travis.yml index 81d60ae..f14ec80 100644 --- a/.travis.yml +++ b/.travis.yml @@ -41,10 +41,18 @@ ################################################################################ -# Use ubuntu xenial (16.04) with sudo privileges. -os: linux -dist: xenial -sudo: required + +# Use ubuntu xenial (16.04) and bionic (18.04) with sudo privileges. +matrix: + include: + - os: linux + dist: xenial + sudo: required + env: ROS_DISTRO=kinetic + - os: linux + dist: bionic + sudo: required + env: ROS_DISTRO=melodic language: - generic @@ -55,7 +63,6 @@ cache: # trigger a build matrix for different ROS distributions if desired. env: global: - - ROS_DISTRO=kinetic - ROS_CI_DESKTOP="`lsb_release -cs`" # e.g. [precise|trusty|...] - CI_SOURCE_PATH=$(pwd) - ROSINSTALL_FILE=$CI_SOURCE_PATH/dependencies.rosinstall @@ -74,9 +81,9 @@ before_install: - sudo rm /var/lib/dpkg/lock - sudo dpkg --configure -a - sudo apt-get update - - sudo apt-get install ros-$ROS_DISTRO-desktop-full ros-$ROS_DISTRO-joy ros-$ROS_DISTRO-octomap-ros - - sudo apt-get install python-wstool python-catkin-tools - - sudo apt-get install protobuf-compiler libgoogle-glog-dev + - sudo apt-get install ros-$ROS_DISTRO-desktop-full ros-$ROS_DISTRO-joy ros-$ROS_DISTRO-octomap-ros ros-$ROS_DISTRO-mavlink + - sudo apt-get install python-wstool python-catkin-tools python-rosinstall build-essential + - sudo apt-get install protobuf-compiler libgoogle-glog-dev python-rosinstall-generator # Prepare rosdep to install dependencies. - sudo rosdep init - rosdep update From 18ba58e444ba0bd34a2b479d535e570558fb6af7 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 20:27:26 +0100 Subject: [PATCH 07/18] Update .travis.yml file --- .travis.yml | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/.travis.yml b/.travis.yml index f14ec80..2ccd0b3 100644 --- a/.travis.yml +++ b/.travis.yml @@ -48,11 +48,11 @@ matrix: - os: linux dist: xenial sudo: required - env: ROS_DISTRO=kinetic + env: ROS_DISTRO=kinetic, OS_DISTRO=xenial - os: linux dist: bionic sudo: required - env: ROS_DISTRO=melodic + env: ROS_DISTRO=melodic, OS_DISTRO=bionic language: - generic @@ -100,13 +100,15 @@ install: - git clone https://github.com/gsilano/BebopS.git - git clone https://github.com/gsilano/rotors_simulator.git - git clone https://github.com/gsilano/mav_comm.git - - git clone https://github.com/gsilano/med_aerial_challenge_launch.git - git clone https://github.com/gsilano/bebop_autonomy.git - cd ~/catkin_ws/src/rotors_simulator - - git checkout med18 + - if [[ "$ROS_DISTRO" == "kinetic" ]]; then git checkout med18; fi + - if [[ "$ROS_DISTRO" == "melodic" ]]; then git checkout med18_gazebo9; fi - cd ~/catkin_ws/src/mav_comm - - git checkout med18 - - rosdep update + - if [[ "$ROS_DISTRO" == "kinetic" ]]; then git checkout med18; fi + - if [[ "$ROS_DISTRO" == "melodic" ]]; then git checkout med18_gazebo9; fi + - cd ~/catkin_ws/src/BebopS + - if [[ "$ROS_DISTRO" == "melodic" ]]; then git checkout dev/gazebo9; fi - cd ~/catkin_ws - rosdep install --from-paths src -i - catkin build From 17c213fbce321d78b8118616a347198fd836b824 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 20:36:26 +0100 Subject: [PATCH 08/18] Test fix issue TravisCI builder --- .travis.yml | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/.travis.yml b/.travis.yml index 2ccd0b3..9ff07fa 100644 --- a/.travis.yml +++ b/.travis.yml @@ -20,7 +20,7 @@ # `wstool`, and should be listed in a file named dependencies.rosinstall. # # There are two variables you may want to change: -# - ROS_DISTRO (default is indigo, but also kinetic is now compatible). Note that +# - ROS_DISTRO (default is indigo, but also kinetic is now compatible). Note that # packages must be available for ubuntu 14.04 trusty and xenial 16.04, respectively. # # See the README.md for more information. @@ -48,11 +48,11 @@ matrix: - os: linux dist: xenial sudo: required - env: ROS_DISTRO=kinetic, OS_DISTRO=xenial + env: ROS_DISTRO=kinetic - os: linux dist: bionic sudo: required - env: ROS_DISTRO=melodic, OS_DISTRO=bionic + env: ROS_DISTRO=melodic language: - generic @@ -78,17 +78,17 @@ env: before_install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main" > /etc/apt/sources.list.d/ros-latest.list' - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - - - sudo rm /var/lib/dpkg/lock - - sudo dpkg --configure -a + - if [[ "$ROS_DISTRO" == "kinetic" ]]; then sudo rm /var/lib/dpkg/lock; fi + - if [[ "$ROS_DISTRO" == "kinetic" ]]; then sudo dpkg --configure -a; fi - sudo apt-get update - sudo apt-get install ros-$ROS_DISTRO-desktop-full ros-$ROS_DISTRO-joy ros-$ROS_DISTRO-octomap-ros ros-$ROS_DISTRO-mavlink - sudo apt-get install python-wstool python-catkin-tools python-rosinstall build-essential - sudo apt-get install protobuf-compiler libgoogle-glog-dev python-rosinstall-generator - # Prepare rosdep to install dependencies. - - sudo rosdep init + # Prepare rosdep to install dependencies. + - sudo rosdep init - rosdep update - source /opt/ros/$ROS_DISTRO/setup.bash - + # Create a catkin workspace with the package under integration. install: - mkdir -p ~/catkin_ws/src @@ -101,13 +101,13 @@ install: - git clone https://github.com/gsilano/rotors_simulator.git - git clone https://github.com/gsilano/mav_comm.git - git clone https://github.com/gsilano/bebop_autonomy.git - - cd ~/catkin_ws/src/rotors_simulator + - cd ~/catkin_ws/src/rotors_simulator - if [[ "$ROS_DISTRO" == "kinetic" ]]; then git checkout med18; fi - if [[ "$ROS_DISTRO" == "melodic" ]]; then git checkout med18_gazebo9; fi - - cd ~/catkin_ws/src/mav_comm + - cd ~/catkin_ws/src/mav_comm - if [[ "$ROS_DISTRO" == "kinetic" ]]; then git checkout med18; fi - if [[ "$ROS_DISTRO" == "melodic" ]]; then git checkout med18_gazebo9; fi - - cd ~/catkin_ws/src/BebopS + - cd ~/catkin_ws/src/BebopS - if [[ "$ROS_DISTRO" == "melodic" ]]; then git checkout dev/gazebo9; fi - cd ~/catkin_ws - rosdep install --from-paths src -i From df7f701923a40ab889d9292c66ceb78a1220f2c1 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:13:47 +0100 Subject: [PATCH 09/18] Update basic.world Disable shadows in Gazebo. --- worlds/basic.world | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/worlds/basic.world b/worlds/basic.world index d662c6e..2d5ca1e 100644 --- a/worlds/basic.world +++ b/worlds/basic.world @@ -7,6 +7,12 @@ model://sun + + + + 0 + + EARTH_WGS84 47.3667 From 1675cd052b0b565b0baa7acbf502b3f03b0b16f0 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:14:49 +0100 Subject: [PATCH 10/18] Update CHANGELOG.rst --- CHANGELOG.rst | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 876b1ac..e0542c9 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -5,11 +5,13 @@ Changelog for package BebopS 2.0.1 (2019-12-26) ------------------ * Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 +* Disabled shadows in Gazebo 9 * Contributors: Giuseppe Silano 0.2.2 (2019-12-26) ------------------ * Inserted the default RotorS IMU (ADIS16448 IMU) in the list of the available sensors when running the simulation +* Disabled shadows in Gazebo 9 * Contributors: Giuseppe Silano 0.2.1 (2019-04-04) From 0ad970ffcd17e5ee008fb3130c8faf9e57f85bac Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:27:15 +0100 Subject: [PATCH 11/18] Update package.xml file --- package.xml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/package.xml b/package.xml index 4ac5eef..b390f64 100644 --- a/package.xml +++ b/package.xml @@ -1,11 +1,10 @@ bebop_simulator - 0.2.1 + 0.2.2 This package aims to simulate the behavior of the Parrot Bebop by using SIL methodologies. Giuseppe Silano - Pasquale Oppido Luigi Iannelli Giuseppe Silano From b7a8746cf93930c2ff222fa77ce6d0849ce63784 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:41:24 +0100 Subject: [PATCH 12/18] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 1c15f92..8ad5a4e 100644 --- a/README.md +++ b/README.md @@ -78,7 +78,7 @@ $ source ~/.bashrc $ 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-get install gazebo9 +$ sudo apt-get install gazebo9 gazebo9-* ``` Installation Instructions - Ubuntu 16.04 with ROS Kinetic and Gazebo 7 From 67641960b251fb36cacbd4f1a3ec6be017f15c8e Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:41:38 +0100 Subject: [PATCH 13/18] Update CHANGELOG.md --- CHANGELOG.rst | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index e0542c9..d7ce0e9 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -6,6 +6,7 @@ Changelog for package BebopS ------------------ * Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 * Disabled shadows in Gazebo 9 +* TravisCI (.travis.yml file) is now compatible with the Melodic distro of ROS and Ubuntu 18.04 * Contributors: Giuseppe Silano 0.2.2 (2019-12-26) From 34edc20ea4884d7da340a47de593c51486f2d9bb Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:50:22 +0100 Subject: [PATCH 14/18] Synch CHANGELOG.md --- CHANGELOG.rst | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index d7ce0e9..a92925b 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -4,10 +4,11 @@ Changelog for package BebopS 2.0.1 (2019-12-26) ------------------ -* Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 -* Disabled shadows in Gazebo 9 -* TravisCI (.travis.yml file) is now compatible with the Melodic distro of ROS and Ubuntu 18.04 -* Contributors: Giuseppe Silano +* Updated the README.md file with instructions for Ubuntu 18.04, ROS Melodic Morenia and Gazebo 9 (master) +* Deleted the README.md file to avoid misunderstanding in the installation procedure (dev/gazebo9 branch) +* Inserted the default RotorS IMU (ADIS16448 IMU) in the list of the available sensors when running the simulation +* Disable shadows in Gazebo 9 and added the rotors_interface_plugin. The plugin is necessary for reading the sensors messages +* Deleted TravisCI (.travisci.yml) file. Only one file is present in the master. The file handles all the distro. * Contributors: Giuseppe Silano 0.2.2 (2019-12-26) ------------------ From dbb3654a04f02f01b5854abd823daddb06de5e61 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Thu, 26 Dec 2019 22:55:10 +0100 Subject: [PATCH 15/18] Update README.md --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 8ad5a4e..a9abdc3 100644 --- a/README.md +++ b/README.md @@ -78,7 +78,8 @@ $ source ~/.bashrc $ 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-get install gazebo9 gazebo9-* +$ sudo apt install gazebo9 gazebo9-* +$ sudo apt upgrade ``` Installation Instructions - Ubuntu 16.04 with ROS Kinetic and Gazebo 7 From 742c494182c510ca5d1d6ab4b31bf367b40ead82 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Fri, 27 Dec 2019 10:02:58 +0100 Subject: [PATCH 16/18] Fix typo --- CHANGELOG.rst | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index a92925b..a0d7302 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -8,7 +8,8 @@ Changelog for package BebopS * Deleted the README.md file to avoid misunderstanding in the installation procedure (dev/gazebo9 branch) * Inserted the default RotorS IMU (ADIS16448 IMU) in the list of the available sensors when running the simulation * Disable shadows in Gazebo 9 and added the rotors_interface_plugin. The plugin is necessary for reading the sensors messages -* Deleted TravisCI (.travisci.yml) file. Only one file is present in the master. The file handles all the distro. * Contributors: Giuseppe Silano +* Deleted TravisCI (.travisci.yml) file. Only one file is present in the master. The file handles all the distro. +* Contributors: Giuseppe Silano 0.2.2 (2019-12-26) ------------------ @@ -51,7 +52,7 @@ Changelog for package BebopS * Added the Kalman filter * Added plots in the launch file to monitor the position and linear velocity errors between the Kalman filter output and the odometry ground truth values. In order to develop such functionality, the teamsannio messages have been created. * A yaml file needed to set up the Kalman filter has been created. Such file contains the tuning matrix of the filter and the standard deviations that characterize the odometry virtual sensor. -* The Kalman filter works with the noisy attitude (standard deviation 0.017). This function considers the nonideality of the attitude filter onboard the quadrotor. +* The Kalman filter works with the noisy attitude (standard deviation 0.017). This function considers the nonideality of the attitude filter onboard the quadrotor. * Contributors: Pasquale Oppido, Giuseppe Silano, Luigi Iannelli 0.1.3 (2018-05-25) @@ -77,4 +78,3 @@ Changelog for package BebopS ------------------ * Initial Ubuntu package release * Contributors: Giuseppe Silano, Pasquale Oppido, Luigi Iannelli - From 7602cfc396dba1b4b4adee2f61d4bc93b5aa8235 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Fri, 27 Dec 2019 10:40:31 +0100 Subject: [PATCH 17/18] Fix typo --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index a9abdc3..8f7c8c7 100644 --- a/README.md +++ b/README.md @@ -53,7 +53,7 @@ $ catkin init $ cd ~/catkin_ws/src $ git clone -b med18_gazebo9 https://github.com/gsilano/rotors_simulator.git $ git clone -b med18_gazebo9 https://github.com/gsilano/mav_comm -$ git clone -b gazebo9 https://github.com/gsilano/BebopS.git +$ git clone -b dev/gazebo9 https://github.com/gsilano/BebopS.git $ git clone https://github.com/AutonomyLab/bebop_autonomy.git $ cd ~/catkin_ws ``` From d018c8be10f94dc31003f077e65586a087177d43 Mon Sep 17 00:00:00 2001 From: Giuseppe Silano Date: Fri, 27 Dec 2019 11:31:37 +0100 Subject: [PATCH 18/18] Fix typo --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 8f7c8c7..ef40fd6 100644 --- a/README.md +++ b/README.md @@ -180,7 +180,7 @@ the Parrot Bebop takes off from the ground and keeps indefinitely the hovering p $ roslaunch bebop_simulator task2_world.launch ``` -the drone starts to follow the trajectory expressed as a sequence of waypoints (```math x_r, y_r, z_r``` and ```math \psi_r```) published at a settled time (```math t_0, t_1, t_3```, etc.), as described in `waypoint.txt` file. To avoid system instabilities, a waypoint filter is employed to smooth the trajectory. +the drone starts to follow the trajectory expressed as a sequence of waypoints (`x_r, y_r, z_r` and `\psi_r`) published at a settled time (`t_0, t_1, t_3`, etc.), as described in `waypoint.txt` file. To avoid system instabilities, a waypoint filter is employed to smooth the trajectory. Gazebo Version --------------