OmniGibson/examples/ros/gibson2-ros
fxia22 43784014da unify interactive assets loading 2020-04-06 12:02:35 -07:00
..
launch fix simulator and launch script 2019-05-22 14:33:32 -07:00
map update ros 2019-05-21 17:08:44 -07:00
param use pointcloud instead of laserscan for lidar 2019-03-06 15:21:48 -08:00
rviz update ros examples 2019-05-22 11:37:28 -07:00
turtlebot fix simulator and launch script 2019-05-22 14:33:32 -07:00
.gitignore merge from ros 2019-05-21 16:11:28 -07:00
CMakeLists.txt gibson v2 ros example 2019-02-13 18:16:53 -08:00
README.md fix simulator and launch script 2019-05-22 14:33:32 -07:00
goggle.py yapf style 2019-05-21 14:30:07 -07:00
noise_injection.py remove extraneous imports 2019-05-22 15:12:51 -07:00
package.xml unify interactive assets loading 2020-04-06 12:02:35 -07:00
publish_true_map_to_odom_tf.py style and clean 2019-05-21 16:15:10 -07:00
turtlebot_rgbd.py remove depth clipping, close #28 2019-06-10 10:19:11 -07:00
turtlebot_rgbd.yaml fix simulator and launch script 2019-05-22 14:33:32 -07:00

README.md

Gibson ROS Binding

Introduction

ROS is a set of well-engineered software libraries for building robotics applications. It includes a wide variety of packages, from low level drivers to efficient implementations of state of the art algorithms. As we strive to build intelligent agents and transfer them to real-world (on a real robot), we need to take advantage of ROS packages to complete the robot application pipeline.

As a starter, we provide an example of integrating Gibson with ROS. This is a ros package integrates Gibson Env with ros navigation stack. It follows the same node topology and topics as turtlebot_navigation package. As shown below, so after a policy is trained in Gibson, it requires minimal changes to deploy onto a turtlebot.

Environment Setup

Here is all the steps you need to perform to install gibson and ros. Note that here you will need to install using pip install -e . and use python2.7. If you did it differntly when installing Gibson, you will need to do it again. python3 is known to not being able to work with ros.

Preparation

  1. Install ROS: in this package, we use navigation stack from ros kinetic. Please follow the instructions.
  2. Install gibson from source following installation guide in python2.7. However, as ros only supports python2.7 at the moment, you need to create python2.7 virtual environment instead of python3.5.
  3. If you use annaconda for setting up python environment, some tweaks of PATH and PYTHONPATH variable are required to avoid conflict. In particular:
    1. For PATH: conda related needs to be removed from PATH
    echo $PATH | grep -oP "[^:;]+" | grep conda	## Remove these paths from $PATH
    
    1. For PYTHONPATH: /usr/lib/python2.7/dist-packages/, /opt/ros/kinetic/lib/python2.7/dist-packages(ros python libraries), <anaconda installation root>/anaconda2/envs/py27/lib/python2.7/site-packages(gibson dependencies) and <gibson root> need to be in PYTHONPATH.
  4. Copy (or soft link) gibson-ros folder to your catkin_ws/src and run catkin_make to index gibson-ros package.
ln -s $PWD/examples/ros/gibson-ros/ ~/catkin_ws/src/
cd ~/catkin_ws && catkin_make && cd -
  1. Install gibson2-ros dependencies:
rosdep install gibson2-ros

Sanity check

which python #should give /usr/bin/python 
python -c 'import gibson, rospy, rospkg' #you should be able to do those without errors.

Running

In order to run gibson+ros examples, you will need to perform the following steps:

  1. Prepare ROS environment
source /opt/ros/kinetic/setup.bash
source <catkin-workspace-root>/catkin_ws/devel/setup.bash
  1. Repeat step 3 from Preparation, sanitize PATH and PYTHONPATH
  2. Here are some of the examples that you can run, including gmapping, hector mapping and navigation.
roslaunch gibson2-ros turtlebot_rgbd.launch #Bare minimal bringup example
roslaunch gibson2-ros turtlebot_gmapping.launch #Run gmapping
roslaunch gibson2-ros turtlebot_hector_mapping.launch #Run hector mapping
roslaunch gibson2-ros turtlebot_navigation.launch #Run the navigation stack, we have provided the map
roslaunch gibson2-ros turtlebot_gt_navigation.launch #Run the navigation stack with ground truth localization

The following screenshot is captured when running the bare minimal bringup example.

The following screenshot is captured when running the gmapping example.

Topics

Here are all the topics that turtlebot_rgbd.py publishes and subscribes.

  • turtlebot_rgbd.py

Publishes:

Topic name Type Usage
/gibson_ros/camera/depth/camera_info sensor_msgs/CameraInfo Camera parameters used in Gibson, same for depth and rgb
/gibson_ros/camera/rgb/image sensor_msgs/Image RGB image captured in Gibson
/gibson_ros/camera/rgb/depth sensor_msgs/Image depth image captured in Gibson, in meters, with dtype being float32
/gibson_ros/camera/rgb/depth_raw sensor_msgs/Image depth image captured in Gibson, mimic raw depth data captured with OpenNI cameras, with dtype being uint16, see more here
/odom nav_msgs/Odometry odometry from odom frame to base_footprint, generated with groudtruth pose in Gibson

Subscribes:

Topic name Type Usage
/mobile_base/commands/velocity geometry_msgs/Twist Velocity command for turtlebot, msg.linear.x is the forward velocity, msg.angular.z is the angular velocity

References