カスタムmsgおよびsrvファイルの作成
目標: カスタムインターフェースファイル(.msgと.srv)を定義し、PythonとC++ノードで使用する。
チュートリアルレベル: 初心者
所要時間: 20分
背景
前のチュートリアルでは、メッセージとサービスインターフェースを利用してトピック、サービス、そして簡単なパブリッシャー/サブスクライバー(C++/Python)とサービス/クライアント(C++/Python)ノードについて学びました。 使用したインターフェースは、それらの場合において事前定義されていました。
事前定義されたインターフェース定義を使用するのは良い習慣ですが、独自のメッセージとサービスを定義する必要がある場合もあるでしょう。 このチュートリアルでは、カスタムインターフェース定義を作成する最も簡単な方法を紹介します。
前提条件
ROS 2ワークスペースが必要です。
このチュートリアルでは、パブリッシャー/サブスクライバー(C++とPython)およびサービス/クライアント(C++とPython)チュートリアルで作成したパッケージも使用して、新しいカスタムメッセージを試します。
タスク
1 新しいパッケージの作成
このチュートリアルでは、カスタム.msgと.srvファイルを独自のパッケージで作成し、別のパッケージでそれらを利用します。 両方のパッケージは同じワークスペース内にある必要があります。
前のチュートリアルで作成したpub/subとservice/clientパッケージを使用するため、それらのパッケージと同じワークスペース(ros2_ws/src)にいることを確認してから、以下のコマンドを実行して新しいパッケージを作成します:
ros2 pkg create --build-type ament_cmake --license Apache-2.0 tutorial_interfacestutorial_interfacesは新しいパッケージの名前です。 これはament_cmakeパッケージであり、そうでなければならないことに注意してください。ただし、これはメッセージとサービスを使用できるパッケージのタイプを制限するものではありません。 ament_cmakeパッケージで独自のカスタムインターフェースを作成し、C++またはPythonノードで使用できます。これについては最後のセクションで説明します。
.msgと.srvファイルは、それぞれmsgとsrvという名前のディレクトリに配置する必要があります。 ros2_ws/src/tutorial_interfacesにディレクトリを作成します:
mkdir msg srv2 カスタム定義の作成
2.1 msg定義
先ほど作成したtutorial_interfaces/msgディレクトリ内で、Num.msgという新しいファイルを作成し、データ構造を宣言する1行のコードを記述します:
int64 numこれは、numという名前の単一の64ビット整数を転送するカスタムメッセージです。
また、先ほど作成したtutorial_interfaces/msgディレクトリ内で、以下の内容でSphere.msgという新しいファイルを作成します:
geometry_msgs/Point center
float64 radiusこのカスタムメッセージは、別のメッセージパッケージ(この場合はgeometry_msgs/Point)のメッセージを使用します。
2.2 srv定義
先ほど作成したtutorial_interfaces/srvディレクトリに戻り、以下の要求と応答構造でAddThreeInts.srvという新しいファイルを作成します:
int64 a
int64 b
int64 c
---
int64 sumこれは、a、b、cという名前の3つの整数を要求し、sumという名前の整数で応答するカスタムサービスです。
3 CMakeLists.txt
定義したインターフェースを言語固有のコード(C++やPythonなど)に変換して、それらの言語で使用できるようにするには、CMakeLists.txtに以下の行を追加します:
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Num.msg"
"msg/Sphere.msg"
"srv/AddThreeInts.srv"
DEPENDENCIES geometry_msgs # Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg
)注意
rosidl_generate_interfacesの最初の引数(ライブラリ名)は、パッケージの名前で始まる必要があります。例:単純に${PROJECT_NAME}または${PROJECT_NAME}_suffix。 https://github.com/ros2/rosidl/issues/441#issuecomment-591025515を参照してください。
4 package.xml
インターフェースは言語固有のコードを生成するためにrosidl_default_generatorsに依存するため、それに対するビルドツール依存関係を宣言する必要があります。 rosidl_default_runtimeは、後でインターフェースを使用できるようにするために必要なランタイムまたは実行段階の依存関係です。 rosidl_interface_packagesは、パッケージtutorial_interfacesが関連付けられるべき依存関係グループの名前で、<member_of_group>タグを使用して宣言されます。
package.xmlの<package>要素内に以下の行を追加します:
<depend>geometry_msgs</depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>5 tutorial_interfacesパッケージのビルド
カスタムインターフェースパッケージのすべての部分が整ったので、パッケージをビルドできます。 ワークスペースのルート(~/ros2_ws)で、以下のコマンドを実行します:
colcon build --packages-select tutorial_interfacesこれで、インターフェースが他のROS 2パッケージによって発見可能になります。
6 msgとsrvの作成確認
新しいターミナルで、ワークスペース内(ros2_ws)から以下のコマンドを実行してソースします:
source install/setup.bashros2 interface showコマンドを使用してインターフェースの作成が成功したことを確認できます。 ターミナルに表示される出力は以下のようになるはずです:
ros2 interface show tutorial_interfaces/msg/Num出力:
int64 numros2 interface show tutorial_interfaces/msg/Sphere出力:
geometry_msgs/Point center
float64 x
float64 y
float64 z
float64 radiusros2 interface show tutorial_interfaces/srv/AddThreeInts出力:
int64 a
int64 b
int64 c
---
int64 sum7 新しいインターフェースのテスト
このステップでは、前のチュートリアルで作成したパッケージを使用できます。 ノード、CMakeLists.txt、package.xmlファイルにいくつかの簡単な変更を加えることで、新しいインターフェースを使用できるようになります。
7.1 pub/subでNum.msgをテスト
前のチュートリアルで作成したパブリッシャー/サブスクライバーパッケージ(C++またはPython)にいくつかの変更を加えることで、Num.msgの動作を確認できます。 標準の文字列msgを数値msgに変更するため、出力は若干異なります。
パブリッシャー
C++の場合:
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/num.hpp" // CHANGE
using namespace std::chrono_literals;
class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<tutorial_interfaces::msg::Num>("topic", 10); // CHANGE
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback()
{
auto message = tutorial_interfaces::msg::Num(); // CHANGE
message.num = this->count_++; // CHANGE
RCLCPP_INFO_STREAM(this->get_logger(), "Publishing: '" << message.num << "'"); // CHANGE
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<tutorial_interfaces::msg::Num>::SharedPtr publisher_; // CHANGE
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}Pythonの場合:
import rclpy
from rclpy.node import Node
from tutorial_interfaces.msg import Num # CHANGE
class MinimalPublisher(Node):
def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(Num, 'topic', 10) # CHANGE
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
def timer_callback(self):
msg = Num() # CHANGE
msg.num = self.i # CHANGE
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%d"' % msg.num) # CHANGE
self.i += 1
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()サブスクライバー
C++の場合:
#include <functional>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/num.hpp" // CHANGE
using std::placeholders::_1;
class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
subscription_ = this->create_subscription<tutorial_interfaces::msg::Num>( // CHANGE
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
private:
void topic_callback(const tutorial_interfaces::msg::Num & msg) const // CHANGE
{
RCLCPP_INFO_STREAM(this->get_logger(), "I heard: '" << msg.num << "'"); // CHANGE
}
rclcpp::Subscription<tutorial_interfaces::msg::Num>::SharedPtr subscription_; // CHANGE
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}Pythonの場合:
import rclpy
from rclpy.node import Node
from tutorial_interfaces.msg import Num # CHANGE
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(
Num, # CHANGE
'topic',
self.listener_callback,
10)
self.subscription # prevent unused variable warning
def listener_callback(self, msg):
self.get_logger().info('I heard: "%d"' % msg.num) # CHANGE
def main(args=None):
rclpy.init(args=args)
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
minimal_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()CMakeLists.txt
以下の行を追加(C++のみ):
#...
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED) # CHANGE
add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp tutorial_interfaces) # CHANGE
add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp tutorial_interfaces) # CHANGE
install(TARGETS
talker
listener
DESTINATION lib/${PROJECT_NAME})
ament_package()package.xml
以下の行を追加:
<depend>tutorial_interfaces</depend>上記の編集を行い、すべての変更を保存した後、パッケージをビルドします:
colcon build --packages-select cpp_pubsubまたは
colcon build --packages-select py_pubsubその後、2つの新しいターミナルを開き、それぞれでros2_wsをソースして実行します:
ros2 run cpp_pubsub talkerros2 run cpp_pubsub listenerまたは
ros2 run py_pubsub talkerros2 run py_pubsub listenerNum.msgは整数のみを中継するため、talkerは以前に公開していた文字列とは対照的に、整数値のみを公開するはずです:
[INFO] [minimal_publisher]: Publishing: '0'
[INFO] [minimal_publisher]: Publishing: '1'
[INFO] [minimal_publisher]: Publishing: '2'7.2 service/clientでAddThreeInts.srvをテスト
前のチュートリアルで作成したサービス/クライアントパッケージ(C++またはPython)にいくつかの変更を加えることで、AddThreeInts.srvの動作を確認できます。 元の2つの整数要求srvを3つの整数要求srvに変更するため、出力は若干異なります。
サービス
C++の場合:
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp" // CHANGE
#include <memory>
void add(const std::shared_ptr<tutorial_interfaces::srv::AddThreeInts::Request> request, // CHANGE
std::shared_ptr<tutorial_interfaces::srv::AddThreeInts::Response> response) // CHANGE
{
response->sum = request->a + request->b + request->c; // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld" " c: %ld", // CHANGE
request->a, request->b, request->c); // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]", (long int)response->sum);
}
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_server"); // CHANGE
rclcpp::Service<tutorial_interfaces::srv::AddThreeInts>::SharedPtr service = // CHANGE
node->create_service<tutorial_interfaces::srv::AddThreeInts>("add_three_ints", &add); // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add three ints."); // CHANGE
rclcpp::spin(node);
rclcpp::shutdown();
}Pythonの場合:
from tutorial_interfaces.srv import AddThreeInts # CHANGE
import rclpy
from rclpy.node import Node
class MinimalService(Node):
def __init__(self):
super().__init__('minimal_service')
self.srv = self.create_service(AddThreeInts, 'add_three_ints', self.add_three_ints_callback) # CHANGE
def add_three_ints_callback(self, request, response):
response.sum = request.a + request.b + request.c # CHANGE
self.get_logger().info('Incoming request\na: %d b: %d c: %d' % (request.a, request.b, request.c)) # CHANGE
return response
def main():
rclpy.init()
minimal_service = MinimalService()
rclpy.spin(minimal_service)
rclpy.shutdown()
if __name__ == '__main__':
main()クライアント
C++の場合:
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp" // CHANGE
#include <chrono>
#include <cstdlib>
#include <memory>
using namespace std::chrono_literals;
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
if (argc != 4) { // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "usage: add_three_ints_client X Y Z"); // CHANGE
return 1;
}
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_client"); // CHANGE
rclcpp::Client<tutorial_interfaces::srv::AddThreeInts>::SharedPtr client = // CHANGE
node->create_client<tutorial_interfaces::srv::AddThreeInts>("add_three_ints"); // CHANGE
auto request = std::make_shared<tutorial_interfaces::srv::AddThreeInts::Request>(); // CHANGE
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
request->c = atoll(argv[3]); // CHANGE
while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
}
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Sum: %ld", result.get()->sum);
} else {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_three_ints"); // CHANGE
}
rclcpp::shutdown();
return 0;
}Pythonの場合:
import sys
from tutorial_interfaces.srv import AddThreeInts # CHANGE
import rclpy
from rclpy.node import Node
class MinimalClientAsync(Node):
def __init__(self):
super().__init__('minimal_client_async')
self.cli = self.create_client(AddThreeInts, 'add_three_ints') # CHANGE
while not self.cli.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = AddThreeInts.Request() # CHANGE
def send_request(self, a, b, c):
self.req.a = a
self.req.b = b
self.req.c = c # CHANGE
return self.cli.call_async(self.req)
def main():
rclpy.init()
minimal_client = MinimalClientAsync()
future = minimal_client.send_request(int(sys.argv[1]), int(sys.argv[2]), int(sys.argv[3])) # CHANGE
rclpy.spin_until_future_complete(minimal_client, future)
response = future.result()
minimal_client.get_logger().info(
'Result of add_three_ints: for %d + %d + %d = %d' % # CHANGE
(int(sys.argv[1]), int(sys.argv[2]), int(sys.argv[3]), response.sum)) # CHANGE
minimal_client.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()CMakeLists.txt
以下の行を追加(C++のみ):
#...
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED) # CHANGE
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp tutorial_interfaces) # CHANGE
add_executable(client src/add_two_ints_client.cpp)
ament_target_dependencies(client
rclcpp tutorial_interfaces) # CHANGE
install(TARGETS
server
client
DESTINATION lib/${PROJECT_NAME})
ament_package()package.xml
以下の行を追加:
<depend>tutorial_interfaces</depend>上記の編集を行い、すべての変更を保存した後、パッケージをビルドします:
colcon build --packages-select cpp_srvcliまたは
colcon build --packages-select py_srvcliその後、2つの新しいターミナルを開き、それぞれでros2_wsをソースして実行します:
ros2 run cpp_srvcli serverros2 run cpp_srvcli client 2 3 1または
ros2 run py_srvcli serviceros2 run py_srvcli client 2 3 1まとめ
このチュートリアルでは、独自のパッケージでカスタムインターフェースを作成し、他のパッケージでそれらのインターフェースを利用する方法を学びました。
このチュートリアルは、カスタムインターフェースの定義について表面的に触れただけです。 詳細については、ROS 2インターフェースについてで学ぶことができます。
次のステップ
次のチュートリアルでは、ROS 2でインターフェースを使用するその他の方法について説明します。