Skip to content

Commit

Permalink
Noetic support (#93)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
Co-authored-by: Jose Luis Rivero <[email protected]>
  • Loading branch information
chapulina and j-rivero authored Jul 23, 2020
1 parent 85b0ccc commit 91265a7
Show file tree
Hide file tree
Showing 20 changed files with 218 additions and 298 deletions.
5 changes: 2 additions & 3 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,7 @@ sudo: required

env:
matrix:
- DOCKER_IMAGE=ubuntu:18.04 IGNITION_VERSION="blueprint" ROS_DISTRO="melodic"
- DOCKER_IMAGE=ubuntu:18.04 IGNITION_VERSION="citadel" ROS_DISTRO="melodic"
- DOCKER_IMAGE=ubuntu:20.04 ROS_DISTRO="noetic"

services:
- docker
Expand All @@ -17,7 +16,7 @@ before_install:
- echo $DOCKER_IMAGE
- echo $IGNITION_VERSION
- docker pull $DOCKER_IMAGE
- docker run -e IGNITION_VERSION -e ROS_DISTRO -d -v $(pwd):/code $DOCKER_IMAGE /bin/bash -c 'while true; do sleep 1; done'
- docker run -e ROS_DISTRO -d -v $(pwd):/code $DOCKER_IMAGE /bin/bash -c 'while true; do sleep 1; done'
- docker exec $(docker ps -aq) /bin/bash -c 'id'

before_script:
Expand Down
47 changes: 13 additions & 34 deletions .travis/build
Original file line number Diff line number Diff line change
Expand Up @@ -2,49 +2,28 @@
set -ev

# Configuration.
export CATKIN_WS=~/catkin_ws
export CATKIN_WS_SRC=${CATKIN_WS}/src
export COLCON_WS=~/ws
export COLCON_WS_SRC=${COLCON_WS}/src
export DEBIAN_FRONTEND=noninteractive

if [ "$IGNITION_VERSION" == "blueprint" ]; then
IGN_DEPS="libignition-msgs4-dev libignition-transport7-dev libignition-gazebo2-dev"
elif [ "$IGNITION_VERSION" == "citadel" ]; then
IGN_DEPS="libignition-msgs5-dev libignition-transport8-dev libignition-gazebo3-dev"
else
exit 1
fi
export ROS_PYTHON_VERSION=3

# Dependencies.
echo "deb [trusted=yes] http://packages.osrfoundation.org/gazebo/ubuntu-stable bionic main" > /etc/apt/sources.list.d/gazebo-stable.list
echo "deb [trusted=yes] http://packages.ros.org/ros/ubuntu bionic main" > /etc/apt/sources.list.d/ros-latest.list
echo "deb [trusted=yes] http://packages.ros.org/ros/ubuntu focal main" > /etc/apt/sources.list.d/ros-latest.list
apt-get update -qq
apt-get install -qq -y $IGN_DEPS \
python-catkin-tools \
python-rosdep
apt-get install -qq -y python3-colcon-common-extensions \
python3-rosdep

rosdep init
rosdep update
rosdep install --from-paths ./ -i -y --rosdistro $ROS_DISTRO \
--skip-keys=ignition-gazebo2 \
--skip-keys=ignition-gazebo3 \
--skip-keys=ignition-msgs4 \
--skip-keys=ignition-msgs5 \
--skip-keys=ignition-rendering2 \
--skip-keys=ignition-rendering3 \
--skip-keys=ignition-sensors2 \
--skip-keys=ignition-sensors3 \
--skip-keys=ignition-transport7 \
--skip-keys=ignition-transport8
rosdep install --from-paths ./ -i -y --rosdistro $ROS_DISTRO

# Build.
source /opt/ros/$ROS_DISTRO/setup.bash
mkdir -p $CATKIN_WS_SRC
ln -s /code $CATKIN_WS_SRC
cd $CATKIN_WS
catkin init
catkin config --install
catkin build --limit-status-rate 0.1 --no-notify -DCMAKE_BUILD_TYPE=Release
catkin build --limit-status-rate 0.1 --no-notify --make-args tests
mkdir -p $COLCON_WS_SRC
ln -s /code $COLCON_WS_SRC
cd $COLCON_WS
colcon build --event-handlers console_direct+

# Tests.
catkin run_tests
colcon test --event-handlers console_direct+
colcon test-result
69 changes: 20 additions & 49 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
[![Build Status](https://travis-ci.org/ignitionrobotics/ros_ign.svg?branch=melodic)](https://travis-ci.org/ignitionrobotics/ros_ign/branches)
[![Build Status](https://travis-ci.org/ignitionrobotics/ros_ign.svg?branch=noetic)](https://travis-ci.org/ignitionrobotics/ros_ign/branches)

* ROS 1 branches:
* [melodic](https://github.com/osrf/ros_ign/tree/melodic)
Expand All @@ -22,66 +22,48 @@
This repository holds packages that provide integration between
[ROS](http://www.ros.org/) and [Ignition](https://ignitionrobotics.org):

* [ros_ign](https://github.com/osrf/ros_ign/tree/melodic/ros_ign):
* [ros_ign](https://github.com/osrf/ros_ign/tree/noetic/ros_ign):
Metapackage which provides all the other packages.
* [ros_ign_image](https://github.com/osrf/ros_ign/tree/melodic/ros_ign_image):
* [ros_ign_image](https://github.com/osrf/ros_ign/tree/noetic/ros_ign_image):
Unidirectional transport bridge for images from
[Ignition Transport](https://ignitionrobotics.org/libs/transport)
to ROS using
[image_transport](http://wiki.ros.org/image_transport).
* [ros_ign_bridge](https://github.com/osrf/ros_ign/tree/melodic/ros_ign_bridge):
* [ros_ign_bridge](https://github.com/osrf/ros_ign/tree/noetic/ros_ign_bridge):
Bidirectional transport bridge between
[Ignition Transport](https://ignitionrobotics.org/libs/transport)
and ROS.
* [ros_ign_gazebo](https://github.com/osrf/ros_ign/tree/melodic/ros_ign_gazebo):
* [ros_ign_gazebo](https://github.com/osrf/ros_ign/tree/noetic/ros_ign_gazebo):
Convenient launch files and executables for using
[Ignition Gazebo](https://ignitionrobotics.org/libs/gazebo)
with ROS.
* [ros_ign_gazebo_demos](https://github.com/osrf/ros_ign/tree/melodic/ros_ign_gazebo_demos):
* [ros_ign_gazebo_demos](https://github.com/osrf/ros_ign/tree/noetic/ros_ign_gazebo_demos):
Demos using the ROS-Ignition integration.
* [ros_ign_point_cloud](https://github.com/osrf/ros_ign/tree/melodic/ros_ign_point_cloud):
* [ros_ign_point_cloud](https://github.com/osrf/ros_ign/tree/noetic/ros_ign_point_cloud):
Plugins for publishing point clouds to ROS from
[Ignition Gazebo](https://ignitionrobotics.org/libs/gazebo) simulations.

## Install

This branch supports ROS Melodic. See above for other ROS versions.

### Binaries

At the moment, Melodic binaries are only available for Blueprint.
They are hosted at https://packages.osrfoundation.org.

1. Add https://packages.osrfoundation.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 https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt-get update

1. Install `ros_ign`

sudo apt install ros-melodic-ros-ign

### From source
This branch supports ROS Noetic. See above for other ROS versions.

### ROS

Be sure you've installed
[ROS Melodic](http://wiki.ros.org/melodic/Installation/Ubuntu) (at least ROS-Base).
More ROS dependencies will be installed below.
[ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu) (at least ROS-Base).

### Ignition
### Binaries

Install either [Blueprint or Citadel](https://ignitionrobotics.org/docs).
Noetic binaries will *soon* be available for Citadel.
They will be hosted at https://packages.ros.org.

Set the `IGNITION_VERSION` environment variable to the Ignition version you'd
like to compile against. For example:
1. Make sure you have ROS Noetic installed.

export IGNITION_VERSION=citadel
1. Install `ros_ign`

> You only need to set this variable when compiling, not when running.
sudo apt install ros-noetic-ros-ign

### Compile ros_ign
### From source

The following steps are for Linux and OSX.

Expand All @@ -93,32 +75,21 @@ The following steps are for Linux and OSX.
cd ~/ws/src
# Download needed software
git clone https://github.com/osrf/ros_ign.git -b melodic
git clone https://github.com/osrf/ros_ign.git -b noetic
```
1. Install ROS dependencies:
1. Install dependencies (this will also install Ignition):
```
cd ~/ws
rosdep install --from-paths src -i -y --rosdistro melodic \
--skip-keys=ignition-gazebo2 \
--skip-keys=ignition-gazebo3 \
--skip-keys=ignition-msgs4 \
--skip-keys=ignition-msgs5 \
--skip-keys=ignition-rendering2 \
--skip-keys=ignition-rendering3 \
--skip-keys=ignition-sensors2 \
--skip-keys=ignition-sensors3 \
--skip-keys=ignition-transport7 \
--skip-keys=ignition-transport8
rosdep install --from-paths src -i -y --rosdistro noetic
```
1. Build the workspace:
```
# Source ROS distro's setup.bash
source /opt/ros/melodic/setup.bash
source /opt/ros/noetic/setup.bash
# Build and install into workspace
cd ~/ws/
Expand Down
2 changes: 1 addition & 1 deletion RELEASING.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ The steps to make a new release of the package are:
1. Bloom it into a custom repository
```
BLOOM_RELEASE_REPO_BASE=https://github.com/osrf/ bloom-release --no-pull-request --rosdistro melodic --track melodic ros_ign
BLOOM_RELEASE_REPO_BASE=https://github.com/osrf/ bloom-release --no-pull-request --rosdistro <ros_distro> --track <ros_distro> ros_ign
```
Will fail fedora: ignore and continue:
Expand Down
14 changes: 7 additions & 7 deletions ros_ign_bridge/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ service calls. Its support is limited to only the following message types:
| geometry_msgs/Transform | ignition::msgs::Pose |
| geometry_msgs/TransformStamped | ignition::msgs::Pose |
| geometry_msgs/Twist | ignition::msgs::Twist |
| mav_msgs/Actuators | ignition::msgs::Actuators |
| mav_msgs/Actuators ([not on Noetic](https://github.com/ethz-asl/mav_comm/issues/86)) | ignition::msgs::Actuators |
| nav_msgs/Odometry | ignition::msgs::Odometry |
| rosgraph_msgs/Clock | ignition::msgs::Clock |
| sensor_msgs/BatteryState | ignition::msgs::BatteryState |
Expand All @@ -44,7 +44,7 @@ First we start a ROS `roscore`:

```
# Shell A:
. /opt/ros/melodic/setup.bash
. /opt/ros/noetic/setup.bash
roscore
```

Expand All @@ -60,7 +60,7 @@ Now we start the ROS listener.

```
# Shell C:
. /opt/ros/melodic/setup.bash
. /opt/ros/noetic/setup.bash
rostopic echo /chatter
```

Expand All @@ -77,7 +77,7 @@ First we start a ROS `roscore`:

```
# Shell A:
. /opt/ros/melodic/setup.bash
. /opt/ros/noetic/setup.bash
roscore
```

Expand All @@ -100,7 +100,7 @@ Now we start the ROS talker.

```
# Shell D:
. /opt/ros/melodic/setup.bash
. /opt/ros/noetic/setup.bash
rostopic pub /chatter std_msgs/String "data: 'Hi'" --once
```

Expand All @@ -113,7 +113,7 @@ First we start a ROS `roscore`:

```
# Shell A:
. /opt/ros/melodic/setup.bash
. /opt/ros/noetic/setup.bash
roscore
```

Expand Down Expand Up @@ -146,7 +146,7 @@ Now we start the ROS GUI:

```
# Shell E:
. /opt/ros/melodic/setup.bash
. /opt/ros/noetic/setup.bash
rqt_image_view /default/camera/link/camera/image
```

Expand Down
24 changes: 12 additions & 12 deletions ros_ign_bridge/include/ros_ign_bridge/convert.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <mav_msgs/Actuators.h>
// #include <mav_msgs/Actuators.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/BatteryState.h>
#include <sensor_msgs/CameraInfo.h>
Expand Down Expand Up @@ -248,17 +248,17 @@ convert_ign_to_ros(
geometry_msgs::Twist & ros_msg);

// mav_msgs
template<>
void
convert_ros_to_ign(
const mav_msgs::Actuators & ros_msg,
ignition::msgs::Actuators & ign_msg);

template<>
void
convert_ign_to_ros(
const ignition::msgs::Actuators & ign_msg,
mav_msgs::Actuators & ros_msg);
// template<>
// void
// convert_ros_to_ign(
// const mav_msgs::Actuators & ros_msg,
// ignition::msgs::Actuators & ign_msg);
//
// template<>
// void
// convert_ign_to_ros(
// const ignition::msgs::Actuators & ign_msg,
// mav_msgs::Actuators & ros_msg);

// nav_msgs
template<>
Expand Down
11 changes: 4 additions & 7 deletions ros_ign_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,10 @@
<buildtool_depend>catkin</buildtool_depend>

<depend>geometry_msgs</depend>
<depend>mav_msgs</depend>
<depend>ignition-msgs5</depend>
<depend>ignition-transport8</depend>
<!-- Not on Noetic https://github.com/ethz-asl/mav_comm/issues/86
<depend>mav_msgs</depend-->
<depend>nav_msgs</depend>
<depend>rosgraph_msgs</depend>
<depend>rosconsole</depend>
Expand All @@ -18,12 +21,6 @@
<depend>std_srvs</depend>
<depend>tf2_msgs</depend>

<!-- Default to citadel, support blueprint -->
<depend condition="$IGNITION_VERSION == blueprint">ignition-msgs4</depend>
<depend condition="$IGNITION_VERSION == blueprint">ignition-transport7</depend>
<depend condition="$IGNITION_VERSION != blueprint">ignition-msgs5</depend>
<depend condition="$IGNITION_VERSION != blueprint">ignition-transport8</depend>

<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
<test_depend>rostest</test_depend>
Expand Down
Loading

0 comments on commit 91265a7

Please sign in to comment.