Skip to content

Commit eb33d70

Browse files
authored
Create turtlesim_msgs (#169)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent b53c4da commit eb33d70

19 files changed

+173
-106
lines changed

turtlesim/CMakeLists.txt

+10-19
Original file line numberDiff line numberDiff line change
@@ -14,29 +14,16 @@ find_package(ament_cmake REQUIRED)
1414
find_package(ament_index_cpp REQUIRED)
1515
find_package(geometry_msgs REQUIRED)
1616
find_package(Qt5 REQUIRED COMPONENTS Widgets)
17-
find_package(rcl_interfaces REQUIRED)
1817
find_package(rclcpp REQUIRED)
1918
find_package(rclcpp_action REQUIRED)
20-
find_package(rosidl_default_generators REQUIRED)
2119
find_package(std_msgs REQUIRED)
2220
find_package(std_srvs REQUIRED)
21+
find_package(turtlesim_msgs REQUIRED)
2322

2423
include_directories(include ${Qt5Widgets_INCLUDE_DIRS})
2524

26-
rosidl_generate_interfaces(${PROJECT_NAME}
27-
"action/RotateAbsolute.action"
28-
"msg/Color.msg"
29-
"msg/Pose.msg"
30-
"srv/Kill.srv"
31-
"srv/SetPen.srv"
32-
"srv/Spawn.srv"
33-
"srv/TeleportAbsolute.srv"
34-
"srv/TeleportRelative.srv")
35-
3625
qt5_wrap_cpp(turtlesim_node_MOCS include/turtlesim/turtle_frame.hpp)
3726

38-
rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" "rosidl_typesupport_cpp")
39-
4027
add_executable(turtlesim_node
4128
src/turtlesim.cpp
4229
src/turtle.cpp
@@ -47,32 +34,32 @@ target_link_libraries(turtlesim_node PRIVATE
4734
ament_index_cpp::ament_index_cpp
4835
${cpp_typesupport_target}
4936
${geometry_msgs_TARGETS}
37+
${turtlesim_msgs_TARGETS}
5038
Qt5::Widgets
51-
${rcl_interfaces_TARGETS}
5239
rclcpp::rclcpp
5340
rclcpp_action::rclcpp_action
5441
${std_srvs_TARGETS}
5542
)
5643

5744
add_executable(turtle_teleop_key tutorials/teleop_turtle_key.cpp)
5845
target_link_libraries(turtle_teleop_key PRIVATE
59-
"${cpp_typesupport_target}"
46+
${turtlesim_msgs_TARGETS}
6047
${geometry_msgs_TARGETS}
6148
rclcpp::rclcpp
6249
rclcpp_action::rclcpp_action
6350
)
6451

6552
add_executable(draw_square tutorials/draw_square.cpp)
6653
target_link_libraries(draw_square PRIVATE
67-
"${cpp_typesupport_target}"
54+
${turtlesim_msgs_TARGETS}
6855
${geometry_msgs_TARGETS}
6956
rclcpp::rclcpp
7057
${std_srvs_TARGETS}
7158
)
7259

7360
add_executable(mimic tutorials/mimic.cpp)
7461
target_link_libraries(mimic PRIVATE
75-
"${cpp_typesupport_target}"
62+
${turtlesim_msgs_TARGETS}
7663
${geometry_msgs_TARGETS}
7764
rclcpp::rclcpp
7865
)
@@ -82,7 +69,11 @@ if(BUILD_TESTING)
8269
ament_lint_auto_find_test_dependencies()
8370
endif()
8471

85-
install(TARGETS turtlesim_node turtle_teleop_key draw_square mimic
72+
install(TARGETS
73+
turtlesim_node
74+
turtle_teleop_key
75+
draw_square
76+
mimic
8677
DESTINATION lib/${PROJECT_NAME})
8778

8879
install(DIRECTORY images

turtlesim/include/turtlesim/turtle.hpp

+21-21
Original file line numberDiff line numberDiff line change
@@ -35,12 +35,12 @@
3535
# include <rclcpp_action/rclcpp_action.hpp>
3636

3737
# include <geometry_msgs/msg/twist.hpp>
38-
# include <turtlesim/action/rotate_absolute.hpp>
39-
# include <turtlesim/msg/color.hpp>
40-
# include <turtlesim/msg/pose.hpp>
41-
# include <turtlesim/srv/set_pen.hpp>
42-
# include <turtlesim/srv/teleport_absolute.hpp>
43-
# include <turtlesim/srv/teleport_relative.hpp>
38+
# include <turtlesim_msgs/action/rotate_absolute.hpp>
39+
# include <turtlesim_msgs/msg/color.hpp>
40+
# include <turtlesim_msgs/msg/pose.hpp>
41+
# include <turtlesim_msgs/srv/set_pen.hpp>
42+
# include <turtlesim_msgs/srv/teleport_absolute.hpp>
43+
# include <turtlesim_msgs/srv/teleport_relative.hpp>
4444
#endif
4545

4646
#include <QImage>
@@ -61,7 +61,7 @@ class Turtle
6161
{
6262
public:
6363
using RotateAbsoluteGoalHandle = rclcpp_action::ServerGoalHandle<
64-
turtlesim::action::RotateAbsolute>;
64+
turtlesim_msgs::action::RotateAbsolute>;
6565

6666
Turtle(
6767
rclcpp::Node::SharedPtr & nh, const std::string & real_name, const QImage & turtle_image,
@@ -75,14 +75,14 @@ class Turtle
7575
private:
7676
void velocityCallback(const geometry_msgs::msg::Twist::ConstSharedPtr vel);
7777
bool setPenCallback(
78-
const turtlesim::srv::SetPen::Request::SharedPtr,
79-
turtlesim::srv::SetPen::Response::SharedPtr);
78+
const turtlesim_msgs::srv::SetPen::Request::SharedPtr,
79+
turtlesim_msgs::srv::SetPen::Response::SharedPtr);
8080
bool teleportRelativeCallback(
81-
const turtlesim::srv::TeleportRelative::Request::SharedPtr,
82-
turtlesim::srv::TeleportRelative::Response::SharedPtr);
81+
const turtlesim_msgs::srv::TeleportRelative::Request::SharedPtr,
82+
turtlesim_msgs::srv::TeleportRelative::Response::SharedPtr);
8383
bool teleportAbsoluteCallback(
84-
const turtlesim::srv::TeleportAbsolute::Request::SharedPtr,
85-
turtlesim::srv::TeleportAbsolute::Response::SharedPtr);
84+
const turtlesim_msgs::srv::TeleportAbsolute::Request::SharedPtr,
85+
turtlesim_msgs::srv::TeleportAbsolute::Response::SharedPtr);
8686
void rotateAbsoluteAcceptCallback(const std::shared_ptr<RotateAbsoluteGoalHandle>);
8787

8888
void rotateImage();
@@ -102,17 +102,17 @@ class Turtle
102102
QPen pen_;
103103

104104
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr velocity_sub_;
105-
rclcpp::Publisher<turtlesim::msg::Pose>::SharedPtr pose_pub_;
106-
rclcpp::Publisher<turtlesim::msg::Color>::SharedPtr color_pub_;
107-
rclcpp::Service<turtlesim::srv::SetPen>::SharedPtr set_pen_srv_;
108-
rclcpp::Service<turtlesim::srv::TeleportRelative>::SharedPtr teleport_relative_srv_;
109-
rclcpp::Service<turtlesim::srv::TeleportAbsolute>::SharedPtr teleport_absolute_srv_;
110-
rclcpp_action::Server<turtlesim::action::RotateAbsolute>
105+
rclcpp::Publisher<turtlesim_msgs::msg::Pose>::SharedPtr pose_pub_;
106+
rclcpp::Publisher<turtlesim_msgs::msg::Color>::SharedPtr color_pub_;
107+
rclcpp::Service<turtlesim_msgs::srv::SetPen>::SharedPtr set_pen_srv_;
108+
rclcpp::Service<turtlesim_msgs::srv::TeleportRelative>::SharedPtr teleport_relative_srv_;
109+
rclcpp::Service<turtlesim_msgs::srv::TeleportAbsolute>::SharedPtr teleport_absolute_srv_;
110+
rclcpp_action::Server<turtlesim_msgs::action::RotateAbsolute>
111111
::SharedPtr rotate_absolute_action_server_;
112112

113113
std::shared_ptr<RotateAbsoluteGoalHandle> rotate_absolute_goal_handle_;
114-
std::shared_ptr<turtlesim::action::RotateAbsolute::Feedback> rotate_absolute_feedback_;
115-
std::shared_ptr<turtlesim::action::RotateAbsolute::Result> rotate_absolute_result_;
114+
std::shared_ptr<turtlesim_msgs::action::RotateAbsolute::Feedback> rotate_absolute_feedback_;
115+
std::shared_ptr<turtlesim_msgs::action::RotateAbsolute::Result> rotate_absolute_result_;
116116
qreal rotate_absolute_start_orient_;
117117

118118
rclcpp::Time last_command_time_;

turtlesim/include/turtlesim/turtle_frame.hpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,8 @@
4949

5050
#include <rcl_interfaces/msg/parameter_event.hpp>
5151
#include <std_srvs/srv/empty.hpp>
52-
#include <turtlesim/srv/spawn.hpp>
53-
#include <turtlesim/srv/kill.hpp>
52+
#include <turtlesim_msgs/srv/spawn.hpp>
53+
#include <turtlesim_msgs/srv/kill.hpp>
5454
#endif
5555

5656
namespace turtlesim
@@ -86,11 +86,11 @@ private slots:
8686
const std_srvs::srv::Empty::Request::SharedPtr,
8787
std_srvs::srv::Empty::Response::SharedPtr);
8888
bool spawnCallback(
89-
const turtlesim::srv::Spawn::Request::SharedPtr,
90-
turtlesim::srv::Spawn::Response::SharedPtr);
89+
const turtlesim_msgs::srv::Spawn::Request::SharedPtr,
90+
turtlesim_msgs::srv::Spawn::Response::SharedPtr);
9191
bool killCallback(
92-
const turtlesim::srv::Kill::Request::SharedPtr,
93-
turtlesim::srv::Kill::Response::SharedPtr);
92+
const turtlesim_msgs::srv::Kill::Request::SharedPtr,
93+
turtlesim_msgs::srv::Kill::Response::SharedPtr);
9494

