Hi,
this discussion raised my curiosity, so I created a small test program
to evaluate the advantage of using shared memory. The program is quite
simple: on one end a publisher is creating an image of some size, and
publishing it with a timestamp given by ros::Time::now(), on the other
end, a receiver is receiving the image, and recording the difference
between ros::Time::now() and the image timestamp.
I made this test for 1000 images, from 640x480x1, 640x480x3,
1500x1000x3, 3000x2000x3. The results are summarised in the attached pdf.
I also attach the test file so that someone can point out if something
is wrong in my test.
The bottom line is: for big object, shared memory transfer reduces
significantly the delivery delay.
I hope that helps.
Best
Josh Faust wrote:
>
>
> Shared memory transport is a common feature request. There's a
> long discussion of the issues at
> http://ros-users.122217.n3.nabble.com/Shared-memory-transport-using-C-in-ROS-td414682.html
> <http://ros-users.122217.n3.nabble.com/Shared-memory-transport-using-C-in-ROS-td414682.html%20>that
> should get you caught up.
>
> This links says me "Not found"...
>
>
> The first link works:
> http://ros-users.122217.n3.nabble.com/Shared-memory-transport-using-C-in-ROS-td414682.html
>
>
>
> Short version:
> * We haven't found shared memory transport of serialized data
> to be a significant improvement versus TCP over loopback, but
> are interested in evidence to the contrary.
> * Storing the message objects themselves in shared memory
> could be a win, but gets very complicated to implement.
> * We've focused on optimizing intra-process (no-copy) message
> passing and are developing the nodelet
> <http://www.ros.org/wiki/nodelet> infrastructure; big point
> clouds are the motivating use case.
>
> Similarly, I don't observe a significant performance gain on my
> laptop either. From htop output, I could make myself believe that
> 5-10% perf gain are possible, but this is clearly marginal.
> However, it might be different with more active processes, more
> cpus, less cpus, more/less rams, bigger use of the network stack,
> different hardware (gumstix?), so I would tend to put this
> image_transport_plugins in the common pool, just in case.
>
>
> Again, without data showing it's faster (and perhaps a testsuite so
> that others can test on different configurations), it's not
> worthwhile. Nodelets will be orders of magnitude faster for any but
> the smallest images (where they will still be faster).
>
> You're welcome to put this in your own repo and share it with the
> community. I would suggest fixing some of the boundary cases first
> though.
>
> Josh
> ------------------------------------------------------------------------
>
> _______________________________________________
> ros-users mailing list
> ros-users@code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
--
Dr. Cedric Pradalier
http://www.asl.ethz.ch/people/cedricp
#include <ros/ros.h>
#include "sensor_msgs/Image.h"
#include <image_transport/image_transport.h>
#include "cv_bridge/CvBridge.h"
#include <opencv/cv.h>
#include <opencv/highgui.h>
class ImageConverter {
protected:
ros::NodeHandle n_;
image_transport::ImageTransport it_;
sensor_msgs::CvBridge bridge_;
image_transport::Publisher image_pub_;
IplImage *cv_image;
sensor_msgs::Image image;
public:
ImageConverter(ros::NodeHandle &n) : n_(n), it_(n_) {
image_pub_ = it_.advertise("image_source",1);
// cv_image = cvCreateImage(cvSize(640,480),8,1);
// image = *(bridge_.cvToImgMsg(cv_image, "mono8"));
// cv_image = cvCreateImage(cvSize(640,480),8,3);
cv_image = cvCreateImage(cvSize(1500,1000),8,3);
// cv_image = cvCreateImage(cvSize(3000,2000),8,3);
image = *(bridge_.cvToImgMsg(cv_image, "bgr8"));
}
~ImageConverter()
{
}
int imageCapture()
{
ros::Rate loop_rate(30);
while (ros::ok())
{
try
{
image.header.stamp = ros::Time::now();
image_pub_.publish(image);
ROS_DEBUG("Published image at %f",image.header.stamp.toSec());
}
catch (sensor_msgs::CvBridgeException error)
{
ROS_ERROR("error");
}
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
};
int main(int argc, char** argv)
{
ros::init(argc, argv, "test_publisher");
ros::NodeHandle n;
ImageConverter ic(n);
ic.imageCapture();
return 0;
}
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <ros/ros.h>
#include <cv_bridge/CvBridge.h>
#include <image_transport/image_transport.h>
#include <boost/format.hpp>
std::string transport;
unsigned int npoints = 0;
FILE * fp=NULL;
void callback(const sensor_msgs::ImageConstPtr& image)
{
double tnow = ros::Time::now().toSec();
double tstamp = image->header.stamp.toSec();
if (!fp) {
char fname[512];
sprintf(fname,"received_%d_%s_%dx%dx%s.txt",
getpid(),transport.c_str(),image->width,image->height,
image->encoding.c_str());
ROS_INFO("Saving data in %s",fname);
fp = fopen(fname,"w");
}
fprintf(fp,"%d %f %f %f\n",npoints,tnow,tstamp,tnow-tstamp);
npoints ++;
ROS_INFO("%d: Image received at %f, delay %f",
getpid(),tstamp,tnow-tstamp);
if (npoints > 1000) {
fclose(fp);
ros::shutdown();
}
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "test_receiver", ros::init_options::AnonymousName);
ros::NodeHandle nh;
image_transport::ImageTransport it(nh);
transport = std::string((argc > 1) ? argv[1] : "raw");
image_transport::Subscriber sub = it.subscribe("image_source", 1, callback,
transport);
ROS_INFO("test_receiver started");
ros::spin();
}