Skip to content

Commit

Permalink
Merge pull request #11 from DriesDM/feature/ros-integration-tutorials
Browse files Browse the repository at this point in the history
Add ROS1 integration tutorials
  • Loading branch information
DriesDM committed Sep 28, 2020
2 parents a0a2b09 + 28da6f5 commit 6933049
Show file tree
Hide file tree
Showing 4 changed files with 306 additions and 3 deletions.
158 changes: 157 additions & 1 deletion docs/ros_integration/tutorial_ros1_2_topics.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,160 @@ with ROS through Orocos ports / ROS topics.
please refer to the first tutorial
:doc:`Installation <tutorial_ros1_1_installation>`.

Let's start from a new console
These tutorials assume you have a working knowledge of Orocos components, if not
read :ref:`orocos-component-builders-manual` or follow the basic
:doc:`RTT tutorials <../rtt/tutorials>`.

In this tutorial we will show you how to connect Orocos ports to ros topics. We
will create a component with an InputPort and an OutputPort over which ``std_msgs``
are transported. We will need the help of ``rtt_std_msgs`` to create the correct
transports.

Component header file:

.. code-block:: cpp
#ifndef STANDARDCOMPONENT_H
#define STANDARDCOMPONENT_H
#include <rtt/RTT.hpp>
#include <rtt/Component.hpp>
#include <std_msgs/Bool.h>
#include <std_msgs/Int32.h>
class StandardComponent:
public RTT::TaskContext
{
public:
/// Constructor
StandardComponent(std::string const& name);
/// Destructor
~StandardComponent(){}
private:
RTT::InputPort<std_msgs::Bool> input;
RTT::OutputPort<std_msgs::Int32> output;
int counter;
std_msgs::Bool incoming_msg;
public:
/// Configure
bool configureHook();
/// Update
void updateHook();
};
#endif // StandardComponent_H
Component cpp file:

.. code-block:: cpp
#include <orocos_ros_communication/StandardComponent.h>
StandardComponent::StandardComponent(std::string const& name)
: RTT::TaskContext(name)
, input("input")
, output("output")
, counter(0)
{
this->ports()->addEventPort("input", input).doc("Input port which is read in the updateHook");
this->ports()->addPort("output", output).doc("Data producing output port");
}
bool StandardComponent::configureHook()
{
return input.connected();
}
void StandardComponent::updateHook()
{
RTT::log(RTT::Info) << "Waking up!" << RTT::endlog();
if(input.read(incoming_msg) == RTT::NewData)
{
counter++;
std_msgs::Int32 out_msg;
out_msg.data = counter;
output.write(out_msg);
}
}
ORO_CREATE_COMPONENT(StandardComponent)
This component has two ports, an input port for ``std_msgs::Bool`` messages,
and an output port that writes ``std_msgs::Int32`` messages. The input port
was added as an event port such that an incoming message will trigger the
``updateHook`` of our component. In the ``updateHook`` a counter is incemented
and written to the output port.

We can deploy, as always, with an ``start.ops`` file:

.. code-block:: none
import("orocos_ros_communication")
import("rtt_rosnode")
import("rtt_roscomm")
import("rtt_std_msgs")
loadComponent("my_component", "StandardComponent")
stream("my_component.input", ros.comm.topic("some_namespace/component_input"))
stream("my_component.output", ros.comm.topic("some_namespace/component_output"))
my_component.configure()
my_component.start()
The first line just imports our component library. The ``rtt_rosnode`` import will
create a ros_node for the deployer, you can check with ``rosnode list`` in the terminal.

The ``rtt_roscomm`` import gives us the tools to connect the ports to topics, and
the ``rtt_std_msgs`` provides the required typekits.

We can then connect the input and output ports to ros topics as follows:

.. code-block:: none
stream("my_component.input", ros.comm.topic("component_input"))
stream("my_component.output", ros.comm.topic("component_output"))
In order for this to work, there must be a ros master running. You can also use a launch
file to deploy this start script, making use of the ``rtt_ros`` package, for example:

.. code-block:: xml
<launch>
<include file="$(find rtt_ros)/launch/deployer.launch">
<arg name="DEPLOYER_ARGS" value="-s $(find orocos_ros_communication)/start/start.ops"/>
<arg name="LOG_LEVEL" value="info"/>
<arg name="DEBUG" value="false"/>
</include>
</launch>
.. _custom-rtt-messages:

Defining custom messages
------------------------

In the example above we have used the ``std_msgs``, and their rtt typekits from ``rtt_std_msgs``.
You can also use custom ROS messages. Fox example, when you have a package ``my_msgs``
with ``.msg`` and ``.srv`` files, you can make their types available using ``create_rtt_msgs`` of
the ``rtt_roscomm`` package:

.. code-block:: bash
rosrun rtt_roscomm create_rtt_msgs my_msgs
This will create a ``rtt_my_msgs`` package with a ``CMakeLists.txt``, and ``package.xml`` file.
When you want to connect the ports to ros topics with the deployer, just import the package in
the ``.ops`` file:

.. code-block:: none
import("rtt_my_msgs")
147 changes: 147 additions & 0 deletions docs/ros_integration/tutorial_ros1_3_services.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,147 @@
============================
Orocos/ROS Services tutorial
============================

This tutorial will teach how to set up an Orocos component to expose its
Operations as ROS services.

.. note::

If you don't have a working version of Orocos + ROS installed in your system,
please refer to the first tutorial
:doc:`Installation <tutorial_ros1_1_installation>`.


These tutorials assume you have a working knowledge of Orocos components, if not
read :ref:`orocos-component-builders-manual` or follow the basic
:doc:`RTT tutorials <../rtt/tutorials>`.

In this tutorial we will show you how to expose the operations of your Orocos
component as ROS services.

In general the signature of the operation you want to expose as a ROS service will
have to adhere to the typical ROS service callback:

.. code-block:: cpp
bool operation(Service::Request&, Service::Response&);
.. note::

If you want to use custom ROS services, see :ref:`custom-rtt-messages`.

Take for example the following component:

Header file:

.. code-block:: cpp
#ifndef STANDARDCOMPONENT_H
#define STANDARDCOMPONENT_H
#include <rtt/RTT.hpp>
#include <rtt/Component.hpp>
#include <my_msgs/MyService.h>
class StandardComponent:
public RTT::TaskContext
{
public:
/// Constructor
StandardComponent(std::string const& name);
/// Destructor
~StandardComponent(){}
bool myOperation(my_msgs::MyService::Request& request, my_msgs::MyService::Response& response)
{
response.success = false;
if (request.data)
{
response.success = true;
}
return true;
}
/// Configure
bool configureHook();
/// Update
void updateHook();
};
#endif // StandardComponent_H
And cpp file:

.. code-block:: cpp
#include <orocos-ros-services/StandardComponent.h>
StandardComponent::StandardComponent(std::string const& name)
: RTT::TaskContext(name)
{
this->provides("simple_service")->addOperation("myOperation", &StandardComponent::myOperation, this, RTT::ClientThread);
}
bool StandardComponent::configureHook()
{
return true;
}
void StandardComponent::updateHook()
{
RTT::log(RTT::Info) << "Waking up!" << RTT::endlog();
}
ORO_CREATE_COMPONENT(StandardComponent)
That exposes an operation using the ``MyService`` type from the ``my_msgs`` package.

We can deploy with the following script:

.. code-block:: none
import("orocos-ros-services")
import("rtt_rosnode")
import("rtt_roscomm")
import("rtt_std_srvs")
import("rtt_my_msgs")
loadComponent("my_component", "StandardComponent")
// load the rosservice service in the component
loadService("my_component", "rosservice")
// connect the operation to the ros service:
my_component.rosservice.connect("simple_service.myOperation", "/my_namespace/my_operation", "my_msgs/MyService")
Operations can also be exposed as ROS services without having to adher to the typical
``bool operation(Service::Request& request, Service::Response& response)`` interface, with
the use of wrappers. For the services in ``std_srvs`` the following operation signatures are
supported:

.. code-block:: none
std_srvs/Empty:
- bool empty() // The service call fails if empty() returns false!
// Use std_srvs/Trigger if the result should be returned as the response.
- void empty()
std_srvs/SetBool:
- bool setBool(bool, std::string &message_out)
- bool setBool(bool) // response.message will be empty
- std::string setBool(bool) // response.success = true
- void setBool(bool) // response.success = true and response.message will be empty
std_srvs/Trigger:
- bool trigger(std::string &message_out)
- bool trigger() // response.message will be empty
- std::string trigger() // response.success = true
This can be extended to other ros service types, see the header files in the
`rtt_std_srvs <https://github.com/orocos/rtt_ros_integration/tree/toolchain-2.9/typekits/rtt_std_srvs>`_
package.
2 changes: 1 addition & 1 deletion docs/ros_integration/tutorials.rst
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ ROS 1 integration

tutorial_ros1_1_installation
tutorial_ros1_2_topics
tutorials_ros1
tutorial_ros1_3_services


ROS 2 integration
Expand Down
2 changes: 1 addition & 1 deletion docs/rtt/orocos-components-manual.rst
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
.. _orocos-component-builders-manual
.. _orocos-component-builders-manual:

=====================================
The Orocos Component Builder's Manual
Expand Down

0 comments on commit 6933049

Please sign in to comment.