9595
void parameterEventCallback(const rcl_interfaces::msg::ParameterEvent::ConstSharedPtr);
9696

@@ -106,8 +106,8 @@ private slots:
106106

107107
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr clear_srv_;
108108
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_srv_;
109-
rclcpp::Service<turtlesim::srv::Spawn>::SharedPtr spawn_srv_;
110-
rclcpp::Service<turtlesim::srv::Kill>::SharedPtr kill_srv_;
109+
rclcpp::Service<turtlesim_msgs::srv::Spawn>::SharedPtr spawn_srv_;
110+
rclcpp::Service<turtlesim_msgs::srv::Kill>::SharedPtr kill_srv_;
111111
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_event_sub_;
112112

113113
typedef std::map<std::string, TurtlePtr> M_Turtle;

turtlesim/package.xml

+1-5
Original file line numberDiff line numberDiff line change
@@ -26,25 +26,21 @@
2626
<build_depend>qtbase5-dev</build_depend>
2727

2828
<buildtool_depend>ament_cmake</buildtool_depend>
29-
<buildtool_depend>rosidl_default_generators</buildtool_depend>
3029

3130
<exec_depend>libqt5-core</exec_depend>
3231
<exec_depend>libqt5-gui</exec_depend>
33-
<exec_depend>rosidl_default_runtime</exec_depend>
3432

