Skip to content

Commit

Permalink
Fix a few more minor nitpicks. (#72)
Browse files Browse the repository at this point in the history
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 <clalancette@openrobotics.org>
  • Loading branch information
clalancette authored Sep 15, 2022
1 parent ddfa435 commit c2667c2
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 9 deletions.
4 changes: 0 additions & 4 deletions turtle_tf2_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ ament_target_dependencies(
rclcpp
tf2
tf2_ros
turtlesim
)

add_executable(turtle_tf2_broadcaster src/turtle_tf2_broadcaster.cpp)
Expand Down Expand Up @@ -72,7 +71,6 @@ ament_target_dependencies(
geometry_msgs
rclcpp
tf2_ros
turtlesim
)

add_executable(dynamic_frame_tf2_broadcaster src/dynamic_frame_tf2_broadcaster.cpp)
Expand All @@ -81,7 +79,6 @@ ament_target_dependencies(
geometry_msgs
rclcpp
tf2_ros
turtlesim
)

add_executable(turtle_tf2_message_filter src/turtle_tf2_message_filter.cpp)
Expand All @@ -90,7 +87,6 @@ ament_target_dependencies(
geometry_msgs
message_filters
rclcpp
tf2
tf2_geometry_msgs
tf2_ros
)
Expand Down
3 changes: 1 addition & 2 deletions turtle_tf2_cpp/src/turtle_tf2_message_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,7 @@ class PoseDrawer : public rclcpp::Node
// Declare and acquire `target_frame` parameter
target_frame_ = this->declare_parameter<std::string>("target_frame", "turtle1");

typedef std::chrono::duration<int> seconds_type;
seconds_type buffer_timeout(1);
std::chrono::duration<int> buffer_timeout(1);

tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
// Create the timer interface before call to waitForTransform,
Expand Down
6 changes: 3 additions & 3 deletions turtle_tf2_py/turtle_tf2_py/turtle_tf2_message_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,9 @@ def on_timer(self):
# Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
request = Spawn.Request()
request.name = 'turtle3'
request.x = float(4)
request.y = float(2)
request.theta = float(0)
request.x = 4.0
request.y = 2.0
request.theta = 0.0
# Call request
self.result = self.spawner.call_async(request)
self.turtle_spawning_service_ready = True
Expand Down

0 comments on commit c2667c2

Please sign in to comment.