Bi-directional communication bridge between ROS and JAUS. ROS/Jaus messages are translated to Jaus/ROS messages and then sent to specific ROS topic or Jaus address.
Every message translation from one message type (e.g. ROS geometry_msgs/Pose) to other message type (e.g. openjaus/mobility/SetLocalPose) and vice versa is performed by specific translation plugin. User can write its own plugins to fulfil its needs regarding message translations.
Compiled translations plugins are loaded automatically and are used by bridge when they are needed.
This repository contains of three packages:
- ros_custom_msgs,
- bridge_plugins,
- ros-jaus-bridge.
See detailed information and usage instructions of each package below.
It is ROS package, which can be used to build ROS custom messages. It is not obligatory to use this package. User can use its own package to create and generate ROS custom messages.
Usage:
1.Place your custom ROS msg file in msg directory.
2.Open CMakeLists.txt file and add your msg file name to add_message_files(...) function, e.g.
add_message_files(
FILES
MyRosMessage.msg
)
Do not forget to add *.msg extension!
3.Build package with catkin.
4.Your custom message header file will be placed in ROS workspace devel/include directory.
This package (directory) contains all example translations plugins.
Creating custom bridge plugin:
Bridge plugins are based on Qt plugins, so to create custom plugin Qt library should be installed in system.
1.Copy and paste PluginTemplate directory. Rename it to your plugin name, e.g. MyPlugin.
2.Rename file PluginTemplate.json to your plugin name, e.g. MyPlugin.json.
3.You can open this file and change plugin version.
{
"version": "1.0"
}
4.Rename files include/plugin_template.h and src/plugin_template.cpp to your plugin name, e.g. my_plugin.h, my_plugin_cpp. 5.Rename PluginTemplate.pro to MyPlugin.pro. 6.Edit file MyPlugin.pro and set correct paths to files:
SOURCES += src/my_plugin.cpp
HEADERS += include/my_plugin.h
7.Open include/my_plugin.h file.
Each plugin should inherit from QObject and PluginInterface classes and each plugin should override virtual functions declared in PluginInterface class:
- getType(),
- translateJausMsg(),
- translateRosMsg(),
- getMaintainer().
Plugin should also use Q_PLUGIN_METADATA macro to specify plugin *.json file.
Important:
User should also declare metatypes of ROS and JAUS message types, which will be used for translation, e.g.:
Q_DECLARE_METATYPE(openjaus::mobility::SetLocalPose)
Q_DECLARE_METATYPE(geometry_msgs::Pose)
Complete example header file should look like this:
#ifndef MY_PLUGIN_H
#define MY_PLUGIN_H
#include <openjaus/mobility.h>
#include <geometry_msgs/Pose.h>
#include <tf/tf.h>
#include "../plugin_interface/plugin_interface.h"
Q_DECLARE_METATYPE(openjaus::mobility::SetLocalPose)
Q_DECLARE_METATYPE(geometry_msgs::Pose)
class MyPlugin : public QObject, public PluginInterface
{
Q_OBJECT
Q_PLUGIN_METADATA(IID "rj_bridge.PluginInterface" FILE "MyPlugin.json")
Q_INTERFACES(PluginInterface)
public:
PluginType getType() override;
QVariant translateJausMsg(QVariant msg) const override;
QVariant translateRosMsg(QVariant msg) const override;
std::string getMaintainer() const override;
};
#endif // MY_PLUGIN_H
8.Open src/my_plugin.cpp.
In this file all functions should be defined.
getMaintainer() function: this function should return std::string with plugin's maintainer name, e.g.
std::string MyPlugin::getMaintainer() const
{
return std::string{"MyTheBestCompany"};
}
getType() function: this function should return plugin type. Plugin type can be retrieved by translateType() template function defined in PluginInterface class. First argument of template should be ROS message type, second argument should be Jaus message type, e.g.:
PluginType MyPlugin::getType()
{
return translateType<geometry_msgs::Pose, openjaus::mobility::SetLocalPose>();
}
translateRosMsg() and translateJausMsg() functions: this two functions perform main action of plugin which is translating ROS or Jaus messages. Message is received in QVariant object and should be casted to appropriate ROS or Jaus message type. After translation message is also returned in QVariant object. Please see example plugins to get familiar with this mechanism.
9.Build plugin in QtCreator. As build product you will receive library file *.so. All library files should be then copied to common directory, e.g.: /home/user/bridge_plugins.
This is ROS package, which loads plugins and creates ROS<->JAUS bridge(s).
Usage:
1.Open file src/bridge/rj_bridge_node.cpp.
2.Main object of bridge is BridgeCore. Constructor of this objects takes four parameters. You can set bridge ROS node name in third parameter and plugins localization path (localization of *.so files) in fourth parameter.
BridgeCore bridge_core(argc, argv, "ros_jaus_bridge", "/home/user/bridge_plugins/");
3.Then you can create bridges which you want. For example to create bridge from ROS to JAUS:
bridge_core.createBridgeR2J<geometry_msgs::Pose,
openjaus::mobility::SetLocalPose>("local_pose", "jaus_cmp_local_pose");
This is template function: first template parameter should be ROS message type, and second parameter should be Jaus message type.
This function takes two parameters. In first you can specify to which ROS topic bridge should subscribe and wait for ROS messages. Second parameters specifies Jaus destination address. When message is received on specified ROS topic it gets translated to Jaus message and then send to specified Jaus address.
4.To create Jaus->ROS bridge you should use createBridgeJ2R() function, e.g.:
bridge_core.createBridgeJ2R<openjaus::mobility::SetWrenchEffort,
rj_bridge_ros_msgs::SetWrenchEffort>("wrench_effort_ros", "wrench_effort_out");
In this template function first template parameter should be Jaus message type, second template parameter should be ROS message type. Same like createBridgeR2J(), this function also takes two parameters. In first you should specify name of bridge's Jaus component (other Jaus components will send messages to this address), in second you should set ROS output topic (where bridge should publish ROS messages).
5.It is also necessary to declare metatypes of used ROS and Jaus message types:
Q_DECLARE_METATYPE(openjaus::mobility::SetWrenchEffort)
Q_DECLARE_METATYPE(rj_bridge_ros_msgs::SetWrenchEffort)
Q_DECLARE_METATYPE(geometry_msgs::Pose)
Q_DECLARE_METATYPE(openjaus::mobility::SetLocalPose)
6.When everything is set you can run bridge. You can specify ROS node loop rate in parameter.
bridge_core.run(10);
7.Build this package using catkin and run it:
rosrun rj_bridge rj_bridge