3533
<depend>ament_index_cpp</depend>
3634
<depend>geometry_msgs</depend>
37-
<depend>rcl_interfaces</depend>
3835
<depend>rclcpp</depend>
3936
<depend>rclcpp_action</depend>
4037
<depend>std_msgs</depend>
4138
<depend>std_srvs</depend>
39+
<depend>turtlesim_msgs</depend>
4240

4341
<test_depend>ament_lint_auto</test_depend>
4442
<test_depend>ament_lint_common</test_depend>
4543

46-
<member_of_group>rosidl_interface_packages</member_of_group>
47-
4844
<export>
4945
<build_type>ament_cmake</build_type>
5046
</export>

turtlesim/src/turtle.cpp

+31-30
Original file line numberDiff line numberDiff line change
@@ -38,12 +38,12 @@
3838
#include "geometry_msgs/msg/twist.hpp"
3939
#include "rclcpp/rclcpp.hpp"
4040

41-
#include "turtlesim/action/rotate_absolute.hpp"
42-
#include "turtlesim/msg/pose.hpp"
43-
#include "turtlesim/msg/color.hpp"
44-
#include "turtlesim/srv/set_pen.hpp"
45-
#include "turtlesim/srv/teleport_absolute.hpp"
46-
#include "turtlesim/srv/teleport_relative.hpp"
41+
#include "turtlesim_msgs/action/rotate_absolute.hpp"
42+
#include "turtlesim_msgs/msg/pose.hpp"
43+
#include "turtlesim_msgs/msg/color.hpp"
44+
#include "turtlesim_msgs/srv/set_pen.hpp"
45+
#include "turtlesim_msgs/srv/teleport_absolute.hpp"
46+
#include "turtlesim_msgs/srv/teleport_relative.hpp"
4747
#include "turtlesim/qos.hpp"
4848

