Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create turtlesim_msgs #169

Merged
merged 3 commits into from
Jul 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 10 additions & 19 deletions turtlesim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,29 +14,16 @@ find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(Qt5 REQUIRED COMPONENTS Widgets)
find_package(rcl_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(turtlesim_msgs REQUIRED)

include_directories(include ${Qt5Widgets_INCLUDE_DIRS})

rosidl_generate_interfaces(${PROJECT_NAME}
"action/RotateAbsolute.action"
"msg/Color.msg"
"msg/Pose.msg"
"srv/Kill.srv"
"srv/SetPen.srv"
"srv/Spawn.srv"
"srv/TeleportAbsolute.srv"
"srv/TeleportRelative.srv")

qt5_wrap_cpp(turtlesim_node_MOCS include/turtlesim/turtle_frame.hpp)

rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" "rosidl_typesupport_cpp")

add_executable(turtlesim_node
src/turtlesim.cpp
src/turtle.cpp
Expand All @@ -47,32 +34,32 @@ target_link_libraries(turtlesim_node PRIVATE
ament_index_cpp::ament_index_cpp
${cpp_typesupport_target}
${geometry_msgs_TARGETS}
${turtlesim_msgs_TARGETS}
Qt5::Widgets
${rcl_interfaces_TARGETS}
rclcpp::rclcpp
rclcpp_action::rclcpp_action
${std_srvs_TARGETS}
)

add_executable(turtle_teleop_key tutorials/teleop_turtle_key.cpp)
target_link_libraries(turtle_teleop_key PRIVATE
"${cpp_typesupport_target}"
${turtlesim_msgs_TARGETS}
${geometry_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_action::rclcpp_action
)

add_executable(draw_square tutorials/draw_square.cpp)
target_link_libraries(draw_square PRIVATE
"${cpp_typesupport_target}"
${turtlesim_msgs_TARGETS}
${geometry_msgs_TARGETS}
rclcpp::rclcpp
${std_srvs_TARGETS}
)

add_executable(mimic tutorials/mimic.cpp)
target_link_libraries(mimic PRIVATE
"${cpp_typesupport_target}"
${turtlesim_msgs_TARGETS}
${geometry_msgs_TARGETS}
rclcpp::rclcpp
)
Expand All @@ -82,7 +69,11 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()

install(TARGETS turtlesim_node turtle_teleop_key draw_square mimic
install(TARGETS
turtlesim_node
turtle_teleop_key
draw_square
mimic
DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY images
Expand Down
42 changes: 21 additions & 21 deletions turtlesim/include/turtlesim/turtle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,12 @@
# include <rclcpp_action/rclcpp_action.hpp>

# include <geometry_msgs/msg/twist.hpp>
# include <turtlesim/action/rotate_absolute.hpp>
# include <turtlesim/msg/color.hpp>
# include <turtlesim/msg/pose.hpp>
# include <turtlesim/srv/set_pen.hpp>
# include <turtlesim/srv/teleport_absolute.hpp>
# include <turtlesim/srv/teleport_relative.hpp>
# include <turtlesim_msgs/action/rotate_absolute.hpp>
# include <turtlesim_msgs/msg/color.hpp>
# include <turtlesim_msgs/msg/pose.hpp>
# include <turtlesim_msgs/srv/set_pen.hpp>
# include <turtlesim_msgs/srv/teleport_absolute.hpp>
# include <turtlesim_msgs/srv/teleport_relative.hpp>
#endif

#include <QImage>
Expand All @@ -61,7 +61,7 @@ class Turtle
{
public:
using RotateAbsoluteGoalHandle = rclcpp_action::ServerGoalHandle<
turtlesim::action::RotateAbsolute>;
turtlesim_msgs::action::RotateAbsolute>;

Turtle(
rclcpp::Node::SharedPtr & nh, const std::string & real_name, const QImage & turtle_image,
Expand All @@ -75,14 +75,14 @@ class Turtle
private:
void velocityCallback(const geometry_msgs::msg::Twist::ConstSharedPtr vel);
bool setPenCallback(
const turtlesim::srv::SetPen::Request::SharedPtr,
turtlesim::srv::SetPen::Response::SharedPtr);
const turtlesim_msgs::srv::SetPen::Request::SharedPtr,
turtlesim_msgs::srv::SetPen::Response::SharedPtr);
bool teleportRelativeCallback(
const turtlesim::srv::TeleportRelative::Request::SharedPtr,
turtlesim::srv::TeleportRelative::Response::SharedPtr);
const turtlesim_msgs::srv::TeleportRelative::Request::SharedPtr,
turtlesim_msgs::srv::TeleportRelative::Response::SharedPtr);
bool teleportAbsoluteCallback(
const turtlesim::srv::TeleportAbsolute::Request::SharedPtr,
turtlesim::srv::TeleportAbsolute::Response::SharedPtr);
const turtlesim_msgs::srv::TeleportAbsolute::Request::SharedPtr,
turtlesim_msgs::srv::TeleportAbsolute::Response::SharedPtr);
void rotateAbsoluteAcceptCallback(const std::shared_ptr<RotateAbsoluteGoalHandle>);

void rotateImage();
Expand All @@ -102,17 +102,17 @@ class Turtle
QPen pen_;

rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr velocity_sub_;
rclcpp::Publisher<turtlesim::msg::Pose>::SharedPtr pose_pub_;
rclcpp::Publisher<turtlesim::msg::Color>::SharedPtr color_pub_;
rclcpp::Service<turtlesim::srv::SetPen>::SharedPtr set_pen_srv_;
rclcpp::Service<turtlesim::srv::TeleportRelative>::SharedPtr teleport_relative_srv_;
rclcpp::Service<turtlesim::srv::TeleportAbsolute>::SharedPtr teleport_absolute_srv_;
rclcpp_action::Server<turtlesim::action::RotateAbsolute>
rclcpp::Publisher<turtlesim_msgs::msg::Pose>::SharedPtr pose_pub_;
rclcpp::Publisher<turtlesim_msgs::msg::Color>::SharedPtr color_pub_;
rclcpp::Service<turtlesim_msgs::srv::SetPen>::SharedPtr set_pen_srv_;
rclcpp::Service<turtlesim_msgs::srv::TeleportRelative>::SharedPtr teleport_relative_srv_;
rclcpp::Service<turtlesim_msgs::srv::TeleportAbsolute>::SharedPtr teleport_absolute_srv_;
rclcpp_action::Server<turtlesim_msgs::action::RotateAbsolute>
::SharedPtr rotate_absolute_action_server_;

std::shared_ptr<RotateAbsoluteGoalHandle> rotate_absolute_goal_handle_;
std::shared_ptr<turtlesim::action::RotateAbsolute::Feedback> rotate_absolute_feedback_;
std::shared_ptr<turtlesim::action::RotateAbsolute::Result> rotate_absolute_result_;
std::shared_ptr<turtlesim_msgs::action::RotateAbsolute::Feedback> rotate_absolute_feedback_;
std::shared_ptr<turtlesim_msgs::action::RotateAbsolute::Result> rotate_absolute_result_;
qreal rotate_absolute_start_orient_;

rclcpp::Time last_command_time_;
Expand Down
16 changes: 8 additions & 8 deletions turtlesim/include/turtlesim/turtle_frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@

#include <rcl_interfaces/msg/parameter_event.hpp>
#include <std_srvs/srv/empty.hpp>
#include <turtlesim/srv/spawn.hpp>
#include <turtlesim/srv/kill.hpp>
#include <turtlesim_msgs/srv/spawn.hpp>
#include <turtlesim_msgs/srv/kill.hpp>
#endif

namespace turtlesim
Expand Down Expand Up @@ -86,11 +86,11 @@ private slots:
const std_srvs::srv::Empty::Request::SharedPtr,
std_srvs::srv::Empty::Response::SharedPtr);
bool spawnCallback(
const turtlesim::srv::Spawn::Request::SharedPtr,
turtlesim::srv::Spawn::Response::SharedPtr);
const turtlesim_msgs::srv::Spawn::Request::SharedPtr,
turtlesim_msgs::srv::Spawn::Response::SharedPtr);
bool killCallback(
const turtlesim::srv::Kill::Request::SharedPtr,
turtlesim::srv::Kill::Response::SharedPtr);
const turtlesim_msgs::srv::Kill::Request::SharedPtr,
turtlesim_msgs::srv::Kill::Response::SharedPtr);

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

Expand All @@ -106,8 +106,8 @@ private slots:

rclcpp::Service<std_srvs::srv::Empty>::SharedPtr clear_srv_;
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_srv_;
rclcpp::Service<turtlesim::srv::Spawn>::SharedPtr spawn_srv_;
rclcpp::Service<turtlesim::srv::Kill>::SharedPtr kill_srv_;
rclcpp::Service<turtlesim_msgs::srv::Spawn>::SharedPtr spawn_srv_;
rclcpp::Service<turtlesim_msgs::srv::Kill>::SharedPtr kill_srv_;
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_event_sub_;

typedef std::map<std::string, TurtlePtr> M_Turtle;
Expand Down
6 changes: 1 addition & 5 deletions turtlesim/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,25 +26,21 @@
<build_depend>qtbase5-dev</build_depend>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<exec_depend>libqt5-core</exec_depend>
<exec_depend>libqt5-gui</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>

<depend>ament_index_cpp</depend>
<depend>geometry_msgs</depend>
<depend>rcl_interfaces</depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>turtlesim_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
61 changes: 31 additions & 30 deletions turtlesim/src/turtle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,12 @@
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"

#include "turtlesim/action/rotate_absolute.hpp"
#include "turtlesim/msg/pose.hpp"
#include "turtlesim/msg/color.hpp"
#include "turtlesim/srv/set_pen.hpp"
#include "turtlesim/srv/teleport_absolute.hpp"
#include "turtlesim/srv/teleport_relative.hpp"
#include "turtlesim_msgs/action/rotate_absolute.hpp"
#include "turtlesim_msgs/msg/pose.hpp"
#include "turtlesim_msgs/msg/color.hpp"
#include "turtlesim_msgs/srv/set_pen.hpp"
#include "turtlesim_msgs/srv/teleport_absolute.hpp"
#include "turtlesim_msgs/srv/teleport_relative.hpp"
#include "turtlesim/qos.hpp"

#define DEFAULT_PEN_R 0xb3
Expand Down Expand Up @@ -78,37 +78,38 @@ Turtle::Turtle(
real_name + "/cmd_vel", qos, std::bind(
&Turtle::velocityCallback, this,
std::placeholders::_1));
pose_pub_ = nh_->create_publisher<turtlesim::msg::Pose>(real_name + "/pose", qos);
color_pub_ = nh_->create_publisher<turtlesim::msg::Color>(real_name + "/color_sensor", qos);
pose_pub_ = nh_->create_publisher<turtlesim_msgs::msg::Pose>(real_name + "/pose", qos);
color_pub_ = nh_->create_publisher<turtlesim_msgs::msg::Color>(real_name + "/color_sensor", qos);
set_pen_srv_ =
nh_->create_service<turtlesim::srv::SetPen>(
nh_->create_service<turtlesim_msgs::srv::SetPen>(
real_name + "/set_pen",
std::bind(&Turtle::setPenCallback, this, std::placeholders::_1, std::placeholders::_2));
teleport_relative_srv_ = nh_->create_service<turtlesim::srv::TeleportRelative>(
teleport_relative_srv_ = nh_->create_service<turtlesim_msgs::srv::TeleportRelative>(
real_name + "/teleport_relative",
std::bind(
&Turtle::teleportRelativeCallback, this, std::placeholders::_1,
std::placeholders::_2));
teleport_absolute_srv_ = nh_->create_service<turtlesim::srv::TeleportAbsolute>(
teleport_absolute_srv_ = nh_->create_service<turtlesim_msgs::srv::TeleportAbsolute>(
real_name + "/teleport_absolute",
std::bind(
&Turtle::teleportAbsoluteCallback, this, std::placeholders::_1,
std::placeholders::_2));
rotate_absolute_action_server_ = rclcpp_action::create_server<turtlesim::action::RotateAbsolute>(
nh,
real_name + "/rotate_absolute",
rotate_absolute_action_server_ =
rclcpp_action::create_server<turtlesim_msgs::action::RotateAbsolute>(
nh,
real_name + "/rotate_absolute",
[](const rclcpp_action::GoalUUID &,
std::shared_ptr<const turtlesim::action::RotateAbsolute::Goal>)
std::shared_ptr<const turtlesim_msgs::action::RotateAbsolute::Goal>)
{
// Accept all goals
// Accept all goals
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
},
[](const std::shared_ptr<RotateAbsoluteGoalHandle>)
{
// Accept all cancel requests
// Accept all cancel requests
return rclcpp_action::CancelResponse::ACCEPT;
},
std::bind(&Turtle::rotateAbsoluteAcceptCallback, this, std::placeholders::_1));
},
std::bind(&Turtle::rotateAbsoluteAcceptCallback, this, std::placeholders::_1));

last_command_time_ = nh_->now();

Expand Down Expand Up @@ -137,8 +138,8 @@ void Turtle::velocityCallback(const geometry_msgs::msg::Twist::ConstSharedPtr ve
}

bool Turtle::setPenCallback(
const turtlesim::srv::SetPen::Request::SharedPtr req,
turtlesim::srv::SetPen::Response::SharedPtr)
const turtlesim_msgs::srv::SetPen::Request::SharedPtr req,
turtlesim_msgs::srv::SetPen::Response::SharedPtr)
{
pen_on_ = !req->off;
if (req->off) {
Expand All @@ -155,16 +156,16 @@ bool Turtle::setPenCallback(
}

bool Turtle::teleportRelativeCallback(
const turtlesim::srv::TeleportRelative::Request::SharedPtr req,
turtlesim::srv::TeleportRelative::Response::SharedPtr)
const turtlesim_msgs::srv::TeleportRelative::Request::SharedPtr req,
turtlesim_msgs::srv::TeleportRelative::Response::SharedPtr)
{
teleport_requests_.push_back(TeleportRequest(0, 0, req->angular, req->linear, true));
return true;
}

bool Turtle::teleportAbsoluteCallback(
const turtlesim::srv::TeleportAbsolute::Request::SharedPtr req,
turtlesim::srv::TeleportAbsolute::Response::SharedPtr)
const turtlesim_msgs::srv::TeleportAbsolute::Request::SharedPtr req,
turtlesim_msgs::srv::TeleportAbsolute::Response::SharedPtr)
{
teleport_requests_.push_back(TeleportRequest(req->x, req->y, req->theta, 0, false));
return true;
Expand All @@ -181,8 +182,8 @@ void Turtle::rotateAbsoluteAcceptCallback(
rotate_absolute_goal_handle_->abort(rotate_absolute_result_);
}
rotate_absolute_goal_handle_ = goal_handle;
rotate_absolute_feedback_.reset(new turtlesim::action::RotateAbsolute::Feedback);
rotate_absolute_result_.reset(new turtlesim::action::RotateAbsolute::Result);
rotate_absolute_feedback_.reset(new turtlesim_msgs::action::RotateAbsolute::Feedback);
rotate_absolute_result_.reset(new turtlesim_msgs::action::RotateAbsolute::Result);
rotate_absolute_start_orient_ = orient_;
}

Expand Down Expand Up @@ -300,7 +301,7 @@ bool Turtle::update(
static_cast<double>(canvas_height)));

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

// Figure out (and publish) the color underneath the turtle
{
auto color = std::make_unique<turtlesim::msg::Color>();
auto color = std::make_unique<turtlesim_msgs::msg::Color>();
QRgb pixel = path_image.pixel((pos_ * meter_).toPoint());
color->r = qRed(pixel);
color->g = qGreen(pixel);
Expand Down
Loading