There are probably a fair number of ROS users who are learning C++, so the following links may be useful.
For why things are done this way:
https://isocpp.org/wiki/faq/pointers-to-members
For the standard library way to solve the problem (note the differences between C++98 and C++11):
http://www.cplusplus.com/reference/functional/bind/?kw=bind .
This code works, using boost::bind , though others may suggest better ways:
#include <string>
#include <iomanip>
#include <sstream>
#include <fstream>
#include <functional>
// image subscriber
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>
#include <camera_info_manager/camera_info_manager.h>
#include <boost/assign/list_of.hpp>
// opencv2.4
#include <opencv2/core/core.hpp>
#include <opencv2/video/tracking.hpp>
#include <opencv2/imgproc/imgproc.hpp>
using namespace cv;
using namespace std;
typedef const boost::function< void(const sensor_msgs::ImageConstPtr &)> callback;
class myImages {
public:
cv::Mat myMatImage1;
sensor_msgs::ImagePtr myMessagePtr;
void imageCallback(const sensor_msgs::ImageConstPtr& msg );
};
static void wrapper_imageCallback(void* pt2Object, const sensor_msgs::ImageConstPtr& msg);
void myImages::imageCallback(const sensor_msgs::ImageConstPtr& msg )
{
try
{
this->myMatImage1 = cv_bridge::toCvShare(msg, "bgr8")->image;
cv::imshow("view", this->myMatImage1);
cv::waitKey(30);
this->myMessagePtr = cv_bridge::CvImage(std_msgs::Header(), "bgr8", this->myMatImage1).toImageMsg();
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
}
}
static void wrapper_imageCallback(void* pt2Object, const sensor_msgs::ImageConstPtr& msg)
{
myImages* mySelf = (myImages*) pt2Object; // explicitly cast to a pointer to class myImages
mySelf->imageCallback(msg ); // call member
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "flow_vision");
ros::NodeHandle nh;
cv::namedWindow("view");
cv::startWindowThread();
image_transport::ImageTransport it(nh);
myImages MyImagesObj;
callback boundImageCallback = boost::bind(&myImages::imageCallback, &MyImagesObj/*&images*/, _1);
// "_1" is a place holder for the first (and only) parameter of myImages::imageCallback(const sensor_msgs::ImageConstPtr& msg )
/*subscribe (
* const std::string &base_topic,
* uint32_t queue_size,
* const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback,
* const ros::VoidPtr &tracked_object=ros::VoidPtr(),
* const TransportHints &transport_hints=TransportHints())
*/
image_transport::Subscriber sub = it.subscribe("camera/image_raw", 1, boundImageCallback);
image_transport::Publisher pub = it.advertise("out_flow_vision_image_base_topic", 1);
ros::Rate loop_rate(15); //need to increase for video
while (nh.ok()) {
pub.publish(MyImagesObj.myMessagePtr);
ros::spinOnce();
loop_rate.sleep();
}
cv::destroyWindow("view");
}