4949
#define DEFAULT_PEN_R 0xb3
@@ -78,37 +78,38 @@ Turtle::Turtle(
7878
real_name + "/cmd_vel", qos, std::bind(
7979
&Turtle::velocityCallback, this,
8080
std::placeholders::_1));
81-
pose_pub_ = nh_->create_publisher<turtlesim::msg::Pose>(real_name + "/pose", qos);
82-
color_pub_ = nh_->create_publisher<turtlesim::msg::Color>(real_name + "/color_sensor", qos);
81+
pose_pub_ = nh_->create_publisher<turtlesim_msgs::msg::Pose>(real_name + "/pose", qos);
82+
color_pub_ = nh_->create_publisher<turtlesim_msgs::msg::Color>(real_name + "/color_sensor", qos);
8383
set_pen_srv_ =
84-
nh_->create_service<turtlesim::srv::SetPen>(
84+
nh_->create_service<turtlesim_msgs::srv::SetPen>(
8585
real_name + "/set_pen",
8686
std::bind(&Turtle::setPenCallback, this, std::placeholders::_1, std::placeholders::_2));
87-
teleport_relative_srv_ = nh_->create_service<turtlesim::srv::TeleportRelative>(
87+
teleport_relative_srv_ = nh_->create_service<turtlesim_msgs::srv::TeleportRelative>(
8888
real_name + "/teleport_relative",
8989
std::bind(
9090
&Turtle::teleportRelativeCallback, this, std::placeholders::_1,
9191
std::placeholders::_2));
92-
teleport_absolute_srv_ = nh_->create_service<turtlesim::srv::TeleportAbsolute>(
92+
teleport_absolute_srv_ = nh_->create_service<turtlesim_msgs::srv::TeleportAbsolute>(
9393
real_name + "/teleport_absolute",
9494
std::bind(
9595
&Turtle::teleportAbsoluteCallback, this, std::placeholders::_1,
9696
std::placeholders::_2));
97-
rotate_absolute_action_server_ = rclcpp_action::create_server<turtlesim::action::RotateAbsolute>(
98-
nh,
99-
real_name + "/rotate_absolute",
97+
rotate_absolute_action_server_ =
98+
rclcpp_action::create_server<turtlesim_msgs::action::RotateAbsolute>(
99+
nh,
100+
real_name + "/rotate_absolute",
100101
[](const rclcpp_action::GoalUUID &,
101-
std::shared_ptr<const turtlesim::action::RotateAbsolute::Goal>)
102+
std::shared_ptr<const turtlesim_msgs::action::RotateAbsolute::Goal>)
102103
{
103-
// Accept all goals
104+
// Accept all goals
104105
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
105-
},
106+
},
106107
[](const std::shared_ptr<RotateAbsoluteGoalHandle>)
107108
{
108-
// Accept all cancel requests
109+
// Accept all cancel requests
109110
return rclcpp_action::CancelResponse::ACCEPT;
110-
},
111-
std::bind(&Turtle::rotateAbsoluteAcceptCallback, this, std::placeholders::_1));
111+
},
112+
std::bind(&Turtle::rotateAbsoluteAcceptCallback, this, std::placeholders::_1));
112113

