OpenRTM-aistのデータポートでは以下のようにデータをバイト列に変換するシリアライザ、データを送信する通信インターフェースの種類については複数の実装から選択可能です。
インターフェース型が選択可能のためRTC同士だけではなく、ROSのノード、あるいはROS2のようにDDSにより通信を行うプロセスとデータのやり取りが可能になります。 またシリアライザが選択可能のため、図のようにTimedLong型をTimedLong型のような別のデータ型に変換して様々なデータ型のポートと柔軟に接続することができます。
現在はC++版、Python版で使用可能です。
以下に独自シリアライザの作成手順を記載します。
OpenRTM-aist 2.0以上が必要なため、以下の手順でソースコードからビルドを行う必要がある。
ビルド終了後、特定の場所にインストールする。
cmake-guiでCMAKE_INSTALL_PREFIXを設定するか、cmake実行時のコマンドで設定する。
cmake -DORB_ROOT=C:/workspace/omniORB-4.2.3-win64-vc141 -G "Visual Studio 16 2019" -A x64 .. -DCMAKE_INSTALL_PREFIX=C:/workspace/openrtm_install
ビルド後に、以下のコマンドでインストールする。
cmake --build .. --target INSTALL --config Release
Visual Studio上でINSTALLのプロジェクトをビルドしてもインストールできる。
独自シリアライザの実装には以下のファイルを作成する必要がある。
CMakeLists.txtにはOpenRTM-aistのパッケージの検出、動的ライブラリを生成するようにコマンドを記述します。
cmake_minimum_required (VERSION 3.0.2) project (TestSerializer VERSION 1.0 LANGUAGES CXX)
#OpenRTM-aistの検出 find_package(OpenRTM REQUIRED) #インクルードディレクトリ、リンクディレクトリ、コンパイル時のフラグの設定 include_directories(${PROJECT_BINARY_DIR}) include_directories(${PROJECT_BINARY_DIR}/idl) include_directories(${OPENRTM_INCLUDE_DIRS}) add_definitions(${OPENRTM_CFLAGS}) link_directories(${OPENRTM_LIBRARY_DIRS}) #動的リンクライブラリの生成 add_library(${PROJECT_NAME} SHARED TestSerializer.cpp) #生成するライブラリ名をTestSerializer.dll(もしくは.so)に設定 set_target_properties(${PROJECT_NAME} PROPERTIES PREFIX "") #OpenRTM-aistのライブラリとリンク target_link_libraries(${PROJECT_NAME} ${OPENRTM_LIBRARIES})
TestSerializer.cppを以下のように作成します。
#include <rtm/ByteDataStreamBase.h> #include <rtm/idl/BasicDataTypeSkel.h> #include <coil/Factory.h> #include <rtm/Manager.h> //以下はシリアライザの実装 template <class DataType> class TestSerializer : public RTC::ByteDataStream<DataType> { public: TestSerializer():m_buffer(NULL), m_length(0){}; void writeData(const unsigned char* buffer, unsigned long length) override { delete m_buffer; m_buffer = new unsigned char[length]; memcpy(m_buffer, buffer, length); m_length = length; } void readData(unsigned char* buffer, unsigned long length) const override { if (m_buffer) { memcpy(buffer, m_buffer, length); } } unsigned long getDataLength() const override { return m_length; } bool serialize(const DataType& data) override { delete m_buffer; m_buffer = new unsigned char[1]; m_buffer[0] = static_cast<unsigned char>(data.data); m_length = 1; return true; } bool deserialize(DataType& data) override { if (m_buffer) { data.data = static_cast<long>(m_buffer[0])+1; return true; } return false; } private: unsigned char* m_buffer; unsigned long m_length; }; extern "C" { //以下はモジュールロード時に呼び出される関数 DLL_EXPORT void TestSerializerInit(RTC::Manager* manager) { //以下のファクトリはデータ型ごとに登録する必要がある RTC::addSerializer<RTC::TimedLong, TestSerializer<RTC::TimedLong>>("test"); }; }
シリアライザにはwriteData関数、readData関数、getDataLength関数、serialize関数、deserialize関数を実装する必要がある。 serialize関数はRTMのデータをunsigned char型に変換して内部のバッファに保存する。 保存したデータはreadData関数で取り出すことができる。 このため、データ送信時の処理は以下のようになっている。
writeData関数は内部のバッファにバイト列のデータを書き込む関数である。 deserialize関数は内部のバッファのデータをRTMのデータ型に変換して外部の変数に渡す。 このため、データ受信時の処理は以下のようになっている。
getDataLengthは内部で保持しているデータの長さを取得する関数である。
OpenRTM-aistをソースコードからビルド、インストールした場合は環境変数が設定されていないためcmake実行時にOpenRTMConfig.cmakeの場所を指定する必要がある。
cmake -G "Visual Studio 15 2017" -A x64 .. -DOpenRTM_DIR=C:/workspace/openrtm1/build/install/2.0.0/cmake
この後Visual Studio等でビルドを行う。
上記の作業でTestSerializer.dllが生成されているはずのため、TestSerializer.dllをRTC実行時にロードして利用できるようにする。
rtc.confに以下のように記述することでロードできる。モジュール探索パスは適宜変更する。
manager.modules.load_path: . manager.modules.preload: TestSerializer.dll
データポート接続時にmarshaling_typeのオプションでシリアライザを設定できる。
manager.components.preconnect: ConsoleOut0.in?port=ConsoleIn0.out&marshaling_type=test
RT System Editorで設定する場合はdataport.marshaling_typeといパラメータで設定する。
これで独自シリアライザ(TestSerializer)が使用可能になったため、ConsoleInとConsoleOutで通信すると標準入力した数値に1を足した数値が表示される。
以下はConsoleInとConsoleOutのデータポートを接続してアクティベートするrtc.confの例。
manager.modules.load_path: . manager.modules.preload: TestSerializer.dll, ConsoleOut.dll manager.components.precreate: ConsoleOut manager.components.preconnect: ConsoleOut0.in?port=ConsoleIn0.out&marshaling_type=test manager.components.preactivation: ConsoleOut0, ConsoleIn0
OpenRTM-aist 2.0以上が必要なため、以下の手順でソースコードからビルドを行う必要がある。
独自シリアライザの実装には以下のファイルを作成する必要がある。
TestSerializer.pyを以下のように作成します。
#!/usr/bin/env python # -*- coding: euc-jp -*- import OpenRTM_aist import RTC #以下はシリアライザの実装 class TestSerializer(OpenRTM_aist.ByteDataStreamBase): def __init__(self): pass def __del__(self): pass def serialize(self, data): if data._NP_RepositoryId == RTC.TimedLong._NP_RepositoryId: bdata = str(data.data) return OpenRTM_aist.ByteDataStreamBase.SERIALIZE_OK, bdata else: return OpenRTM_aist.ByteDataStreamBase.SERIALIZE_ERROR, "" def deserialize(self, cdr, data_type): if data_type._NP_RepositoryId == RTC.TimedLong._NP_RepositoryId: data_type.data = int(cdr)+1 return OpenRTM_aist.ByteDataStreamBase.SERIALIZE_OK, data_type else: return OpenRTM_aist.ByteDataStreamBase.SERIALIZE_ERROR, data_type #以下はモジュールロード時に呼び出される関数 def TestSerializerInit(mgr): OpenRTM_aist.SerializerFactories.instance().addSerializer("test:RTC.TimedLong", # addFactory関数の第1引数で登録名を設定。以下で独自シリアライザを利用するときはこの名前を使用する。 TestSerializer, RTC.TimedLong) #OpenRTM_aist.SerializerFactory.instance().addSerializerGlobal("test", #addSerializerGlobalを使うと特定のデータ型だけではなく、全てのデータ型でTestSerializerを使用可能にする TestSerializer)
シリアライザにはserialize関数、deserialize関数を実装する必要がある。 serialize関数はRTMのデータをバイト列のデータ等に変換してリターンコードと変換後のデータを返す。
deserialize関数はバイト列のデータなどをRTMのデータに変換してリターンコードと変換後のデータを返す。
TestSerializer.pyをRTC実行時にロードして利用できるようにする。
rtc.confに以下のように記述することでロードできる。モジュール探索パスは適宜変更する。
manager.modules.load_path: . manager.modules.preload: TestSerializer.py
データポート接続時にmarshaling_typeのオプションでシリアライザを設定できる。
manager.components.preconnect: ConsoleOut0.in?port=ConsoleIn0.out&marshaling_type=test
RT System Editorで設定する場合はdataport.marshaling_typeといパラメータで設定する。
これで独自シリアライザ(TestSerializer)が使用可能になったため、ConsoleInとConsoleOutで通信すると標準入力した数値に1を足した数値が表示される。
以下はConsoleInとConsoleOutのデータポートを接続してアクティベートするrtc.confの例。
manager.modules.load_path: . manager.modules.preload: TestSerializer.py, ConsoleOut.py manager.components.precreate: ConsoleOut manager.components.preconnect: ConsoleOut0.in?port=ConsoleIn0.out&marshaling_type=test manager.components.preactivation: ConsoleOut0, ConsoleIn0
OpenRTM-aistのデータ型とROSのメッセージ型を変換するシリアライザの作成のためには、ROSTransport、ROSのヘッダーファイルのインクルード、ライブラリのリンクが必要になります。 以下のようにCMakeLists.txtでOpenRTM-aist、ROS、Boostを検出します。
#OpenRTM-aistの検出 find_package(OpenRTM 2.0 REQUIRED) find_package(ROSTransport REQUIRED)
#ROSの検出 find_package(PkgConfig REQUIRED) pkg_check_modules(roscpp roscpp) if(NOT roscpp_FOUND) message(FATAL_ERROR "can not find roscpp.") endif() #Boostの検出 find_package(Boost COMPONENTS chrono filesystem system) if(NOT Boost_FOUND) find_package(Boost REQUIRED COMPONENTS chrono filesystem signals system) endif()
以下のように動的リンクライブラリの生成、検出したライブラリのリンク、インクルードディレクトリの設定を行います。
#インクルードディレクトリ、リンクディレクトリ、コンパイル時のフラグの設定 include_directories(${OPENRTM_INCLUDE_DIRS}) add_definitions(${OPENRTM_CFLAGS}) link_directories(${OPENRTM_LIBRARY_DIRS}) link_directories(${roscpp_LIBRARY_DIRS}) #動的リンクライブラリの生成 add_library(${PROJECT_NAME} SHARED TestRosSerializer.cpp) #生成するライブラリ名をTestRosSerializer.dll(もしくは.so)に設定 set_target_properties(${PROJECT_NAME} PROPERTIES PREFIX "") #OpenRTM-aist、ROS、Boostのライブラリとリンク target_include_directories(${PROJECT_NAME} SYSTEM PRIVATE ${roscpp_INCLUDE_DIRS} PRIVATE ${Boost_INCLUDE_DIRS} PRIVATE ${ROSTRANSPORT_INCLUDE_DIRS}) target_link_libraries(${PROJECT_NAME} ${OPENRTM_LIBRARIES} ${roscpp_LIBRARIES} ${Boost_LIBRARIES} ${ROSTRANSPORT_LIBRARIES})
ROS用シリアライザを作成する場合、CPPファイルでROSSerializer.hをインクルードします。 また、今回はROSのgeometry_msgs/TwistStamped型を使用するため、geometry_msgs/TwistStamped.hをインクルードします。このインクルードファイルは使用するメッセージ型により変更します。
#include <rtm/ByteDataStreamBase.h> #include <rtm/idl/BasicDataTypeSkel.h> #include <rtm/idl/ExtendedDataTypesSkel.h> #include <coil/Factory.h> #include <rtm/Manager.h> #include <rtm/ext/ROSTransport/ROSSerializer.h> #include <geometry_msgs/TwistStamped.h>
ROSSerializerBaseクラスを継承したクラスを定義します。 ROSSerializerBaseクラスのテンプレート引数には使用するOpenRTM-aistのデータ型を指定します。今回はRTC::TimedVelocity3D型を使用するため、RTC::TimedVelocity3Dを指定します。
class TestRosSerializer : public RTC::ROSSerializerBase<RTC::TimedVelocity3D> { public: TestRosSerializer(){};
以下のようにTestRosSerializerクラスのメンバ関数としてserialize関数を定義する。 serialize関数では、RTC::TimedVelocity3D型のデータをgeometry_msgs/TwistStamped型のデータに変換し、その後バイト列データに変換しています。
bool serialize(const RTC::TimedVelocity3D& data) override { geometry_msgs::TwistStamped msg; msg.header.stamp.sec = data.tm.sec; msg.header.stamp.nsec = data.tm.nsec; msg.twist.linear.x = data.data.vx; msg.twist.linear.y = data.data.vy; msg.twist.linear.z = data.data.vz; msg.twist.angular.x = data.data.vr; msg.twist.angular.y = data.data.vp; msg.twist.angular.z = data.data.va; RTC::ROSSerializerBase<RTC::TimedVelocity3D>::m_message = ros::serialization::serializeMessage<geometry_msgs::TwistStamped>(msg); return true; }
次にdeserialize関数を定義します。 deserialize関数では、バイト列データをgeometry_msgs/TwistStamped型のデータに変換し、その後RTC::TimedVelocity3D型のデータに変換しています。
bool deserialize(RTC::TimedVelocity3D& data) override { geometry_msgs::TwistStamped msg; ros::serialization::deserializeMessage(ROSSerializerBase<RTC::TimedVelocity3D>::m_message, msg); data.tm.sec = msg.header.stamp.sec; data.tm.nsec = msg.header.stamp.nsec; data.data.vx = msg.twist.linear.x; data.data.vy = msg.twist.linear.y; data.data.vz = msg.twist.linear.z; data.data.vr = msg.twist.angular.x; data.data.vp = msg.twist.angular.y; data.data.va = msg.twist.angular.z; return true; }
以下ように{ライブラリ名}Init関数を定義すると、動的リンクライブラリのロード時にこの関数が呼ばれます。 TestRosSerializerInit関数内でファクトリにシリアライザを追加することにより、RTC起動時に実装したシリアライザが使えるようにします。
extern "C" { //以下はモジュールロード時に呼び出される関数 DLL_EXPORT void TestRosSerializerInit(RTC::Manager* /*manager*/) { //シリアライザの登録 RTC::addRosSerializer<RTC::TimedVelocity3D, geometry_msgs::TwistStamped, TestRosSerializer>("ros:geometry_msgs/TwistStamped"); } }
以下から作成済みのシリアライザ、動作確認用のRTCをダウンロードできます。
作成したTestRosSerializerをビルドしてください。 ビルド、実行時にはROSの環境変数が設定されている必要があるため、以下のコマンドを実行してください。
source /opt/ros/noetic/setup.bash
rtc.confを作成します。 ROSTransport.soと、作成したシリアライザTestRosSerializer.soをロードするように設定します。 TestRosSerializer.soのパスは、ビルドしたディレクトリのパスに変更してください。
manager.modules.load_path: /usr/lib/openrtm-2.0/transport/, ~/TestRosSerializer/build manager.modules.preload: ROSTransport.so, TestRosSerializer.so
以下のようにサンプルコンポーネントのtestVelocity3DInのInPort、testVelocity3DOutのOutPortでコネクションを生成します。
manager.components.preconnect: testVelocity3DIn0.in?interface_type=ros&marshaling_type=ros:geometry_msgs/TwistStamped&ros.topic=chatter&ros.so_keepalive=NO&ros.node.name=testVelocity3DIn0, testVelocity3DOut0.out?interface_type=ros&marshaling_type=ros:geometry_msgs/TwistStamped&ros.topic=chatter&ros.node.name=testVelocity3DOut0
動作確認する場合は、testOpenRTMSerializerに含まれているtestVelocity3DIn、testVelocity3DOutのサンプルコンポーネントをビルドしてください。
以下のコマンド実行後、RTCをアクティブ化するとtestVelocity3DOutのPublisherからtestVelocity3DInのSubscriberにデータが送信されて、testVelocity3DInを起動した画面に数値が表示されます。
testVelocity3DOutComp -f rtc.conf
testVelocity3DInComp -f rtc.conf
今回の動作確認ではRTC同士でROSのトピック通信を実行しましたが、ROSノードと通信を確認する場合は、geometry_msgs/TwistStamped型のPublisher、Subscriberを持つROSノードを作成して試してください。
OpenRTM-aistのデータ型とROSのメッセージ型を変換するシリアライザの作成のためには、ROSTransport、ROS2のヘッダーファイルのインクルード、ライブラリのリンクが必要になります。 以下のようにCMakeLists.txtでOpenRTM-aist、ROS2、FastDDSを検出します。
#OpenRTM-aistの検出 find_package(OpenRTM 2.0 REQUIRED) find_package(ROS2Transport REQUIRED) #ROS2の検出 find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(sensor_msgs REQUIRED) #FastDDSの検出 find_package(fastcdr REQUIRED) find_package(fastrtps REQUIRED)
以下のように動的リンクライブラリの生成、検出したライブラリのリンク、インクルードディレクトリの設定を行います。
#インクルードディレクトリ、リンクディレクトリ、コンパイル時のフラグの設定 include_directories(${OPENRTM_INCLUDE_DIRS}) add_definitions(${OPENRTM_CFLAGS}) link_directories(${OPENRTM_LIBRARY_DIRS}) #動的リンクライブラリの生成 add_library(${PROJECT_NAME} SHARED TestRos2Serializer.cpp) #生成するライブラリ名をTestRos2Serializer.dll(もしくは.so)に設定 set_target_properties(${PROJECT_NAME} PROPERTIES PREFIX "") target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${rclcpp_INCLUDE_DIRS} PUBLIC ${std_msgs_INCLUDE_DIRS} PUBLIC ${geometry_msgs_INCLUDE_DIRS} PUBLIC ${sensor_msgs_INCLUDE_DIRS} PUBLIC ${ROS2TRANSPORT_INCLUDE_DIRS}) #OpenRTM-aistのライブラリとリンク target_link_libraries(${PROJECT_NAME} ${OPENRTM_LIBRARIES} ${ROS2TRANSPORT_LIBRARIES} ${rclcpp_LIBRARIES} ${std_msgs_LIBRARIES} ${geometry_msgs_LIBRARIES} ${sensor_msgs_LIBRARIES} ${std_msgs_LIBRARIES__rosidl_typesupport_fastrtps_cpp} ${geometry_msgs_LIBRARIES__rosidl_typesupport_fastrtps_cpp} ${sensor_msgs_LIBRARIES__rosidl_typesupport_fastrtps_cpp} fastcdr fastrtps) target_compile_definitions(${PROJECT_NAME} PRIVATE STD_MSGS_VERSION_MAJOR=${std_msgs_VERSION_MAJOR} GEOMETORY_MSGS_VERSION_MAJOR=${geometry_msgs_VERSION_MAJOR} SENSOR_MSGS_VERSION_MAJOR=${sensor_msgs_VERSION_MAJOR} STD_MSGS_VERSION_MINOR=${std_msgs_VERSION_MINOR} GEOMETORY_MSGS_VERSION_MINOR=${geometry_msgs_VERSION_MINOR} SENSOR_MSGS_VERSION_MINOR==${sensor_msgs_VERSION_MINOR})
ROS用シリアライザを作成する場合、CPPファイルでROS2Serializer.hをインクルードします。 また、今回はROS2のgeometry_msgs/TwistStamped型を使用するため、geometry_msgs/msg/twist_stamped.hpp、geometry_msgs/msg/detail/twist_stamped__rosidl_typesupport_fastrtps_cpp.hppをインクルードします。このインクルードファイルは使用するメッセージ型により変更します。
#include <rtm/ByteDataStreamBase.h> #include <rtm/idl/BasicDataTypeSkel.h> #include <rtm/idl/ExtendedDataTypesSkel.h> #include <coil/Factory.h> #include <rtm/Manager.h> #include <rtm/ext/ROS2Transport/ROS2Serializer.h> #include <geometry_msgs/msg/twist_stamped.hpp> #if (STD_MSGS_VERSION_MAJOR >= 2) #include <geometry_msgs/msg/detail/twist_stamped__rosidl_typesupport_fastrtps_cpp.hpp> #else #include <geometry_msgs/msg/twist_stamped__rosidl_typesupport_fastrtps_cpp.hpp> #endif
ROS2SerializerBaseクラスを継承したクラスを定義します。 ROS2SerializerBaseクラスのテンプレート引数には使用するOpenRTM-aistのデータ型を指定します。今回はRTC::TimedVelocity3D型を使用するため、RTC::TimedVelocity3Dを指定します。
class TestRos2Serializer : public RTC::ROS2SerializerBase<RTC::TimedVelocity3D> { public: TestRos2Serializer(){};
以下のようにTestRos2Serializerクラスのメンバ関数としてserialize関数を定義する。 serialize関数では、RTC::TimedVelocity3D型のデータをgeometry_msgs/TwistStamped型のデータに変換し、その後バイト列データに変換しています。 geometry_msgs/TwistStamped型のデータからバイト列データへの変換は、geometrymsg_serialize関数を使用しています。 std_msgパッケージのメッセージ型の場合はstdmsg_serialize関数、geometry_msgsパッケージのメッセージ型の場合はgeometrymsg_serialize関数、sensor_msgパッケージのメッセージ型の場合はsensormsg_serialize関数を使用します。
bool serialize(const RTC::TimedVelocity3D& data) override { geometry_msgs::msg::TwistStamped msg; msg.header.stamp.sec = data.tm.sec; msg.header.stamp.nanosec = data.tm.nsec; msg.twist.linear.x = data.data.vx; msg.twist.linear.y = data.data.vy; msg.twist.linear.z = data.data.vz; msg.twist.angular.x = data.data.vr; msg.twist.angular.y = data.data.vp; msg.twist.angular.z = data.data.va;
return RTC::ROS2SerializerBase<RTC::TimedVelocity3D>::geometrymsg_serialize(msg); }
std_msg、geometry_msgs、sensor_msg以外のパッケージのメッセージ型の場合は、stdmsg_serialize関数の実装を参考にして記述してください。
次にdeserialize関数を定義します。 deserialize関数では、バイト列データをgeometry_msgs/TwistStamped型のデータに変換し、その後RTC::TimedVelocity3D型のデータに変換しています。 バイト列データからgeometry_msgs/TwistStamped型のデータへの変換は、geometrymsg_deserialize関数を使用しています。 std_msgパッケージのメッセージ型の場合はstdmsg_deserialize関数、geometry_msgsパッケージのメッセージ型の場合はgeometrymsg_deserialize関数、sensor_msgパッケージのメッセージ型の場合はsensormsg_deserialize関数を使用します。
bool deserialize(RTC::TimedVelocity3D& data) override { geometry_msgs::msg::TwistStamped msg; bool ret = ROS2SerializerBase<RTC::TimedVelocity3D>::geometrymsg_deserialize(msg); data.tm.sec = msg.header.stamp.sec; data.tm.nsec = msg.header.stamp.nanosec; data.data.vx = msg.twist.linear.x; data.data.vy = msg.twist.linear.y; data.data.vz = msg.twist.linear.z; data.data.vr = msg.twist.angular.x; data.data.vp = msg.twist.angular.y; data.data.va = msg.twist.angular.z;
return ret; }
std_msg、geometry_msgs、sensor_msg以外のパッケージのメッセージ型の場合は、stdmsg_deserialize関数の実装を参考にして記述してください。
以下ように{ライブラリ名}Init関数を定義すると、動的リンクライブラリのロード時にこの関数が呼ばれます。 TestRos2SerializerInit関数内でファクトリにシリアライザを追加することにより、RTC起動時に実装したシリアライザが使えるようにします。
extern "C" {//以下はモジュールロード時に呼び出される関数 DLL_EXPORT void TestRos2SerializerInit(RTC::Manager* /*manager*/) { //シリアライザの登録 RTC::addRos2Serializer<RTC::TimedVelocity3D, geometry_msgs::msg::TwistStamped, TestRos2Serializer>("ros2:geometry_msgs/TwistStamped"); }
以下から作成済みのシリアライザ、動作確認用のRTCをダウンロードできます。
作成したTestRos2Serializerをビルドしてください。 ビルド、実行時にはROS2の環境変数が設定されている必要があるため、以下のコマンドを実行してください。
source /opt/ros/foxy/setup.bash
rtc.confを作成します。 FastRTPSTransport.so、ROS2Transport.soと、作成したシリアライザTestRos2Serializer.soをロードするように設定します。 TestRos2Serializer.soのパスは、ビルドしたディレクトリのパスに変更してください。
manager.modules.load_path: /usr/lib/openrtm-2.0/transport/, ~/TestRos2Serializer/build manager.modules.preload: FastRTPSTransport.so, ROS2Transport.so, TestRos2Serializer.so
以下のようにサンプルコンポーネントのtestVelocity3DInのInPort、testVelocity3DOutのOutPortでコネクションを生成します。
manager.components.preconnect: testVelocity3DIn0.in?interface_type=fast-rtps&marshaling_type=ros2:geometry_msgs/TwistStamped&fast-rtps.topic=chatter, testVelocity3DOut0.out?interface_type=fast-rtps&marshaling_type=ros2:geometry_msgs/TwistStamped&fast-rtps.topic=chatter
動作確認する場合は、testOpenRTMSerializerに含まれているtestVelocity3DIn、testVelocity3DOutのサンプルコンポーネントをビルドしてください。
以下のコマンド実行後、RTCをアクティブ化するとtestVelocity3DOutのPublisherからtestVelocity3DInのSubscriberにデータが送信されて、testVelocity3DInを起動した画面に数値が表示されます。
testVelocity3DOutComp -f rtc.conf
testVelocity3DInComp -f rtc.conf
今回の動作確認ではRTC同士でROS2のトピック通信を実行しましたが、ROS2ノードと通信を確認する場合は、geometry_msgs/TwistStamped型のPublisher、Subscriberを持つROS2ノードを作成して試してください。