Show EOL distros:
Documentation
The stack contains all of the Orocos Toolchain v2.4.x integrated in the ROS build system. The orocos_toolchain_ros stack contains utilmm, utilrb, typelib and orogen, to automatically create ros packages for the automatic typekit generation for C++ classes.
On top of the Orocos Toolchain v2.4.x this stack contains:
rtt_ros_integration: This package contains the following:
- The ros-plugin: this RTT plugin allows Orocos/RTT components to contact the ROS master
- CMake macro's to automatically create Orocos/RTT typekits and transport plugins from .msg files
rtt_ros_integration_std_msgs: This package shows how the CMake macro's have to be used, it creates the Orocos/RTT typekits and transport plugins for all roslib and std_msgs messages
rtt_ros_integration_example: This package shows how the rtt_ros_integration should be used from an Orocos/RTT user/developer point of view. It contains a HelloRobot component which can be contacted using rostopic echo
For Orocos/RTT new-commers, there are also the rtt_exercises. They can be found at https://gitorious.org/orocos-toolchain/rtt_examples ,and have native ROS build support.
If anyone has any questions please do not hesitate to contact the orocos-users, orocos-dev or ros-users mailing list.
Installation
First, install 'regular' ROS on your system following these instructions: Install
Prebuild deb packages are available for Ubuntu systems. Installation is as simple as
sudo apt-get install ros-(cturtle/diamondback)-orocos-toolchain-ros
Installation for other systems can be done through git. All code is currently on git on http://git.mech.kuleuven.be/robotics/orocos_toolchain_ros.git . You must extract the software in a (sub)directory of your ROS_PACKAGE_PATH:
cd $HOME mkdir ros cd ros export ROS_PACKAGE_PATH=$HOME/ros:$ROS_PACKAGE_PATH
Most people set that export statement in their .bashrc file, right after they sourced the 'setup.bash' file. Then in $HOME/ros:
git clone http://git.mech.kuleuven.be/robotics/orocos_toolchain_ros.git
Make sure to either check out the diamondback branch (for diamondback)
cd orocos_toolchain_ros git checkout -b diamondback origin/diamondback
or cturtle branch (for cturtle)
cd orocos_toolchain_ros git checkout -b cturtle origin/cturtle
initialise and update the git submodules
git submodule init git submodule update --recursive
and build the orocos_toolchain_ros stack
rosmake --rosdep-install orocos_toolchain_ros
Don't forget to source the Orocos specific env.sh script in order to use the orogen functionality:
. env.sh echo -e "\n. $(pwd)/env.sh" >> ~/.bashrc
This file needs to be sourced in addition to ROS's setup.bash file.
Using
The deployer, taskbrowser and any program part of OCL needs to be run with the rosrun command:
rosrun ocl deployer-gnulinux
You should now proceed to the Orocos Toolchain Main Page for further documentation and examples.
Documentation
The stack contains all of the Orocos Toolchain v2.4.x integrated in the ROS build system. The orocos_toolchain_ros stack contains utilmm, utilrb, typelib and orogen, to automatically create ros packages for the automatic typekit generation for C++ classes.
On top of the Orocos Toolchain v2.4.x this stack contains:
rtt_ros_integration: This package contains the following:
- The ros-plugin: this RTT plugin allows Orocos/RTT components to contact the ROS master
- CMake macro's to automatically create Orocos/RTT typekits and transport plugins from .msg files
rtt_ros_integration_std_msgs: This package shows how the CMake macro's have to be used, it creates the Orocos/RTT typekits and transport plugins for all roslib and std_msgs messages
rtt_ros_integration_example: This package shows how the rtt_ros_integration should be used from an Orocos/RTT user/developer point of view. It contains a HelloRobot component which can be contacted using rostopic echo
For Orocos/RTT new-commers, there are also the rtt_exercises. They can be found at https://gitorious.org/orocos-toolchain/rtt_examples ,and have native ROS build support.
If anyone has any questions please do not hesitate to contact the orocos-users, orocos-dev or ros-users mailing list.
Installation
First, install 'regular' ROS on your system following these instructions: Install
Prebuild deb packages are available for Ubuntu systems. Installation is as simple as
sudo apt-get install ros-(cturtle/diamondback)-orocos-toolchain-ros
Installation for other systems can be done through git. All code is currently on git on http://git.mech.kuleuven.be/robotics/orocos_toolchain_ros.git . You must extract the software in a (sub)directory of your ROS_PACKAGE_PATH:
cd $HOME mkdir ros cd ros export ROS_PACKAGE_PATH=$HOME/ros:$ROS_PACKAGE_PATH
Most people set that export statement in their .bashrc file, right after they sourced the 'setup.bash' file. Then in $HOME/ros:
git clone http://git.mech.kuleuven.be/robotics/orocos_toolchain_ros.git
Make sure to either check out the diamondback branch (for diamondback)
cd orocos_toolchain_ros git checkout -b diamondback origin/diamondback
or cturtle branch (for cturtle)
cd orocos_toolchain_ros git checkout -b cturtle origin/cturtle
initialise and update the git submodules
git submodule init git submodule update --recursive
and build the orocos_toolchain_ros stack
rosmake --rosdep-install orocos_toolchain_ros
Don't forget to source the Orocos specific env.sh script in order to use the orogen functionality:
. env.sh echo -e "\n. $(pwd)/env.sh" >> ~/.bashrc
This file needs to be sourced in addition to ROS's setup.bash file.
Using
The deployer, taskbrowser and any program part of OCL needs to be run with the rosrun command:
rosrun ocl deployer-gnulinux
You should now proceed to the Orocos Toolchain Main Page for further documentation and examples.
As of the ROS electric release, the orocos_toolchain_ros stack is split up in 5 different stacks:
orocos_toolchain: containing the bare orocos packages
rtt_ros_integration (now a stack!): containing all orocos-ros integration code
rtt_geometry: containing integration code for working with orocos and tf
rtt_ros_comm: RTT typekits for the ros_comm messages
rtt_common_msgs: RTT typekits for the common_msgs messages
Coming soon: the orocos_toolchain_ros stack will be available in electric as a metapackage to provide a convenient way to install all stacks at once.
Installation
Ubuntu
sudo aptitude install ros-electric-orocos-toolchain ros-electric-rtt-ros-integration ros-electric-rtt-ros-comm ros-electric-rtt-common-msgs ros-electric-rtt-geometry
And source the env.sh script after installation (you might want to add this to your .bashrc file)
source `rosstack find orocos_toolchain`/env.sh
Compiling from source
git clone --recursive git://gitorious.org/orocos-toolchain/orocos_toolchain.git git clone http://git.mech.kuleuven.be/robotics/rtt_ros_integration.git git clone http://git.mech.kuleuven.be/robotics/rtt_ros_comm.git git clone http://git.mech.kuleuven.be/robotics/rtt_common_msgs.git git clone http://git.mech.kuleuven.be/robotics/rtt_geometry.git roscd orocos_toolchain git submodule init git submodule update source env.sh rosmake orocos_toolchain rtt_ros_integration rtt_ros_comm rtt_common_msgs rtt_geometry
As of the ROS electric release, the orocos_toolchain_ros stack is split up in 5 different stacks:
orocos_toolchain: containing the bare orocos packages
rtt_ros_integration (now a stack!): containing all orocos-ros integration code
rtt_geometry: containing integration code for working with orocos and tf
rtt_ros_comm: RTT typekits for the ros_comm messages
rtt_common_msgs: RTT typekits for the common_msgs messages
With Ubuntu
sudo apt-get install ros-fuerte-orocos-toolchain ros-fuerte-rtt-ros-integration ros-fuerte-rtt-geometry ros-fuerte-rtt-ros-comm ros-fuerte-rtt-common-msgs
Don't forget to add source orocos_toolchain/env.sh to your environment when you want to use OROCOS packages.
With rosinstall
If you do not already have a ros workspace, create one:
export ROS_WORKSPACE=~/path/to/workspace mkdir $ROS_WORKSPACE cd $ROS_WORKSPACE rosws init . /opt/ros/fuerte
Navigate to your ros workspace, and add the orocos sources:
roscd rosws set -y orocos/orocos_toolchain --git git://gitorious.org/orocos-toolchain/orocos_toolchain.git -v fuerte rosws set -y orocos/rtt_ros_integration --git http://git.mech.kuleuven.be/robotics/rtt_ros_integration.git -v fuerte rosws set -y orocos/rtt_ros_comm --git http://git.mech.kuleuven.be/robotics/rtt_ros_comm.git -v fuerte rosws set -y orocos/rtt_common_msgs --git http://git.mech.kuleuven.be/robotics/rtt_common_msgs.git -v fuerte rosws set -y orocos/rtt_geometry --git http://git.mech.kuleuven.be/robotics/rtt_geometry.git -v fuerte rosws update rosws regenerate source setup.sh
Build the packages:
roscd orocos_toolchain source env.sh rosdep install orogen rosmake orocos_toolchain rtt_ros_integration rtt_ros_comm rtt_common_msgs rtt_geometry
Don't forget to add source orocos_toolchain/env.sh to your environment when you want to use OROCOS packages.
Manual Installation
Compiling from source
mkdir $HOME/rosstacks echo "export ROS_PACKAGE_PATH=\$ROS_PACKAGE_PATH:\$HOME/rosstacks" >> ~/.bashrc export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$HOME/rosstacks cd $HOME/rosstacks
Ubuntu 12.04 (Precise)
sudo apt-get install libreadline-dev omniorb omniidl omniorb-nameserver libomniorb4-1 libomniorb4-dev libomnithread3-dev libomnithread3c2 gccxml antlr libantlr-dev libxslt1-dev liblua5.1-0-dev ruby1.8-dev libruby1.8 rubygems1.8
git clone --recursive -b fuerte git://gitorious.org/orocos-toolchain/orocos_toolchain.git git clone -b fuerte http://git.mech.kuleuven.be/robotics/rtt_ros_integration.git git clone -b fuerte http://git.mech.kuleuven.be/robotics/rtt_ros_comm.git git clone -b fuerte http://git.mech.kuleuven.be/robotics/rtt_common_msgs.git git clone -b fuerte http://git.mech.kuleuven.be/robotics/rtt_geometry.git roscd orocos_toolchain # Checkout the fuerte branch for ROS Fuerte: git checkout fuerte git submodule init git submodule update source env.sh rosmake orocos_toolchain rtt_ros_integration rtt_ros_comm rtt_common_msgs rtt_geometry
Debian Squeeze
sudo apt-get install libreadline-dev omniorb omniidl omniorb-nameserver libomniorb4-1 libomniorb4-dev libomnithread3-dev libomnithread3c2 gccxml antlr libantlr-dev libxslt1-dev liblua5.1-0-dev ruby1.8-dev libruby1.8 rubygems1.8 libcppunit-dev sip4
git clone --recursive git://gitorious.org/orocos-toolchain/orocos_toolchain.git git clone http://git.mech.kuleuven.be/robotics/rtt_ros_integration.git git clone http://git.mech.kuleuven.be/robotics/rtt_ros_comm.git git clone http://git.mech.kuleuven.be/robotics/rtt_common_msgs.git git clone http://git.mech.kuleuven.be/robotics/rtt_geometry.git roscd orocos_toolchain git submodule init git submodule update source env.sh
roscd ocl nano manifest.xml
Edit manifest.xml and add following line:
<depend package="roslib"/>
after line 12.
roscd ocl nano CMakeLists.txt
Edit CMakeLists.txt and uncomment following lines (123-126):
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) rosbuild_init() rosbuild_find_ros_package( rtt ) set( RTT_HINTS HINTS ${rtt_PACKAGE_PATH}/install )
Now orocos_toolchain_ros can be compiled:
rosmake orocos_toolchain rtt_ros_integration rtt_ros_comm rtt_common_msgs rtt_geometry
As of the ROS electric release, the orocos_toolchain_ros stack is split up in 5 different stacks:
orocos_toolchain: containing the bare orocos packages
rtt_ros_integration (now a stack!): containing all orocos-ros integration code
rtt_geometry: containing integration code for working with orocos and tf
rtt_ros_comm: RTT typekits for the ros_comm messages
rtt_common_msgs: RTT typekits for the common_msgs messages
With Ubuntu
sudo apt-get install ros-groovy-orocos-toolchain ros-groovy-rtt-ros-integration ros-groovy-rtt-geometry ros-groovy-rtt-ros-comm ros-groovy-rtt-common-msgs
Don't forget to add source orocos_toolchain/env.sh to your environment when you want to use OROCOS packages.
With rosinstall
If you do not already have a ros workspace, create one:
export ROS_WORKSPACE=~/path/to/workspace mkdir $ROS_WORKSPACE cd $ROS_WORKSPACE rosws init . /opt/ros/fuerte
Navigate to your ros workspace, and add the orocos sources:
roscd rosws set -y orocos/orocos_toolchain --git git://gitorious.org/orocos-toolchain/orocos_toolchain.git -v groovy rosws set -y orocos/rtt_ros_integration --git http://git.mech.kuleuven.be/robotics/rtt_ros_integration.git -v groovy rosws set -y orocos/rtt_ros_comm --git http://git.mech.kuleuven.be/robotics/rtt_ros_comm.git -v groovy rosws set -y orocos/rtt_common_msgs --git http://git.mech.kuleuven.be/robotics/rtt_common_msgs.git -v groovy rosws set -y orocos/rtt_geometry --git http://git.mech.kuleuven.be/robotics/rtt_geometry.git -v groovy rosws update rosws regenerate source setup.sh
Build the packages:
roscd orocos_toolchain source env.sh rosdep install orogen rosmake orocos_toolchain rtt_ros_integration rtt_ros_comm rtt_common_msgs rtt_geometry
Don't forget to add source orocos_toolchain/env.sh to your environment when you want to use OROCOS packages.
With catkin
IN PROGRESS
Create a catkin workspace if it doesn't already exist and navigate to the source directory:
mkdir -p ~/ws/orocos/src cd ~/ws/orocos/src
Clone the orocos toolchain and build it with catkin_make_isolated:
git clone --recursive git://gitorious.org/orocos-toolchain/orocos_toolchain.git cd .. catkin_make_isolated --install
Source the setup file for the orocos underlay:
source install_isolated/setup.bash
Create the workspace for catkin packages:
mkdir -p ~/ws/my_project
Since the ROS Hydro release, the Orocos ROS integration has been reorganized to reside entirely in the rtt_ros_integration repository.
Please see rtt_ros_integration for more information.