Skip to content

Commit

Permalink
Merge branch 'rolling' into ahcorde/rolling/clean_ci
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Jul 11, 2024
2 parents af4539e + 59a0a0e commit bb05465
Show file tree
Hide file tree
Showing 13 changed files with 78 additions and 60 deletions.
3 changes: 3 additions & 0 deletions geometry_tutorials/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package geometry_tutorials
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.6.0 (2024-07-10)
------------------

0.3.6 (2022-09-15)
------------------

Expand Down
2 changes: 1 addition & 1 deletion geometry_tutorials/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>geometry_tutorials</name>
<version>0.3.6</version>
<version>0.6.0</version>
<description>Metapackage of geometry tutorials ROS.</description>
<maintainer email="alejandro@openrobotics.org">Alejandro Hernández Cordero</maintainer>
<maintainer email="audrow@openrobotics.org">Audrow Nash</maintainer>
Expand Down
12 changes: 12 additions & 0 deletions turtle_tf2_cpp/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,18 @@
Changelog for package turtle_tf2_cpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.6.0 (2024-07-10)
------------------
* Used turtlesim_msgs (`#78 <https://github.com/ros/geometry_tutorials/issues/78>`_)
* Migrate std::bind calls to lambda expressions (`#76 <https://github.com/ros/geometry_tutorials/issues/76>`_)
* ♻️ Geometry msgs lambda refactor
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
* Fix a few more minor nitpicks. (`#72 <https://github.com/ros/geometry_tutorials/issues/72>`_)
1. Remove dependencies from the targets that don't need them.
2. Remove a totally unnecessary typedef.
3. Remove unnecessary casts to float.
* Contributors: Alejandro Hernández Cordero, Chris Lalancette, Felipe Gomes de Melo

