Skip to content

Commit 55ddd50

Browse files
authored
Used turtlesim_msgs (#78)
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 6481e8f commit 55ddd50

File tree

9 files changed

+24
-22
lines changed

9 files changed

+24
-22
lines changed

turtle_tf2_cpp/CMakeLists.txt

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ find_package(rclcpp REQUIRED)
2121
find_package(tf2 REQUIRED)
2222
find_package(tf2_geometry_msgs REQUIRED)
2323
find_package(tf2_ros REQUIRED)
24-
find_package(turtlesim REQUIRED)
24+
find_package(turtlesim_msgs REQUIRED)
2525

2626
if(TARGET tf2_geometry_msgs::tf2_geometry_msgs)
2727
get_target_property(_include_dirs tf2_geometry_msgs::tf2_geometry_msgs INTERFACE_INCLUDE_DIRECTORIES)
@@ -52,7 +52,7 @@ ament_target_dependencies(
5252
rclcpp
5353
tf2
5454
tf2_ros
55-
turtlesim
55+
turtlesim_msgs
5656
)
5757

5858
add_executable(turtle_tf2_listener src/turtle_tf2_listener.cpp)
@@ -62,7 +62,7 @@ ament_target_dependencies(
6262
rclcpp
6363
tf2
6464
tf2_ros
65-
turtlesim
65+
turtlesim_msgs
6666
)
6767

6868
add_executable(fixed_frame_tf2_broadcaster src/fixed_frame_tf2_broadcaster.cpp)

turtle_tf2_cpp/package.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
<author email="abilkasov@gmail.com">Shyngyskhan Abilkassov</author>
1414

1515
<buildtool_depend>ament_cmake</buildtool_depend>
16-
16+
1717
<depend>geometry_msgs</depend>
1818
<depend>launch</depend>
1919
<depend>launch_ros</depend>
@@ -22,7 +22,7 @@
2222
<depend>tf2</depend>
2323
<depend>tf2_geometry_msgs</depend>
2424
<depend>tf2_ros</depend>
25-
<depend>turtlesim</depend>
25+
<depend>turtlesim_msgs</depend>
2626

2727
<test_depend>ament_lint_auto</test_depend>
2828
<test_depend>ament_lint_common</test_depend>

turtle_tf2_cpp/src/turtle_tf2_broadcaster.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
#include "rclcpp/rclcpp.hpp"
2222
#include "tf2/LinearMath/Quaternion.h"
2323
#include "tf2_ros/transform_broadcaster.h"
24-
#include "turtlesim/msg/pose.hpp"
24+
#include "turtlesim_msgs/msg/pose.hpp"
2525

2626
class FramePublisher : public rclcpp::Node
2727
{
@@ -42,7 +42,7 @@ class FramePublisher : public rclcpp::Node
4242
stream << "/" << turtlename_.c_str() << "/pose";
4343
std::string topic_name = stream.str();
4444

45-
auto handle_turtle_pose = [this](const std::shared_ptr<turtlesim::msg::Pose> msg) {
45+
auto handle_turtle_pose = [this](const std::shared_ptr<turtlesim_msgs::msg::Pose> msg) {
4646
geometry_msgs::msg::TransformStamped t;
4747

4848
// Read message content and assign it to
@@ -70,13 +70,13 @@ class FramePublisher : public rclcpp::Node
7070
// Send the transformation
7171
tf_broadcaster_->sendTransform(t);
7272
};
73-
subscription_ = this->create_subscription<turtlesim::msg::Pose>(
73+
subscription_ = this->create_subscription<turtlesim_msgs::msg::Pose>(
7474
topic_name, 10,
7575
handle_turtle_pose);
7676
}
7777

7878
private:
79-
rclcpp::Subscription<turtlesim::msg::Pose>::SharedPtr subscription_;
79+
rclcpp::Subscription<turtlesim_msgs::msg::Pose>::SharedPtr subscription_;
8080
std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
8181
std::string turtlename_;
8282
};

turtle_tf2_cpp/src/turtle_tf2_listener.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
#include "tf2/exceptions.h"
2424
#include "tf2_ros/transform_listener.h"
2525
#include "tf2_ros/buffer.h"
26-
#include "turtlesim/srv/spawn.hpp"
26+
#include "turtlesim_msgs/srv/spawn.hpp"
2727

2828
using namespace std::chrono_literals;
2929

@@ -45,7 +45,7 @@ class FrameListener : public rclcpp::Node
4545

4646
// Create a client to spawn a turtle
4747
spawner_ =
48-
this->create_client<turtlesim::srv::Spawn>("spawn");
48+
this->create_client<turtlesim_msgs::srv::Spawn>("spawn");
4949

5050
// Create turtle2 velocity publisher
5151
publisher_ =
@@ -102,16 +102,16 @@ class FrameListener : public rclcpp::Node
102102
// Check if the service is ready
103103
if (spawner_->service_is_ready()) {
104104
// Initialize request with turtle name and coordinates
105-
// Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
106-
auto request = std::make_shared<turtlesim::srv::Spawn::Request>();
105+
// Note that x, y and theta are defined as floats in turtlesim_msgs/srv/Spawn
106+
auto request = std::make_shared<turtlesim_msgs::srv::Spawn::Request>();
107107
request->x = 4.0;
108108
request->y = 2.0;
109109
request->theta = 0.0;
110110
request->name = "turtle2";
111111

112112
// Call request
113113
using ServiceResponseFuture =
114-
rclcpp::Client<turtlesim::srv::Spawn>::SharedFuture;
114+
rclcpp::Client<turtlesim_msgs::srv::Spawn>::SharedFuture;
115115
auto response_received_callback = [this](ServiceResponseFuture future) {
116116
auto result = future.get();
117117
if (strcmp(result->name.c_str(), "turtle2") == 0) {
@@ -132,7 +132,7 @@ class FrameListener : public rclcpp::Node
132132
bool turtle_spawning_service_ready_;
133133
// if the turtle was successfully spawned
134134
bool turtle_spawned_;
135-
rclcpp::Client<turtlesim::srv::Spawn>::SharedPtr spawner_{nullptr};
135+
rclcpp::Client<turtlesim_msgs::srv::Spawn>::SharedPtr spawner_{nullptr};
136136
rclcpp::TimerBase::SharedPtr timer_{nullptr};
137137
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_{nullptr};
138138
std::shared_ptr<tf2_ros::TransformListener> tf_listener_{nullptr};

turtle_tf2_cpp/src/turtle_tf2_message_filter.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,9 @@ class PoseDrawer : public rclcpp::Node
5252
tf2_listener_ =
5353
std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
5454

55-
point_sub_.subscribe(this, "/turtle3/turtle_point_stamped");
55+
point_sub_.subscribe(
56+
this, "/turtle3/turtle_point_stamped",
57+
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)));
5658
tf2_filter_ = std::make_shared<tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped>>(
5759
point_sub_, *tf2_buffer_, target_frame_, 100, this->get_node_logging_interface(),
5860
this->get_node_clock_interface(), buffer_timeout);

turtle_tf2_py/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
<exec_depend>python3-numpy</exec_depend>
2020
<exec_depend>rclpy</exec_depend>
2121
<exec_depend>tf2_ros</exec_depend>
22-
<exec_depend>turtlesim</exec_depend>
22+
<exec_depend>turtlesim_msgs</exec_depend>
2323

2424
<test_depend>ament_copyright</test_depend>
2525
<test_depend>ament_flake8</test_depend>

turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323

2424
from tf2_ros import TransformBroadcaster
2525

26-
from turtlesim.msg import Pose
26+
from turtlesim_msgs.msg import Pose
2727

2828

2929
# This function is a stripped down version of the code in

turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ def on_timer(self):
9494
else:
9595
if self.spawner.service_is_ready():
9696
# Initialize request with turtle name and coordinates
97-
# Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
97+
# Note that x, y and theta are defined as floats in turtlesim_msgs/srv/Spawn
9898
request = Spawn.Request()
9999
request.name = 'turtle2'
100100
request.x = 4.0

turtle_tf2_py/turtle_tf2_py/turtle_tf2_message_broadcaster.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,8 @@
1818
import rclpy
1919
from rclpy.node import Node
2020

21-
from turtlesim.msg import Pose
22-
from turtlesim.srv import Spawn
21+
from turtlesim_msgs.msg import Pose
22+
from turtlesim_msgs.srv import Spawn
2323

2424

2525
class PointPublisher(Node):
@@ -53,7 +53,7 @@ def on_timer(self):
5353
else:
5454
if self.spawner.service_is_ready():
5555
# Initialize request with turtle name and coordinates
56-
# Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
56+
# Note that x, y and theta are defined as floats in turtlesim_msgs/srv/Spawn
5757
request = Spawn.Request()
5858
request.name = 'turtle3'
5959
request.x = 4.0

0 commit comments

Comments
 (0)