ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

ERROR: Cannot load message class for...Are your messages built?

asked 2013-03-05 00:15:48 -0500

mateo_7_7 gravatar image

hi, i'm trying to use this simple program to acquire an image from a ROS node (in gray-scale), convert it via cv_bridge (in order to elaborate it through OpenCV), find the middle point of some stains at the image borders and publish this poins on a topic as ROS messages. my code is the following:

#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;


rd_ctrl::proc_data points;

 ros::Publisher data_pub_; 

 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;

 int nu=0,nd=0,nl=0,nr=0;


 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);

 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;
 }

 CvMat frame= cv_ptr->image;
cvSmooth(&frame, &frame, CV_MEDIAN);
cvThreshold(&frame, &frame,200, 255,CV_THRESH_BINARY);

//boundaries scanner

//left side (1)
for(i=0;i<256;i++){

 scalarl = cvGet2D(&frame, 0, i);
if(scalarl.val[0]==0) accl++;
if((scalarl.val[0]==255)&&(accl!=0)){
 l[jl]=(i-1-accl)/2;
 jl++;
 accl=0;
 nl=1;
 }
 if((i=255)&&(accl!=0)){ 
  l[jl]=(255-accl)/2;
 nl=1;
 }

 //right side (3)
 ...
 //up side (4)
 ...

 //down side (2)
 ...

  }
  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_proc");
  ImageConverter ic;

  ros::NodeHandle n;
  data_pub_ = n.advertise<rd_ctrl::proc_data>("/data_im", 1);

  points.u=u;
  points.d=d;
  points.l=l;
  points.r=r;
  data_pub_.publish(points);

  ros::spin();
  return 0;
   }

it compiles and runs but no messages are published (the above error occurs). what could be the problem? thanks for your time!!

edit retag flag offensive close merge delete

Comments

I see you are advertising rd_ctrl::proc_data which I don't know its type. Can you post the entire error in your question? Maybe the problem is in that advertisement.

Miquel Massot gravatar image Miquel Massot  ( 2013-03-05 10:52:00 -0500 )edit

Hey, Did you figure out how to fix this problem.

Asfandyar Ashraf Malik gravatar image Asfandyar Ashraf Malik  ( 2013-07-10 22:42:14 -0500 )edit

Remove the line containing " data_pub_ = n.advertise<rd_ctrl::proc_data>("/data_im", 1); " and try again.

Miquel Massot gravatar image Miquel Massot  ( 2013-07-12 02:44:52 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2013-12-08 20:58:04 -0500

tfoote gravatar image

From a brief look at your code. Your problem is that you are publishing only once immediately. If the topic communications have not been setup yet in the background your single publish will likely get dropped. Especially since you are publishing immediately at startup.

I suggest that you try publishing your data repeatedly like in the talker listener tutorials. http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29

edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-03-05 00:15:48 -0500

Seen: 2,345 times

Last updated: Dec 08 '13