Skip to content

Instantly share code, notes, and snippets.

@caguero
Created July 1, 2024 16:35
Show Gist options
  • Save caguero/e51f1b63b44c2d3a4b250bff7599aa92 to your computer and use it in GitHub Desktop.
Save caguero/e51f1b63b44c2d3a4b250bff7599aa92 to your computer and use it in GitHub Desktop.
ros_gz performance binaries
---
- topic_name: "/camera"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS
lazy: false
# External Gz Transport, external bridge, external ROS node
ros2 run rclcpp_components component_container
ros2 component load /ComponentManager ros_gz_bridge ros_gz_bridge::RosGzBridge -p config_file:=/home/caguero/ros_gz_ws/src/ros_gz/ros_gz_sim_demos/config/camera_bridge.yaml -p name:=bridge
ros2 run ros_gz_bridge ros_subscriber_node
ros2 run ros_gz_bridge publisher_node
# (Gz Transport + bridge), external ROS node
ros2 run rclcpp_components component_container
ros2 component load /ComponentManager ros_gz_bridge ros_gz_bridge::RosGzBridge -p config_file:=/home/caguero/ros_gz_ws/src/ros_gz/ros_gz_sim_demos/config/camera_bridge.yaml -p name:=bridge
ros2 run ros_gz_bridge ros_subscriber_node
ros2 component load /ComponentManager ros_gz_bridge ros_gz_bridge::Publisher
# (Gz Transport + bridge + ROS node)
ros2 run rclcpp_components component_container
ros2 component load /ComponentManager ros_gz_bridge ros_gz_bridge::RosGzBridge -p config_file:=/home/caguero/ros_gz_ws/src/ros_gz/ros_gz_sim_demos/config/camera_bridge.yaml -p name:=bridge -e use_intra_process_comms:=true
ros2 component load /ComponentManager ros_gz_bridge ros_gz_bridge::RosSubscriber -e use_intra_process_comms:=true
ros2 component load /ComponentManager ros_gz_bridge ros_gz_bridge::Publisher -e use_intra_process_comms:=true
import matplotlib.pyplot as plt
# Data for selected series
x_values = list(range(1, 9))
y_values_external_gz_ros = [1212, 1156, 1239, 1349, 1236, 1201, 1149, 1197]
y_values_gz_bridge_external_ros = [1079, 1069, 1022, 1030, 1044, 1035, 1024, 1022]
y_values_gz_bridge_ros = [593, 539, 535, 538, 536, 550, 593, 612]
# Plot
plt.figure(figsize=(12, 8))
# Adding each dataset to the plot
plt.plot(x_values, y_values_external_gz_ros, marker='d', label='External Gz Transport, external bridge, external ROS node', linestyle='-')
plt.plot(x_values, y_values_gz_bridge_external_ros, marker='*', label='(Gz Transport + bridge), external ROS node', linestyle='--')
plt.plot(x_values, y_values_gz_bridge_ros, marker='P', label='(Gz Transport + bridge + ROS node)', linestyle='-.')
# Labels and title
plt.xlabel('Data Point Index')
plt.ylabel('Time (ms.)')
plt.title('Gazebo to ROS performance - 1000 images received (all examples running within a ROS node)')
plt.legend()
plt.grid(True)
plt.tight_layout()
# Show plot
plt.show()
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gz/msgs.hh>
#include <ros_gz_bridge/publisher.hpp>
#include <iostream>
#include <memory>
#include <string>
namespace ros_gz_bridge
{
Publisher::Publisher(const rclcpp::NodeOptions & options)
: rclcpp::Node("publisher", options)
{
gz::transport::Node node;
std::string topic = "/camera";
pub_ = node.Advertise<gz::msgs::Image>(topic);
if (!pub_)
{
std::cerr << "Error advertising topic [" << topic << "]" << std::endl;
return;
}
uint32_t width = 800;
uint32_t height = 600;
msg_.set_width(width);
msg_.set_height(height);
msg_.set_pixel_format_type(gz::msgs::PixelFormatType::R_FLOAT32);
unsigned int num_channels = 1u;
unsigned int octets_per_channel = 4u;
msg_.set_step(msg_.width() * num_channels * octets_per_channel);
msg_.set_data(std::string(msg_.height() * msg_.step(), '1'));
heartbeat_timer_ = this->create_wall_timer(
std::chrono::microseconds(100),
std::bind(&Publisher::spin, this));
}
void Publisher::spin()
{
pub_.Publish(msg_);
}
} // namespace ros_gz_bridge
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(ros_gz_bridge::Publisher)
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gz/msgs.hh>
#include <ros_gz_bridge/ros_publisher.hpp>
#include <iostream>
#include <memory>
#include <string>
namespace ros_gz_bridge
{
RosPublisher::RosPublisher(const rclcpp::NodeOptions & options)
: rclcpp::Node("ros_publisher", options)
{
std::string topic = "/camera";
pub_ = this->create_publisher<sensor_msgs::msg::Image>(topic, 10000);
uint32_t width = 800;
uint32_t height = 600;
msg_.width = width;
msg_.height = height;
msg_.encoding = "32FC1";
unsigned int num_channels = 1u;
unsigned int octets_per_channel = 4u;
msg_.is_bigendian = false;
msg_.step = msg_.width * num_channels * octets_per_channel;
msg_.data.resize(msg_.step * msg_.height, '1');
heartbeat_timer_ = this->create_wall_timer(
std::chrono::microseconds(100),
std::bind(&RosPublisher::spin, this));
}
void RosPublisher::spin()
{
pub_->publish(msg_);
}
} // namespace ros_gz_bridge
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(ros_gz_bridge::RosPublisher)
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gz/msgs.hh>
#include <ros_gz_bridge/ros_subscriber.hpp>
#include <functional>
#include <iostream>
#include <memory>
#include <string>
using std::placeholders::_1;
namespace ros_gz_bridge
{
//////////////////////////////////////////////////
/// \brief Function called each time a topic update is received.
void RosSubscriber::cb(const sensor_msgs::msg::Image &/*_msg*/)
{
static uint32_t counter = 0;
static std::chrono::time_point<std::chrono::high_resolution_clock> beg;
if (counter == 0)
beg = std::chrono::high_resolution_clock::now();
if (counter == 1000)
{
auto end = std::chrono::high_resolution_clock::now();
auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(end - beg);
// Displaying the elapsed time
std::cerr << "Elapsed Time: " << duration.count() << " ms" << std::endl;
counter = 0;
}
else
counter++;
}
RosSubscriber::RosSubscriber(const rclcpp::NodeOptions & options)
: rclcpp::Node("ros_subscriber", options)
{
std::string topic = "/camera";
subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
topic, 10000, std::bind(&RosSubscriber::cb, this, _1));
}
} // namespace ros_gz_bridge
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(ros_gz_bridge::RosSubscriber)
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gz/msgs.hh>
#include <ros_gz_bridge/subscriber.hpp>
#include <iostream>
#include <memory>
#include <string>
namespace ros_gz_bridge
{
//////////////////////////////////////////////////
/// \brief Function called each time a topic update is received.
void Subscriber::cb(const gz::msgs::Image &/*_msg*/)
{
static uint32_t counter = 0;
static std::chrono::time_point<std::chrono::high_resolution_clock> beg;
if (counter == 0)
beg = std::chrono::high_resolution_clock::now();
if (counter == 1000)
{
auto end = std::chrono::high_resolution_clock::now();
auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(end - beg);
// Displaying the elapsed time
std::cerr << "Elapsed Time: " << duration.count() << " ms" << std::endl;
counter = 0;
}
else
counter++;
}
Subscriber::Subscriber(const rclcpp::NodeOptions & options)
: rclcpp::Node("subscriber", options)
{
std::string topic = "/camera";
// Subscribe to a topic by registering a callback.
if (!node_.Subscribe(topic, &Subscriber::cb, this))
{
std::cerr << "Error subscribing to topic [" << topic << "]" << std::endl;
return;
}
}
} // namespace ros_gz_bridge
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(ros_gz_bridge::Subscriber)
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment