-
Notifications
You must be signed in to change notification settings - Fork 2
Home
This repository contains material for a basic Talker / Listener tutorial for OROCOS (2.x) similarly to ROS WritingPublisherSubscriber. There is even a communication between ROS and OROCOS Talkers / Listeners in the last part of this tutorial.
- Creating Components
- Using ports and properties
- Deploying components and periodicity changing
- Connecting to ROS
A C++ framework for component-based robot control
- Features that we use
- Multi-platform (Linux, Windows, Mac)
- Extension to robotics framework : ROS / Rock / Yarp
- Run-time and realtime configurable
- Integrated state-machine (FSM or rFSM)
- Part of the tools that we use
- RTT : RealTime Toolkit : realtime environment running components
- OCL : Orocos Component Library : setting up applications
- Component
- All components run in a single process in single computer mode
- Multi-process mode uses interprocess dataflow (MQueue)
- 1 component = 1 thread allocated for the execution engine
- Local and remote (seen by peers) ports
- Scripting
- OPS (Orocos Program Script): RT functional prog. calls method/sends command
- OSD (Orocos State-machine Description)
- Lua
- Deployment
- Components are imported, loaded, configured, connected, started
- Services loaded and installed, Peers added
- Unloading only if not running
- Protection on bad connecting request (input to input)
PUT A PICTURE HERE
- Task State (Init / Stopped / PreOperational / Running)
- Task Code
- configureHook
- startHook
- updateHook
- stopHook
- cleanupHook
- Activity : periodic or even-based
- Properties
- Ports / Event Ports : Basic types (int, float, string) or TypeKit based
more details http://www.orocos.org/stable/documentation/rtt/v2.x/doc-xml/orocos-components-manual.html
- Services
- Provide functionality to a component
- Can be added afterwards to the component at configuration time
- Composed of one or more Operations
- Operations
- Define the function
- Can run in Caller (client) or in Target (Own) thread
- Called (blocking) similar to rosservice or Sent (non-blocking) similar but simpler than actionlib
more details http://www.orocos.org/stable/documentation/rtt/v2.x/doc-xml/orocos-components-manual.html
Lua scripting language is used
- The Deployer is the top level component
- Only the Deployer can deploy other components
- All its components are its peers
- A component can also have peers
- Common commands
- require : loads services
- import : import components (like including a class) and typekits (like including a type)
- loadComponent : instantiate a component
- setActivity : set the periodicity of a component
- getPeer : access a component instance
- provides : access loaded services
more info http://www.orocos.org/wiki/orocos/toolchain/luacookbook
http://www.orocos.org/stable/documentation/rtt/v2.x/doc-xml/orocos_cheat_sheet.pdf
A Talker/Listener scheme will help discover different aspects
- Creating Components
- Using ports and properties
- Deploying components and periodicity changing
- Connecting to ROS
We suppose you have the orocos_toolchain installed as well as rtt_ros_integration metapackage
If you already did the ROS tutorials WritingPublisherSubscriber http://wiki.ros.org/ROS/Tutorials/WritingServiceClient%28c%2B%2B%29 , skip this part as we use the same workspace
To simplify, we copy paste the commands from there
source /opt/ros/indigo/setup.bash
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
catkin_init_workspace
cd ~/catkin_ws/
catkin build
Similarly to ROS CreatingPackage, there is a way to create orocos packages for catkin
orocreate-catkin-pkg <package> [type]
The only difference is that we cannot set the dependencies but can define which type of OROCOS object we want. Can be components, services, typekits, etc...
We need 2 components, a talker and a listener
cd ~/catkin_ws/src
orocreate-catkin-pkg rtt_talker component
orocreate-catkin-pkg rtt_listener component
cd ~/catkin_ws/src/rtt_talker/src
- At the top add includes permitting to declare ports
#include <rtt/Port.hpp>
#include <std_msgs/String.h>
- In the class add a port declaration and some internal storage places
protected :
RTT::OutputPort <std_msgs::String> output_port;
int init_count;
private :
int count;
std_msgs::String msg;
std::stringstream sstream;
- In the Constructor() instantiate a property and a port
init_count = 0;
this->addProperty("init_count", init_count);
ports()->addPort("Out", output_port);
- In the configureHook() initialize the counter
count = init_count;
- Add the publishing to the updateHook()
// DONT INITIALIZE MEM at RUNTIME std_msgs::String msg ;
// DONT INITIALIZE MEM at RUNTIME std::stringstream sstream ;
std::cout << "Rtt_talker talking !" << std::endl;
sstream << "hello world" << count;
msg.data = sstream.str();
output_port.write(msg);
sstream.str(std::string());
sstream.clear();
++count;
cd ~/catkin_ws/src/rtt_listener/src
- At the top add includes permitting to declare ports
#include <rtt/Port.hpp>
#include <std_msgs/String.h>
- In the class add a port declaration and some internal storage places
protected:
RTT::InputPort <std_msgs::String> input_port;
private :
std_msgs::String msg;
- Instantiate a port in the Constructor()
ports()->addPort("In", input_port);
- Read and print the incoming message in the updateHook()
// DONT INITIALIZE MEM at RUNTIME std_msgs::String msg;
std::cout << "Rtt_listener listening !" << std::endl;
if (input_port.read(msg) == RTT::NewData)
{
std::cout << "I heard : [" << msg.data << "]" << std::endl;
}
- Access the deployer and import all the required components
require "rttlib"
require "rttros"
tc = rtt.getTC()
d = tc:getPeer("Deployer")
-- ROS integration
d:import("rtt_rosnode")
d:import("rtt_roscomm")
--d:import("rtt_std_msgs")
d:import("rtt_talker")
d:import("rtt_listener")
- Instantiate a Listener, set its activity to be 0 (non-periodic), and configure it
--listener
lstname ="LST"
d:loadComponent(lstname, "Rtt_listener")
d:setActivity(lstname, 0.0, 10, rtt.globals.ORO_SCHED_RT)
lst = d:getPeer(lstname)
lst:configure()
- Instantiate a Talker, set its activity to 10 Hz
--talker
tlkname = "TLK"
d:loadComponent(tlkname, "Rtt_talker")
d:setActivity(tlkname, 0.1 , 10, rtt.globals.ORO_SCHED_RT)
tlk = d:getPeer(tlkname)
--myprop = tlk:getProperty("init_count")
--myprop:set(200)
tlk:configure()
- Connect the components together (and prepare connection to ROS for next steps), and start them
-- connection
d:connect("TLK.Out", "LST.In", rtt.Variable("ConnPolicy"))
-- connect to ros
--local ros = rtt.provides("ros")
--d:stream("TLK.Out", ros:topic("/chatter"))
--d:stream("LST.In", ros:topic("/chatter")))
lst:start()
tlk:start()
catkin build
(in another terminal) source ~/catkin_ws/devel/setup.bash
roscore
(in another terminal) source ~/catkin_ws/devel/setup.bash
cd ~/catkin_ws/src
rttlua -i deploy.lua
What do you notice ? Hover this text to find out
Change the periodicity of the listener to make it poll every second on the input
d:setActivity(lstname, 1, 10, rtt.globals.ORO_SCHED_RT)
Is it working ? What happens ? Hover this text to find out
Change the periodicity of the listener back to 0
d:setActivity(lstname, 1, 0, rtt.globals.ORO_SCHED_RT)
Make the Port Event-based in the listener
ports()->addEventPort("In", input_port);
Recompile and Redeploy
catkin build
rttlua -i deploy.lua
Is it working ? Hover this text to find out
Comment out
myprop=tlk:getProperty("init_count")
myprop:set(200)
Did you notice the change ?
Comment out ROS Out stream connection and the typekit
d:import("rtt_std_msgs")
d:stream("TLK.Out",ros:topic("/chatter"))
Start the ROS listener first then Lua deployer
rosrun beginner_tutorials listener
rttlua -i deploy.lua
What do you notice ? Hover this text to find out
Comment ROS Out stream connection and talker and comment out ROS In stream connection, also stop the OROCOS talker
--d:stream("TLK.Out",ros:topic("/chatter"))
d:stream("LST.In",ros:topic("/chatter"))
--tlk:start()
Start the Lua deployer first then ROS talker
rttlua -i deploy.lua
rosrun beginner_tutorials talker
What do you notice ? Hover this text to find out