Skip to content

Commit

Permalink
update plugin subscribers to use all of qos (#827)
Browse files Browse the repository at this point in the history
Co-authored-by: Ben <[email protected]>
Co-authored-by: David Anthony <[email protected]>
  • Loading branch information
3 people authored Aug 29, 2024
1 parent 7946f91 commit df6ae20
Show file tree
Hide file tree
Showing 13 changed files with 24 additions and 24 deletions.
6 changes: 3 additions & 3 deletions mapviz_plugins/src/attitude_indicator_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,15 +121,15 @@ namespace mapviz_plugins
{
odom_sub_ = node_->create_subscription<nav_msgs::msg::Odometry>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&AttitudeIndicatorPlugin::AttitudeCallbackOdom, this, std::placeholders::_1));
imu_sub_ = node_->create_subscription<sensor_msgs::msg::Imu>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&AttitudeIndicatorPlugin::AttitudeCallbackImu, this, std::placeholders::_1));
pose_sub_ = node_->create_subscription<geometry_msgs::msg::Pose>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&AttitudeIndicatorPlugin::AttitudeCallbackPose, this, std::placeholders::_1));

RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str());
Expand Down
2 changes: 1 addition & 1 deletion mapviz_plugins/src/disparity_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ namespace mapviz_plugins
{
disparity_sub_ = node_->create_subscription<stereo_msgs::msg::DisparityImage>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&DisparityPlugin::disparityCallback, this, std::placeholders::_1)
);

Expand Down
10 changes: 5 additions & 5 deletions mapviz_plugins/src/float_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,31 +352,31 @@ namespace mapviz_plugins
{
float32_sub_ = node_->create_subscription<std_msgs::msg::Float32>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const std_msgs::msg::Float32::ConstSharedPtr msg) {
floatCallback(msg->data);
});
float64_sub_ = node_->create_subscription<std_msgs::msg::Float64>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const std_msgs::msg::Float64::ConstSharedPtr msg) {
floatCallback(msg->data);
});
float32_stamped_sub_ = node_->create_subscription<marti_common_msgs::msg::Float32Stamped>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const marti_common_msgs::msg::Float32Stamped::ConstSharedPtr msg) {
floatCallback(msg->value);
});
float64_stamped_sub_ = node_->create_subscription<marti_common_msgs::msg::Float64Stamped>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const marti_common_msgs::msg::Float64Stamped::ConstSharedPtr msg) {
floatCallback(msg->value);
});
velocity_sub_ = node_->create_subscription<marti_sensor_msgs::msg::Velocity>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const marti_sensor_msgs::msg::Velocity::ConstSharedPtr msg) {
floatCallback(msg->velocity);
});
Expand Down
2 changes: 1 addition & 1 deletion mapviz_plugins/src/gps_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ namespace mapviz_plugins
{
gps_sub_ = node_->create_subscription<gps_msgs::msg::GPSFix>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&GpsPlugin::GPSFixCallback, this, std::placeholders::_1));

RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str());
Expand Down
2 changes: 1 addition & 1 deletion mapviz_plugins/src/laserscan_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,7 @@ namespace mapviz_plugins
{
laserscan_sub_ = node_->create_subscription<sensor_msgs::msg::LaserScan>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&LaserScanPlugin::laserScanCallback, this, std::placeholders::_1)
);

Expand Down
4 changes: 2 additions & 2 deletions mapviz_plugins/src/marker_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,14 +137,14 @@ namespace mapviz_plugins
{
marker_sub_ = node_->create_subscription<visualization_msgs::msg::Marker>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&MarkerPlugin::handleMarker, this, std::placeholders::_1));
}
else if (topic_type == "visualization_msgs/msg/MarkerArray")
{
marker_array_sub_ = node_->create_subscription<visualization_msgs::msg::MarkerArray>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&MarkerPlugin::handleMarkerArray, this, std::placeholders::_1));
}
else
Expand Down
2 changes: 1 addition & 1 deletion mapviz_plugins/src/navsat_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ namespace mapviz_plugins
{
navsat_sub_ = node_->create_subscription<sensor_msgs::msg::NavSatFix>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&NavSatPlugin::NavSatFixCallback, this, std::placeholders::_1));

RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str());
Expand Down
4 changes: 2 additions & 2 deletions mapviz_plugins/src/occupancy_grid_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,13 +266,13 @@ namespace mapviz_plugins
{
grid_sub_ = node_->create_subscription<nav_msgs::msg::OccupancyGrid>(
topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&OccupancyGridPlugin::Callback, this, std::placeholders::_1));
if(ui_.checkbox_update->isChecked())
{
update_sub_ = node_->create_subscription<map_msgs::msg::OccupancyGridUpdate>(
topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&OccupancyGridPlugin::CallbackUpdate, this, std::placeholders::_1));
}
RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic.c_str());
Expand Down
2 changes: 1 addition & 1 deletion mapviz_plugins/src/odometry_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ namespace mapviz_plugins
{
odometry_sub_ = node_->create_subscription<nav_msgs::msg::Odometry>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&OdometryPlugin::odometryCallback, this, std::placeholders::_1));

RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str());
Expand Down
2 changes: 1 addition & 1 deletion mapviz_plugins/src/path_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ namespace mapviz_plugins
{
path_sub_ = node_->create_subscription<nav_msgs::msg::Path>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&PathPlugin::pathCallback, this, std::placeholders::_1)
);
RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str());
Expand Down
4 changes: 2 additions & 2 deletions mapviz_plugins/src/route_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ namespace mapviz_plugins
route_sub_ =
node_->create_subscription<marti_nav_msgs::msg::Route>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&RoutePlugin::RouteCallback, this, std::placeholders::_1)
);

Expand Down Expand Up @@ -210,7 +210,7 @@ namespace mapviz_plugins
position_qos_ = qos;
position_sub_ = node_->create_subscription<marti_nav_msgs::msg::RoutePosition>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&RoutePlugin::PositionCallback, this, std::placeholders::_1)
);

Expand Down
4 changes: 2 additions & 2 deletions mapviz_plugins/src/string_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ namespace mapviz_plugins
try
{
string_sub_ = node_->create_subscription<std_msgs::msg::String>(topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const std_msgs::msg::String::ConstSharedPtr str) {
SetText(QString(str->data.c_str()));
});
Expand All @@ -374,7 +374,7 @@ namespace mapviz_plugins
try
{
string_stamped_sub_ = node_->create_subscription<marti_common_msgs::msg::StringStamped>(topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
[this](const marti_common_msgs::msg::StringStamped::ConstSharedPtr str) {
SetText(QString(str->value.c_str()));
});
Expand Down
4 changes: 2 additions & 2 deletions mapviz_plugins/src/textured_marker_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,12 +161,12 @@ void TexturedMarkerPlugin::connectCallback(const std::string& topic, const rmw_q
marker_arr_sub_ =
node_->create_subscription<marti_visualization_msgs::msg::TexturedMarkerArray>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&TexturedMarkerPlugin::MarkerArrayCallback, this, std::placeholders::_1)
);
marker_sub_ = node_->create_subscription<marti_visualization_msgs::msg::TexturedMarker>(
topic_,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
std::bind(&TexturedMarkerPlugin::MarkerCallback, this, std::placeholders::_1)
);

Expand Down

0 comments on commit df6ae20

Please sign in to comment.