Skip to content

Commit c2667c2

Browse files
authored
Fix a few more minor nitpicks. (#72)
1. Remove dependencies from the targets that don't need them. 2. Remove a totally unnecessary typedef. 3. Remove unnecessary casts to float. Signed-off-by: Chris Lalancette <[email protected]>
1 parent ddfa435 commit c2667c2

File tree

3 files changed

+4
-9
lines changed

3 files changed

+4
-9
lines changed

turtle_tf2_cpp/CMakeLists.txt

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,6 @@ ament_target_dependencies(
4343
rclcpp
4444
tf2
4545
tf2_ros
46-
turtlesim
4746
)
4847

4948
add_executable(turtle_tf2_broadcaster src/turtle_tf2_broadcaster.cpp)
@@ -72,7 +71,6 @@ ament_target_dependencies(
7271
geometry_msgs
7372
rclcpp
7473
tf2_ros
75-
turtlesim
7674
)
7775

7876
add_executable(dynamic_frame_tf2_broadcaster src/dynamic_frame_tf2_broadcaster.cpp)
@@ -81,7 +79,6 @@ ament_target_dependencies(
8179
geometry_msgs
8280
rclcpp
8381
tf2_ros
84-
turtlesim
8582
)
8683

8784
add_executable(turtle_tf2_message_filter src/turtle_tf2_message_filter.cpp)
@@ -90,7 +87,6 @@ ament_target_dependencies(
9087
geometry_msgs
9188
message_filters
9289
rclcpp
93-
tf2
9490
tf2_geometry_msgs
9591
tf2_ros
9692
)

turtle_tf2_cpp/src/turtle_tf2_message_filter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,7 @@ class PoseDrawer : public rclcpp::Node
4040
// Declare and acquire `target_frame` parameter
4141
target_frame_ = this->declare_parameter<std::string>("target_frame", "turtle1");
4242

43-
typedef std::chrono::duration<int> seconds_type;
44-
seconds_type buffer_timeout(1);
43+
std::chrono::duration<int> buffer_timeout(1);
4544

4645
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
4746
// Create the timer interface before call to waitForTransform,

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
@@ -56,9 +56,9 @@ def on_timer(self):
5656
# Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
5757
request = Spawn.Request()
5858
request.name = 'turtle3'
59-
request.x = float(4)
60-
request.y = float(2)
61-
request.theta = float(0)
59+
request.x = 4.0
60+
request.y = 2.0
61+
request.theta = 0.0
6262
# Call request
6363
self.result = self.spawner.call_async(request)
6464
self.turtle_spawning_service_ready = True

0 commit comments

Comments
 (0)