Skip to content

Commit

Permalink
add one missing qos() pub
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Apr 8, 2024
1 parent 5dde95a commit 45306ca
Showing 1 changed file with 10 additions and 14 deletions.
24 changes: 10 additions & 14 deletions mrpt_reactivenav2d/src/mrpt_reactivenav2d_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ ReactiveNav2DNode::ReactiveNav2DNode(const rclcpp::NodeOptions& options)
// Init ROS publishers:
// -----------------------
auto qos = rclcpp::SystemDefaultsQoS();

pubCmdVel_ =
this->create_publisher<geometry_msgs::msg::Twist>(pubTopicCmdVel_, qos);

Expand All @@ -142,33 +142,29 @@ ReactiveNav2DNode::ReactiveNav2DNode(const rclcpp::NodeOptions& options)
pubTopicSelectedPtg_, qos);

pubNavEvents_ =
this->create_publisher<std_msgs::msg::String>(pubTopicEvents_, 1);
this->create_publisher<std_msgs::msg::String>(pubTopicEvents_, qos);

// Init ROS subs:
// -----------------------
subOdometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
subTopicOdometry_, qos,
[this](const nav_msgs::msg::Odometry::SharedPtr odom) {
this->on_odometry_received(odom);
});
[this](const nav_msgs::msg::Odometry::SharedPtr odom)
{ this->on_odometry_received(odom); });

subWpSeq_ = this->create_subscription<mrpt_msgs::msg::WaypointSequence>(
subTopicWpSeq_, qos,
[this](const mrpt_msgs::msg::WaypointSequence::SharedPtr msg) {
this->on_waypoint_seq_received(msg);
});
[this](const mrpt_msgs::msg::WaypointSequence::SharedPtr msg)
{ this->on_waypoint_seq_received(msg); });

subNavGoal_ = this->create_subscription<geometry_msgs::msg::PoseStamped>(
subTopicNavGoal_, qos,
[this](const geometry_msgs::msg::PoseStamped::SharedPtr msg) {
this->on_goal_received(msg);
});
[this](const geometry_msgs::msg::PoseStamped::SharedPtr msg)
{ this->on_goal_received(msg); });

subLocalObs_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
subTopicLocalObstacles_, qos,
[this](const sensor_msgs::msg::PointCloud2::SharedPtr msg) {
this->on_local_obstacles(msg);
});
[this](const sensor_msgs::msg::PointCloud2::SharedPtr msg)
{ this->on_local_obstacles(msg); });

// Init tf buffers
// ----------------------------------------------------
Expand Down

0 comments on commit 45306ca

Please sign in to comment.