Skip to content

Commit

Permalink
Use same QoS for all topic pub/subs (#161)
Browse files Browse the repository at this point in the history
Signed-off-by: Yadunund <[email protected]>
  • Loading branch information
Yadunund authored Jan 15, 2024
1 parent 67633fa commit 78a96ae
Show file tree
Hide file tree
Showing 5 changed files with 60 additions and 6 deletions.
43 changes: 43 additions & 0 deletions turtlesim/include/turtlesim/qos.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// Copyright (c) 2024, Open Source Robotics Foundation, Inc.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef TURTLESIM__QOS_HPP_
#define TURTLESIM__QOS_HPP_

#include <rclcpp/rclcpp.hpp>

namespace turtlesim
{
// Return the QoS used for all publishers/subscriptions.
inline rclcpp::QoS topic_qos()
{
return rclcpp::QoS(rclcpp::KeepLast(7)).reliable();
}
} // namespace turtlesim

#endif // TURTLESIM__QOS_HPP_
3 changes: 2 additions & 1 deletion turtlesim/src/turtle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include "turtlesim/srv/set_pen.hpp"
#include "turtlesim/srv/teleport_absolute.hpp"
#include "turtlesim/srv/teleport_relative.hpp"
#include "turtlesim/qos.hpp"

#define DEFAULT_PEN_R 0xb3
#define DEFAULT_PEN_G 0xb8
Expand Down Expand Up @@ -72,7 +73,7 @@ Turtle::Turtle(
{
pen_.setWidth(3);

rclcpp::QoS qos(rclcpp::KeepLast(7));
const rclcpp::QoS qos = topic_qos();
velocity_sub_ = nh_->create_subscription<geometry_msgs::msg::Twist>(
real_name + "/cmd_vel", qos, std::bind(
&Turtle::velocityCallback, this,
Expand Down
7 changes: 5 additions & 2 deletions turtlesim/tutorials/draw_square.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@
#include <std_srvs/srv/empty.hpp>
#include <turtlesim/msg/pose.hpp>

#include "turtlesim/qos.hpp"

#define PI 3.141592f

class DrawSquare final : public rclcpp::Node
Expand All @@ -44,11 +46,12 @@ class DrawSquare final : public rclcpp::Node
explicit DrawSquare(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
: rclcpp::Node("draw_square", options)
{
twist_pub_ = this->create_publisher<geometry_msgs::msg::Twist>("turtle1/cmd_vel", 1);
const rclcpp::QoS qos = turtlesim::topic_qos();
twist_pub_ = this->create_publisher<geometry_msgs::msg::Twist>("turtle1/cmd_vel", qos);

pose_sub_ =
this->create_subscription<turtlesim::msg::Pose>(
"turtle1/pose", 1, std::bind(&DrawSquare::poseCallback, this, std::placeholders::_1));
"turtle1/pose", qos, std::bind(&DrawSquare::poseCallback, this, std::placeholders::_1));

reset_client_ = this->create_client<std_srvs::srv::Empty>("reset");

Expand Down
7 changes: 5 additions & 2 deletions turtlesim/tutorials/mimic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,18 @@
#include <turtlesim/msg/pose.hpp>
#include <geometry_msgs/msg/twist.hpp>

#include "turtlesim/qos.hpp"

class MimicNode : public rclcpp::Node
{
public:
MimicNode()
: rclcpp::Node("turtle_mimic")
{
twist_pub_ = this->create_publisher<geometry_msgs::msg::Twist>("output/cmd_vel", 1);
const rclcpp::QoS qos = turtlesim::topic_qos();
twist_pub_ = this->create_publisher<geometry_msgs::msg::Twist>("output/cmd_vel", qos);
pose_sub_ = this->create_subscription<turtlesim::msg::Pose>(
"input/pose", 1, std::bind(&MimicNode::poseCallback, this, std::placeholders::_1));
"input/pose", qos, std::bind(&MimicNode::poseCallback, this, std::placeholders::_1));
}

private:
Expand Down
6 changes: 5 additions & 1 deletion turtlesim/tutorials/teleop_turtle_key.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
# include <unistd.h> // NO LINT
#endif

#include "turtlesim/qos.hpp"

static constexpr char KEYCODE_RIGHT = 0x43;
static constexpr char KEYCODE_LEFT = 0x44;
static constexpr char KEYCODE_UP = 0x41;
Expand Down Expand Up @@ -186,7 +188,9 @@ class TeleopTurtle final
nh_->declare_parameter("scale_angular", 2.0);
nh_->declare_parameter("scale_linear", 2.0);

twist_pub_ = nh_->create_publisher<geometry_msgs::msg::Twist>("turtle1/cmd_vel", 1);
twist_pub_ = nh_->create_publisher<geometry_msgs::msg::Twist>(
"turtle1/cmd_vel",
turtlesim::topic_qos());
rotate_absolute_client_ = rclcpp_action::create_client<turtlesim::action::RotateAbsolute>(
nh_,
"turtle1/rotate_absolute");
Expand Down

0 comments on commit 78a96ae

Please sign in to comment.