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

Add QoS profile parameter to image bridge #335

Merged
merged 4 commits into from
Feb 8, 2023
Merged
Changes from 2 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
30 changes: 24 additions & 6 deletions ros_gz_image/src/image_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,26 +18,44 @@
#include <string>
#include <vector>

#include <rmw/qos_profiles.h>
#include <gz/transport/Node.hh>
#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <ros_gz_bridge/convert.hpp>

//////////////////////////////////////////////////
/// \brief Bridges one topic
/// \brief Bridges one image topic
class Handler
{
public:
/// \brief Constructor
/// \param[in] _topic Image base topic
/// \param[in] _it_node Pointer to image transport node
/// \param[in] _node Pointer to ROS node
/// \param[in] _gz_node Pointer to Gazebo node
Handler(
const std::string & _topic,
std::shared_ptr<image_transport::ImageTransport> _it_node,
std::shared_ptr<rclcpp::Node> _node,
std::shared_ptr<gz::transport::Node> _gz_node)
{
this->ros_pub = _it_node->advertise(_topic, 1);
// Get QoS profile from parameter
rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
const auto qos_str =
_node->get_parameter("qos").get_parameter_value().get<std::string>();
if (qos_str == "system_default") {
qos_profile = rmw_qos_profile_system_default;
} else if (qos_str == "sensor_data") {
qos_profile = rmw_qos_profile_sensor_data;
} else if (qos_str != "default") {
RCLCPP_ERROR(
_node->get_logger(),
"Invalid QoS profile %s specified. Using default profile.",
qos_str.c_str());
}

// Create publishers and subscribers
this->ros_pub = image_transport::create_publisher(
_node.get(), _topic, qos_profile);

_gz_node->Subscribe(_topic, &Handler::OnImage, this);
}
Expand Down Expand Up @@ -77,7 +95,7 @@ int main(int argc, char * argv[])

// ROS node
auto node_ = rclcpp::Node::make_shared("ros_gz_image");
auto it_node = std::make_shared<image_transport::ImageTransport>(node_);
node_->declare_parameter("qos", "default");

// Gazebo node
auto gz_node = std::make_shared<gz::transport::Node>();
Expand All @@ -91,7 +109,7 @@ int main(int argc, char * argv[])

// Create publishers and subscribers
for (auto topic : args) {
handlers.push_back(std::make_shared<Handler>(topic, it_node, gz_node));
handlers.push_back(std::make_shared<Handler>(topic, node_, gz_node));
}

// Spin ROS and Gz until shutdown
Expand Down