Compare commits

...

9 Commits
pose ... main

Author SHA1 Message Date
Wojciech Kwolek
5158318fcb update comments, close #2 2021-06-17 13:54:31 +02:00
Wojciech Kwolek
842f753665 publish robot state 2021-05-21 11:46:48 +00:00
Wojciech Kwolek
265dc23371 publish charge/battery state (not tested, our pionieers don't do this) 2021-05-20 12:51:28 +00:00
Wojciech Kwolek
15e172d066 implement clutch
closes #10
2021-05-20 12:17:40 +00:00
Wojciech Kwolek
e41661ca61 add a script that builds the dev container 2021-05-20 12:04:42 +00:00
Wojciech Kwolek
236bb1609a implement wheels
closes #5
2021-05-20 12:02:05 +00:00
Wojciech Kwolek
71dbeb6b85 tell the compiler about intentionally unused parameters to keep it quiet 2021-05-14 12:00:10 +00:00
Wojciech Kwolek
02adf17947 add gripper services 2021-05-14 11:57:46 +00:00
Wojciech Kwolek
62ad6e683b Implement pose
Squashed commit of the following:

commit 00d9bc9ffa
Author: Wojciech Kwolek <me@irth.pl>
Date:   Fri May 7 12:38:15 2021 +0000

    turns out the only incorrect thing was my assumptions

commit 6d653383a8
Author: Wojciech Kwolek <me@irth.pl>
Date:   Fri Apr 30 14:42:40 2021 +0000

    WIP: initial pose implementation
2021-05-07 12:38:44 +00:00
20 changed files with 413 additions and 10 deletions

View File

@ -8,6 +8,7 @@
"includePath": [
"/opt/ros/foxy/include/**",
"/workspaces/ros2aria/src/ros2aria/include/**",
"/workspaces/ros2aria/install/ros2aria_msgs/include/**",
"/usr/include/**",
"/usr/local/Aria/include"
],

View File

@ -1,4 +1,4 @@
.PHONY: build run upload
.PHONY: build run upload legacy
SOURCES := $(wildcard src/ros2aria/src/*.cpp)
HEADERS := $(wildcard src/ros2aria/src/*.hpp)
@ -8,13 +8,15 @@ build/ros2aria/ros2aria: $(SOURCES) $(HEADERS)
build: build/ros2aria/ros2aria
.uploaded: build/ros2aria/ros2aria
rsync -r build/ros2aria/ros2aria lab1_5@pionier6:~/ros2aria
# .uploaded: build/ros2aria/ros2aria
upload:
rsync -r . lab1_5@pionier6:~/ros2aria
touch .uploaded
upload: .uploaded
# upload: .uploaded
run: upload
ssh lab1_5@pionier6 -t -- docker run --rm --network=host -it --device /dev/ttyS0 -v /home/lab1_5:/ws irth7/ros2aria-dev /ws/ros2aria
ssh lab1_5@pionier6 -t -- docker run --rm --network=host -it --device /dev/ttyS0 -v /home/lab1_5:/ws irth7/ros2aria-dev /bin/bash /ws/ros2aria/run.sh
legacy:
ssh lab1_5@pionier6 -t -- ./run.sh

0
build_devcontainer.sh Normal file → Executable file
View File

61
node_info_ros1.txt Normal file
View File

@ -0,0 +1,61 @@
--------------------------------------------------------------------------------
Node [/PIONIER6/RosAria]
Publications:
* /PIONIER6/RosAria/battery_recharge_state [std_msgs/Int8]
* /PIONIER6/RosAria/battery_state_of_charge [std_msgs/Float32]
* /PIONIER6/RosAria/bumper_state [rosaria/BumperState]
* /PIONIER6/RosAria/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /PIONIER6/RosAria/parameter_updates [dynamic_reconfigure/Config]
* /PIONIER6/RosAria/pose [nav_msgs/Odometry]
* /PIONIER6/RosAria/robot_info [rosaria_msgs/RobotInfoMsg]
* /PIONIER6/RosAria/sonar [sensor_msgs/PointCloud]
* /PIONIER6/RosAria/sonar_pointcloud2 [sensor_msgs/PointCloud2]
* /PIONIER6/RosAria/wheels [sensor_msgs/JointState]
* /rosout [rosgraph_msgs/Log]
* /tf [tf2_msgs/TFMessage]
Subscriptions:
* /PIONIER/master_stop [std_msgs/Bool]
* /PIONIER/restrictions [rosaria_msgs/RestrictionsMsg]
* /PIONIER6/RosAria/clutch [std_msgs/Bool]
* /PIONIER6/RosAria/cmd_vel [unknown type]
* /PIONIER6/RosAria/user_stop [std_msgs/Bool]
Services:
* /PIONIER6/RosAria/get_loggers
* /PIONIER6/RosAria/gripper_close
* /PIONIER6/RosAria/gripper_down
* /PIONIER6/RosAria/gripper_open
* /PIONIER6/RosAria/gripper_up
* /PIONIER6/RosAria/set_logger_level
* /PIONIER6/RosAria/set_parameters
contacting node http://10.104.16.45:35307/ ...
Pid: 52
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
* topic: /PIONIER6/RosAria/robot_info
* to: /master_plugin_lab15_19_12824_1114070233125035517
* direction: outbound
* transport: TCPROS
* topic: /PIONIER/restrictions
* to: /master_plugin_lab15_19_12824_1114070233125035517 (http://10.104.16.29:35537/)
* direction: inbound
* transport: TCPROS
* topic: /PIONIER6/RosAria/user_stop
* to: /user_plugin_lab15_19_15229_5138248156866338464 (http://10.104.16.29:43275/)
* direction: inbound
* transport: TCPROS
* topic: /PIONIER/master_stop
* to: /master_plugin_lab15_19_12824_1114070233125035517 (http://10.104.16.29:35537/)
* direction: inbound
* transport: TCPROS
* topic: /PIONIER6/RosAria/clutch
* to: /user_plugin_lab15_19_15229_5138248156866338464 (http://10.104.16.29:43275/)
* direction: inbound
* transport: TCPROS

6
run.sh Executable file
View File

@ -0,0 +1,6 @@
#!/bin/bash
export LD_LIBRARY_PATH=/usr/local/Aria/lib
source /opt/ros/foxy/setup.bash
source /ws/ros2aria/install/setup.bash
ros2 run ros2aria ros2aria

View File

@ -22,6 +22,8 @@ find_package(std_srvs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(ros2aria_msgs REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
@ -33,13 +35,21 @@ add_executable(ros2aria
src/raiibot.cpp
src/cmd_vel.cpp
src/publish.cpp
src/sonar.cpp)
src/sonar.cpp
src/pose.cpp
src/gripper.cpp
src/wheels.cpp
src/clutch.cpp
src/state.cpp)
ament_target_dependencies(ros2aria rclcpp)
ament_target_dependencies(ros2aria std_srvs)
ament_target_dependencies(ros2aria geometry_msgs)
ament_target_dependencies(ros2aria sensor_msgs)
ament_target_dependencies(ros2aria nav_msgs)
ament_target_dependencies(ros2aria tf2)
ament_target_dependencies(ros2aria ros2aria_msgs)
target_include_directories(ros2aria PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>

View File

@ -17,6 +17,7 @@
<depend>geometry_msgs</depend>
<depend>sensor_msgs</depend>
<depend>nav_msgs</depend>
<depend>ros2aria_msgs</depend>
<export>
<build_type>ament_cmake</build_type>

View File

@ -0,0 +1,12 @@
#include "ros2aria.hpp"
void Ros2Aria::clutch_callback(const std_msgs::msg::Bool::SharedPtr msg)
{
std::lock_guard<RAIIBot> lock(*robot.get());
auto r = robot->getRobot();
if (msg->data)
r->enableMotors();
else
r->disableMotors();
}

View File

@ -0,0 +1,34 @@
#include "./ros2aria.hpp"
void Ros2Aria::gripper_open_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const
{
UNUSED(request);
UNUSED(response);
std::lock_guard<RAIIBot> lock(*robot.get());
auto g = robot->getGripper();
g->gripOpen();
}
void Ros2Aria::gripper_close_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const
{
UNUSED(request);
UNUSED(response);
std::lock_guard<RAIIBot> lock(*robot.get());
auto g = robot->getGripper();
g->gripClose();
}
void Ros2Aria::gripper_up_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const
{
UNUSED(request);
UNUSED(response);
std::lock_guard<RAIIBot> lock(*robot.get());
auto g = robot->getGripper();
g->liftUp();
}
void Ros2Aria::gripper_down_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const
{
UNUSED(request);
UNUSED(response);
std::lock_guard<RAIIBot> lock(*robot.get());
auto g = robot->getGripper();
g->liftDown();
}

46
src/ros2aria/src/pose.cpp Normal file
View File

@ -0,0 +1,46 @@
#include "ros2aria.hpp"
#include "tf2/utils.h"
#include "tf2/transform_datatypes.h"
inline void convert_transform_to_pose(const tf2::Transform &trans, geometry_msgs::msg::Pose &pose)
{
geometry_msgs::msg::Transform msg = tf2::toMsg(trans);
pose.orientation = msg.rotation;
pose.position.x = msg.translation.x;
pose.position.y = msg.translation.y;
pose.position.z = msg.translation.z;
}
nav_msgs::msg::Odometry Ros2Aria::handlePose(rclcpp::Time stamp)
{
nav_msgs::msg::Odometry pose;
auto r = robot->getRobot();
ArPose p = r->getPose();
tf2::Quaternion rotation;
rotation.setRPY(0, 0, p.getTh() * M_PI / 180);
tf2::Vector3 position = tf2::Vector3(p.getX() / 1000, p.getY() / 1000, 0);
convert_transform_to_pose(tf2::Transform(rotation, position),
pose.pose.pose);
pose.twist.twist.linear.x = r->getVel() / 1000;
pose.twist.twist.linear.y = r->getLatVel() / 1000;
pose.twist.twist.angular.z = r->getRotVel() * M_PI / 180;
pose.header.frame_id = "header.frame_id"; // TODO: use correct frame_id
pose.child_frame_id = "child_frame_id"; // TODO: use correct child_frame_id
pose.header.stamp = stamp;
return pose;
}
void Ros2Aria::publishPose(nav_msgs::msg::Odometry pose)
{
if (this->pose_pub_->get_subscription_count() == 0)
return;
this->pose_pub_->publish(pose);
}

View File

@ -4,7 +4,16 @@ void Ros2Aria::publish()
{
// RCLCPP_INFO(this->get_logger(), "publish");
rclcpp::Time t = robot->getClock()->now();
sensor_msgs::msg::PointCloud sonarData = handleSonar(t);
publishSonar(sonarData);
publishSonarPointCloud2(sonarData);
nav_msgs::msg::Odometry pose = handlePose(t);
publishPose(pose);
sensor_msgs::msg::JointState wheels = handleWheels(t);
publishWheels(wheels);
publishState(t);
}

View File

@ -15,6 +15,7 @@ public:
RAIIBot(rclcpp::Node *node, std::string port)
{
this->robot = new ArRobot();
this->gripper = new ArGripper(this->robot);
this->node = node;
this->clock = rclcpp::Clock::make_shared();
@ -34,8 +35,11 @@ public:
// RCLCPP_INFO(this->get_logger(), "RosAria: ARIA could not connect to robot! (Check ~port parameter is correct, and permissions on port device, or any errors reported above)");
// rclcpp::shutdown();
}
this->robot->runAsync(true);
this->robot->enableMotors();
this->startWatchdog();
}
~RAIIBot()
@ -73,6 +77,11 @@ public:
return this->robot;
}
ArGripper *getGripper()
{
return this->gripper;
}
rclcpp::Clock::SharedPtr getClock()
{
return this->clock;
@ -101,6 +110,7 @@ private:
ArRobotConnector *robotConn = nullptr;
ArArgumentBuilder *args = nullptr;
ArArgumentParser *argparser = nullptr;
ArGripper *gripper = nullptr;
rclcpp::Node *node = nullptr;
rclcpp::TimerBase::SharedPtr watchdogTimer;
rclcpp::Time lastWatchdogPoke;

View File

@ -12,11 +12,27 @@ Ros2Aria::Ros2Aria()
RCLCPP_INFO(this->get_logger(), "starting subscribers and services");
cmd_vel_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
"cmd_vel", 10, std::bind(&Ros2Aria::cmd_vel_callback, this, _1));
stop_service_ = this->create_service<std_srvs::srv::Empty>("stop", std::bind(&Ros2Aria::stop, this, _1, _2));
clutch_sub_ = this->create_subscription<std_msgs::msg::Bool>(
"clutch", 10, std::bind(&Ros2Aria::clutch_callback, this, _1));
sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10);
sonar_pointcloud2_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("sonar_pointcloud2", 10);
pose_pub_ = this->create_publisher<nav_msgs::msg::Odometry>("pose", 1000);
wheels_pub_ = this->create_publisher<sensor_msgs::msg::JointState>("wheels", 1000);
battery_recharge_state_pub_ = this->create_publisher<std_msgs::msg::Int8>("battery_recharge_state", 10);
battery_state_of_charge_pub_ = this->create_publisher<std_msgs::msg::Float32>("battery_state_of_charge", 10);
robot_info_pub_ = this->create_publisher<ros2aria_msgs::msg::RobotInfoMsg>("robot_info", 10);
// services
stop_service_ = this->create_service<std_srvs::srv::Empty>("stop", std::bind(&Ros2Aria::stop, this, _1, _2));
gripper_open_service_ = this->create_service<std_srvs::srv::Empty>("gripper_open", std::bind(&Ros2Aria::gripper_open_callback, this, _1, _2));
gripper_close_service_ = this->create_service<std_srvs::srv::Empty>("gripper_close", std::bind(&Ros2Aria::gripper_close_callback, this, _1, _2));
gripper_up_service_ = this->create_service<std_srvs::srv::Empty>("gripper_up", std::bind(&Ros2Aria::gripper_up_callback, this, _1, _2));
gripper_down_service_ = this->create_service<std_srvs::srv::Empty>("gripper_down", std::bind(&Ros2Aria::gripper_down_callback, this, _1, _2));
// listen to sensors
auto r = robot->getRobot();
r->addSensorInterpTask("ROSPublishingTask", 100, &this->sensorCb);
@ -32,6 +48,8 @@ Ros2Aria::~Ros2Aria()
void Ros2Aria::stop(const std::shared_ptr<std_srvs::srv::Empty::Request> request, std::shared_ptr<std_srvs::srv::Empty::Response> response) const
{
UNUSED(request);
UNUSED(response);
RCLCPP_INFO(this->get_logger(), "stop");
rclcpp::shutdown();
}

View File

@ -3,11 +3,19 @@
#include "sensor_msgs/msg/point_cloud.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "std_srvs/srv/empty.hpp"
#include "std_msgs/msg/bool.hpp"
#include "std_msgs/msg/int8.hpp"
#include "std_msgs/msg/float32.hpp"
#include "ros2aria_msgs/msg/robot_info_msg.hpp"
#include "./raiibot.cpp"
#define UNUSED(x) (void)(x)
class Ros2Aria : public rclcpp::Node
{
public:
@ -25,18 +33,45 @@ private:
// publishers
void publish();
sensor_msgs::msg::PointCloud handleSonar(rclcpp::Time stamp);
rclcpp::Publisher<sensor_msgs::msg::PointCloud>::SharedPtr sonar_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr sonar_pointcloud2_pub_;
sensor_msgs::msg::PointCloud handleSonar(rclcpp::Time stamp);
void publishSonar(sensor_msgs::msg::PointCloud cloud);
void publishSonarPointCloud2(sensor_msgs::msg::PointCloud cloud);
nav_msgs::msg::Odometry handlePose(rclcpp::Time stamp);
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pose_pub_;
void publishPose(nav_msgs::msg::Odometry pose);
sensor_msgs::msg::JointState handleWheels(rclcpp::Time stamp);
rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr wheels_pub_;
void publishWheels(sensor_msgs::msg::JointState wheels);
rclcpp::Publisher<std_msgs::msg::Int8>::SharedPtr battery_recharge_state_pub_;
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr battery_state_of_charge_pub_;
rclcpp::Publisher<ros2aria_msgs::msg::RobotInfoMsg>::SharedPtr robot_info_pub_;
void publishState(rclcpp::Time stamp);
// subscribers
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;
void cmd_vel_callback(const geometry_msgs::msg::Twist::SharedPtr msg);
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr clutch_sub_;
void clutch_callback(const std_msgs::msg::Bool::SharedPtr msg);
// services
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr stop_service_;
void stop(const std::shared_ptr<std_srvs::srv::Empty::Request> request, std::shared_ptr<std_srvs::srv::Empty::Response> response) const;
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr gripper_open_service_;
void gripper_open_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const;
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr gripper_close_service_;
void gripper_close_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const;
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr gripper_up_service_;
void gripper_up_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const;
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr gripper_down_service_;
void gripper_down_callback(const std_srvs::srv::Empty::Request::SharedPtr request, std_srvs::srv::Empty::Response::SharedPtr response) const;
};

View File

@ -0,0 +1,44 @@
#include "ros2aria.hpp"
void Ros2Aria::publishState(rclcpp::Time stamp)
{
auto r = this->robot->getRobot();
// TODO: original rosaria only publishes it when it changes.
if (this->battery_recharge_state_pub_->get_subscription_count() > 0)
{
char s = r->getChargeState();
std_msgs::msg::Int8 recharge_state;
recharge_state.data = s;
this->battery_recharge_state_pub_->publish(recharge_state);
}
// TODO: our robots don't have this, cannot test
if (r->haveStateOfCharge() && this->battery_state_of_charge_pub_->get_subscription_count() > 0)
{
std_msgs::msg::Float32 soc;
soc.data = r->getStateOfCharge() / 100.0;
this->battery_state_of_charge_pub_->publish(soc);
}
if (this->robot_info_pub_->get_subscription_count() > 0)
{
ros2aria_msgs::msg::RobotInfoMsg robot_info_msg;
// TODO: allow setting the robot_id
robot_info_msg.robot_id.data = 6;
robot_info_msg.battery_voltage.data = r->getRealBatteryVoltageNow();
robot_info_msg.twist.linear.x = r->getVel() / 1000;
robot_info_msg.twist.linear.y = r->getLatVel() / 1000.0;
robot_info_msg.twist.angular.z = r->getRotVel() * M_PI / 180;
// TODO: actually keep track of robot state (true -> unlocked, false ->
// locked). This requires safety plugin to be implemented
robot_info_msg.state.data = true;
robot_info_msg.clutch.data = r->areMotorsEnabled();
// TODO: actually look for obstacles
robot_info_msg.obstacle_detected.data = false;
this->robot_info_pub_->publish(robot_info_msg);
}
}

View File

@ -0,0 +1,32 @@
#include "ros2aria.hpp"
sensor_msgs::msg::JointState Ros2Aria::handleWheels(rclcpp::Time stamp)
{
sensor_msgs::msg::JointState wheels;
auto r = this->robot->getRobot();
r->requestEncoderPackets(); // TODO: check if this is synchronous or do we have a race condition or something
wheels.header.stamp = stamp;
wheels.name.resize(2);
wheels.position.resize(2);
wheels.velocity.resize(2);
wheels.effort.resize(0);
wheels.name[0] = "Wheel_L";
wheels.name[1] = "Wheel_R";
wheels.position[0] = r->getLeftEncoder();
wheels.position[1] = r->getRightEncoder();
wheels.velocity[0] = r->getLeftVel();
wheels.velocity[1] = r->getRightVel();
return wheels;
}
void Ros2Aria::publishWheels(sensor_msgs::msg::JointState wheels)
{
if (this->wheels_pub_->get_subscription_count() == 0)
return;
this->wheels_pub_->publish(wheels);
}

View File

@ -0,0 +1,49 @@
cmake_minimum_required(VERSION 3.5)
project(ros2aria_msgs)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
rosidl_generate_interfaces(ros2aria_msgs
"msg/RestrictionsMsg.msg"
"msg/RobotInfoMsg.msg"
DEPENDENCIES std_msgs geometry_msgs
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_export_dependencies(rosidl_default_runtime)
ament_package()

View File

@ -0,0 +1,3 @@
std_msgs/Float64 distance
std_msgs/Float64 linear_velocity
std_msgs/Float64 angular_velocity

View File

@ -0,0 +1,6 @@
std_msgs/UInt8 robot_id
std_msgs/Float64 battery_voltage
geometry_msgs/Twist twist
std_msgs/Bool state
std_msgs/Bool clutch
std_msgs/Bool obstacle_detected

View File

@ -0,0 +1,24 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros2aria_msgs</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="me@irth.pl">wojciech</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>