113114
last_command_time_ = nh_->now();
114115

@@ -137,8 +138,8 @@ void Turtle::velocityCallback(const geometry_msgs::msg::Twist::ConstSharedPtr ve
137138
}
138139

139140
bool Turtle::setPenCallback(
140-
const turtlesim::srv::SetPen::Request::SharedPtr req,
141-
turtlesim::srv::SetPen::Response::SharedPtr)
141+
const turtlesim_msgs::srv::SetPen::Request::SharedPtr req,
142+
turtlesim_msgs::srv::SetPen::Response::SharedPtr)
142143
{
143144
pen_on_ = !req->off;
144145
if (req->off) {
@@ -155,16 +156,16 @@ bool Turtle::setPenCallback(
155156
}
156157

157158
bool Turtle::teleportRelativeCallback(
158-
const turtlesim::srv::TeleportRelative::Request::SharedPtr req,
159-
turtlesim::srv::TeleportRelative::Response::SharedPtr)
159+
const turtlesim_msgs::srv::TeleportRelative::Request::SharedPtr req,
160+
turtlesim_msgs::srv::TeleportRelative::Response::SharedPtr)
160161
{
161162
teleport_requests_.push_back(TeleportRequest(0, 0, req->angular, req->linear, true));
162163
return true;
163164
}
164165

165166
bool Turtle::teleportAbsoluteCallback(
166-
const turtlesim::srv::TeleportAbsolute::Request::SharedPtr req,
167-
turtlesim::srv::TeleportAbsolute::Response::SharedPtr)
167+
const turtlesim_msgs::srv::TeleportAbsolute::Request::SharedPtr req,
168+
turtlesim_msgs::srv::TeleportAbsolute::Response::SharedPtr)
168169
{
169170
teleport_requests_.push_back(TeleportRequest(req->x, req->y, req->theta, 0, false));
170171
return true;
@@ -181,8 +182,8 @@ void Turtle::rotateAbsoluteAcceptCallback(
181182
rotate_absolute_goal_handle_->abort(rotate_absolute_result_);
182183
}
183184
rotate_absolute_goal_handle_ = goal_handle;
184-
rotate_absolute_feedback_.reset(new turtlesim::action::RotateAbsolute::Feedback);
185-
rotate_absolute_result_.reset(new turtlesim::action::RotateAbsolute::Result);
185+
rotate_absolute_feedback_.reset(new turtlesim_msgs::action::RotateAbsolute::Feedback);
186+
rotate_absolute_result_.reset(new turtlesim_msgs::action::RotateAbsolute::Result);
186187
rotate_absolute_start_orient_ = orient_;
187188
}
188189

@@ -300,7 +301,7 @@ bool Turtle::update(
300301
static_cast<double>(canvas_height)));
301302

302303
// Publish pose of the turtle
303-
auto p = std::make_unique<turtlesim::msg::Pose>();
304+
auto p = std::make_unique<turtlesim_msgs::msg::Pose>();
304305
p->x = pos_.x();
305306
p->y = canvas_height - pos_.y();
306307
p->theta = orient_;
@@ -310,7 +311,7 @@ bool Turtle::update(
310311

311312
// Figure out (and publish) the color underneath the turtle
312313
{
313-
auto color = std::make_unique<turtlesim::msg::Color>();
314+
auto color = std::make_unique<turtlesim_msgs::msg::Color>();
314315
QRgb pixel = path_image.pixel((pos_ * meter_).toPoint());
315316
color->r = qRed(pixel);
316317
color->g = qGreen(pixel);

0 commit comments

Comments
 (0)