error: cannot convert ‘cv::Mat’ to ‘const CvArr* - Video from ROS node to OpenCV
hi, i'm trying to receive a video from a ROS node and elaborate the data of the frames and publish some stuff. this is my code (i'm using cv_bridge as suggested by ROS documentation in order to connect ROS to OpenCV):
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <vector>
#include "rd_ctrl/proc_data.h"
#include <cv.h>
using namespace std;
namespace enc = sensor_msgs::image_encodings;
ros::Publisher data_pub_;
ros::NodeHandle n;
rd_ctrl::proc_data data;
static const char WINDOW[] = "Image window";
int i;
int accu=0, accr=0, accd=0,accl=0;
int jd=0, jr=0, jl=0, ju=0, je=0;
CvScalar scalarl,scalaru,scalard,scalarr;
std::vector <int> l,d,r,u;
class ImageConverter
{
ros::NodeHandle nh_;
image_transport::ImageTransport it_;
image_transport::Subscriber image_sub_;
image_transport::Publisher image_pub_;
public:
ImageConverter()
: it_(nh_)
{
image_pub_ = it_.advertise("out", 1);
image_sub_ = it_.subscribe("/vrep/visionSensorData",...
1,&ImageConverter::imageCb,this);
data_pub_ = n.advertise<rd_ctrl::proc_data>("data", 1);
cv::namedWindow(WINDOW);
}
~ImageConverter()
{
cv::destroyWindow(WINDOW);
}
void imageCb(const sensor_msgs::ImageConstPtr& msg)
{
cv_bridge::CvImagePtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
IplImage stub, *frame;
frame = cvGetImage(cv_ptr->image, &stub); //error !!!
cvThreshold(frame, frame,60, 255,CV_THRESH_BINARY);
//function-not important
scalarr = cvGet2D(frame, 255, i);
if(scalarr.val[0]==0) accr++;
if((scalarr.val[0]==255)&&(accr!=0)){
r[jr]=(i-1-accr)/2;
jr++;
accr=0;
}
}
data.r=r;
cv::imshow(WINDOW, cv_ptr->image);
cv::waitKey(3);
image_pub_.publish(cv_ptr->toImageMsg());
}
};
int main(int argc, char** argv)
{
ros::init(argc, argv, "image_converter");
ImageConverter ic;
ros::spin();
return 0;
}
My problems are of 2 types: the first is: the error of the title occurs. why? cvGetImage is not the function adopted to make the conversion between cvMat an IplImage?
the second is that i really don't know how can I extract 2 consecutive frames (for example to find a matching) of video stream acquired
THANK YOU VERY MUCH 4 YOUR HELP!