0.3.6 (2022-09-15)
------------------
* Minor cleanups across the tutorials. (`#71 <https://github.com/ros/geometry_tutorials/issues/71>`_)
Expand Down
70 changes: 32 additions & 38 deletions turtle_tf2_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ find_package(rclcpp REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(turtlesim REQUIRED)
find_package(turtlesim_msgs REQUIRED)

if(TARGET tf2_geometry_msgs::tf2_geometry_msgs)
get_target_property(_include_dirs tf2_geometry_msgs::tf2_geometry_msgs INTERFACE_INCLUDE_DIRECTORIES)
Expand All @@ -37,58 +37,52 @@ find_file(TF2_CPP_HEADERS
)

add_executable(static_turtle_tf2_broadcaster src/static_turtle_tf2_broadcaster.cpp)
ament_target_dependencies(
static_turtle_tf2_broadcaster
geometry_msgs
rclcpp
tf2
tf2_ros
target_link_libraries(static_turtle_tf2_broadcaster PRIVATE
${geometry_msgs_TARGET}
rclcpp::rclcpp
tf2::tf2
tf2_ros::tf2_ros
)

add_executable(turtle_tf2_broadcaster src/turtle_tf2_broadcaster.cpp)
ament_target_dependencies(
turtle_tf2_broadcaster
geometry_msgs
rclcpp
tf2
tf2_ros
turtlesim
target_link_libraries(turtle_tf2_broadcaster PRIVATE
${geometry_msgs_TARGET}
rclcpp::rclcpp
tf2::tf2
tf2_ros::tf2_ros
${turtlesim_msgs_TARGETS}
)

add_executable(turtle_tf2_listener src/turtle_tf2_listener.cpp)
ament_target_dependencies(
turtle_tf2_listener
geometry_msgs
rclcpp
tf2
tf2_ros
turtlesim
target_link_libraries(turtle_tf2_listener PRIVATE
${geometry_msgs_TARGET}
rclcpp::rclcpp
tf2::tf2
tf2_ros::tf2_ros
${turtlesim_msgs_TARGETS}
)

add_executable(fixed_frame_tf2_broadcaster src/fixed_frame_tf2_broadcaster.cpp)
ament_target_dependencies(
fixed_frame_tf2_broadcaster
geometry_msgs
rclcpp
tf2_ros
target_link_libraries(fixed_frame_tf2_broadcaster PRIVATE
${geometry_msgs_TARGET}
rclcpp::rclcpp
tf2_ros::tf2_ros
)

add_executable(dynamic_frame_tf2_broadcaster src/dynamic_frame_tf2_broadcaster.cpp)
ament_target_dependencies(
dynamic_frame_tf2_broadcaster
geometry_msgs
rclcpp
tf2_ros
target_link_libraries(dynamic_frame_tf2_broadcaster PRIVATE
${geometry_msgs_TARGETS}
rclcpp::rclcpp
tf2_ros::tf2_ros
)

add_executable(turtle_tf2_message_filter src/turtle_tf2_message_filter.cpp)
ament_target_dependencies(
turtle_tf2_message_filter
geometry_msgs
message_filters
rclcpp
tf2_geometry_msgs
tf2_ros
target_link_libraries(turtle_tf2_message_filter PRIVATE
${geometry_msgs_TARGETS}
message_filters::message_filters
rclcpp::rclcpp
${tf2_geometry_msgs_TARGETS}
tf2_ros::tf2_ros
)

if(EXISTS ${TF2_CPP_HEADERS})
Expand Down
6 changes: 3 additions & 3 deletions turtle_tf2_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>turtle_tf2_cpp</name>
<version>0.3.6</version>
<version>0.6.0</version>
<description>
turtle_tf2_cpp demonstrates how to write a ROS2 C++ tf2 broadcaster and listener with the turtlesim. The turtle_tf2_listener commands turtle2 to follow turtle1 around as you drive turtle1 using the keyboard.
</description>
Expand All @@ -13,7 +13,7 @@
<author email="abilkasov@gmail.com">Shyngyskhan Abilkassov</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>geometry_msgs</depend>
<depend>launch</depend>
<depend>launch_ros</depend>
Expand All @@ -22,7 +22,7 @@
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>turtlesim</depend>
<depend>turtlesim_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
8 changes: 4 additions & 4 deletions turtle_tf2_cpp/src/turtle_tf2_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2_ros/transform_broadcaster.h"
#include "turtlesim/msg/pose.hpp"
#include "turtlesim_msgs/msg/pose.hpp"

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

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

// Read message content and assign it to
Expand Down Expand Up @@ -70,13 +70,13 @@ class FramePublisher : public rclcpp::Node
// Send the transformation
tf_broadcaster_->sendTransform(t);
};
subscription_ = this->create_subscription<turtlesim::msg::Pose>(
subscription_ = this->create_subscription<turtlesim_msgs::msg::Pose>(
topic_name, 10,
handle_turtle_pose);
}

private:
rclcpp::Subscription<turtlesim::msg::Pose>::SharedPtr subscription_;
rclcpp::Subscription<turtlesim_msgs::msg::Pose>::SharedPtr subscription_;
std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
std::string turtlename_;
};
Expand Down
12 changes: 6 additions & 6 deletions turtle_tf2_cpp/src/turtle_tf2_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "tf2/exceptions.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/buffer.h"
#include "turtlesim/srv/spawn.hpp"
#include "turtlesim_msgs/srv/spawn.hpp"

using namespace std::chrono_literals;

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

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

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

// Call request
using ServiceResponseFuture =
rclcpp::Client<turtlesim::srv::Spawn>::SharedFuture;
rclcpp::Client<turtlesim_msgs::srv::Spawn>::SharedFuture;
auto response_received_callback = [this](ServiceResponseFuture future) {
auto result = future.get();
if (strcmp(result->name.c_str(), "turtle2") == 0) {
Expand All @@ -132,7 +132,7 @@ class FrameListener : public rclcpp::Node
bool turtle_spawning_service_ready_;
// if the turtle was successfully spawned
bool turtle_spawned_;
rclcpp::Client<turtlesim::srv::Spawn>::SharedPtr spawner_{nullptr};
rclcpp::Client<turtlesim_msgs::srv::Spawn>::SharedPtr spawner_{nullptr};
rclcpp::TimerBase::SharedPtr timer_{nullptr};
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_{nullptr};
std::shared_ptr<tf2_ros::TransformListener> tf_listener_{nullptr};
Expand Down
9 changes: 9 additions & 0 deletions turtle_tf2_py/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@
Changelog for package turtle_tf2_py
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.6.0 (2024-07-10)
------------------
* Used turtlesim_msgs (`#78 <https://github.com/ros/geometry_tutorials/issues/78>`_)
* Fix a few more minor nitpicks. (`#72 <https://github.com/ros/geometry_tutorials/issues/72>`_)
1. Remove dependencies from the targets that don't need them.
2. Remove a totally unnecessary typedef.
3. Remove unnecessary casts to float.
* Contributors: Alejandro Hernández Cordero, Chris Lalancette

0.3.6 (2022-09-15)
------------------
* Minor cleanups across the tutorials. (`#71 <https://github.com/ros/geometry_tutorials/issues/71>`_)
Expand Down
4 changes: 2 additions & 2 deletions turtle_tf2_py/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>turtle_tf2_py</name>
<version>0.3.6</version>
<version>0.6.0</version>
<description>
turtle_tf2_py demonstrates how to write a ROS2 Python tf2 broadcaster and listener with the turtlesim. The turtle_tf2_listener commands turtle2 to follow turtle1 around as you drive turtle1 using the keyboard.
</description>
Expand All @@ -19,7 +19,7 @@
<exec_depend>python3-numpy</exec_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>turtlesim</exec_depend>
<exec_depend>turtlesim_msgs</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion turtle_tf2_py/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

setup(
name=package_name,
version='0.3.6',
version='0.6.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
Expand Down
2 changes: 1 addition & 1 deletion turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

from tf2_ros import TransformBroadcaster

from turtlesim.msg import Pose
from turtlesim_msgs.msg import Pose


# This function is a stripped down version of the code in
Expand Down
2 changes: 1 addition & 1 deletion turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ def on_timer(self):
else:
if self.spawner.service_is_ready():
# Initialize request with turtle name and coordinates
# Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
# Note that x, y and theta are defined as floats in turtlesim_msgs/srv/Spawn
request = Spawn.Request()
request.name = 'turtle2'
request.x = 4.0
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 @@ -18,8 +18,8 @@
import rclpy
from rclpy.node import Node

from turtlesim.msg import Pose
from turtlesim.srv import Spawn
from turtlesim_msgs.msg import Pose
from turtlesim_msgs.srv import Spawn


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

0 comments on commit bb05465

Please sign in to comment.