-
Notifications
You must be signed in to change notification settings - Fork 10
RosConversion
The goal of this tutorial is to make a message convertible from CS::APEX to ROS format.
We first create a new ROS message type to convert to.
Firstly, add the following lines to your package.xml
:
<build_depend>csapex_ros</build_depend>
<run_depend>csapex_ros</run_depend>
<build_depend>message_generation</build_depend>
<run_depend>message_runtime</run_depend>
This allows us to generate a new ROS message and imports the later needed csapex_ros
package.
Next create a directory msg
next to src
and include
.
Now you can add the ROS message. Create a file msg/TutorialMessage.msg
and fill it with the following text:
# Tutorial Message
bool value
Now change the CMakeLists.txt
to match the following:
find_package(catkin REQUIRED COMPONENTS
csapex
csapex_opencv
csapex_ros
message_generation
)
add_message_files(
FILES
TutorialMessage.msg
)
generate_messages(
)
catkin_package(
INCLUDE_DIRS include
LIBRARIES csapex_tutorial
CATKIN_DEPENDS message_runtime
)
This will generate a ROS message. You can verify that everything worked by calling
rosmsg show TutorialMessage
which should give you the output
[csapex_tutorial/TutorialMessage]:
bool value
Now we can convert between the cs::APEX version of TutorialMessage
and the ROS version.
We achieve this by extending the previously created CorePlugin to register the ROS conversion:
/// PROJECT
#include <csapex/core/core_plugin.h>
#include <csapex/utility/register_apex_plugin.h>
#include <csapex/profiling/timer.h>
#include <csapex_ros/ros_message_conversion.h>
#include <csapex_tutorial/TutorialMessage.h>
#include <csapex_tutorial/tutorial_message.h>
namespace csapex
{
namespace tutorial
{
struct ConvertTutorialMessage
{
static typename connection_types::TutorialMessage::Ptr ros2apex(const typename csapex_tutorial::TutorialMessage::ConstPtr &ros_msg) {
typename connection_types::TutorialMessage::Ptr out(new connection_types::TutorialMessage);
out->value = ros_msg->value;
return out;
}
static typename csapex_tutorial::TutorialMessage::Ptr apex2ros(const typename connection_types::TutorialMessage::ConstPtr& apex_msg) {
typename csapex_tutorial::TutorialMessage::Ptr out(new csapex_tutorial::TutorialMessage);
out->value = apex_msg->value;
return out;
}
};
class RegisterPlugin : public CorePlugin
{
public:
RegisterPlugin()
: timer("Application Duration")
{}
virtual void init(CsApexCore& core) override
{
timer.restart();
RosMessageConversion::registerConversion<csapex_tutorial::TutorialMessage, connection_types::TutorialMessage, ConvertTutorialMessage>();
}
virtual void shutdown() override
{
timer.finish();
long duration_ms = timer.stopTimeMs() - timer.startTimeMs();
std::cerr << "the program ran for " << (duration_ms / 1000.) << " seconds" << std::endl;
}
private:
csapex::Timer timer;
};
} // namespace tutorial
} // namespace csapex
CSAPEX_REGISTER_CLASS(csapex::tutorial::RegisterPlugin, csapex::CorePlugin)
The struct ConvertTutorialMessage
performs the conversion.
For more complex messages, this might entail more work, but for this simple example there is only one data member to copy.
The registration is done by calling
RosMessageConversion::registerConversion<csapex_tutorial::TutorialMessage, connection_types::TutorialMessage, ConvertTutorialMessage>();
with the ROS type csapex_tutorial::TutorialMessage
, the cs::APEX type connection_types::TutorialMessage
and the converter struct ConvertTutorialMessage
.
To test the ROS export, first start a roscore
.
You can now test the ROS export using the example configuration Tutorials
/ Plug-in Creation
/ 03 - ROS Export
.
Running
rostopic echo /csapex/export -n 1
should print
value: True
---