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

processing image outside callback

asked 2013-10-12 03:09:12 -0500

espee gravatar image

updated 2013-10-12 17:51:41 -0500

Hello,

I am trying to process image outside callback. Its a Harris detector using opencv but I am running into segmentation fault error.

my code is as follows;

namespace enc = sensor_msgs::image_encodings;
class harris_node
{
  protected:
  //   image_transport::ImageTransport it_;
image_transport::Subscriber sub_;
image_transport::Publisher pub_;
ros::NodeHandle nh_;
ros::NodeHandle nhPrivate_;

sensor_msgs::ImageConstPtr imageIn_;
cv_bridge::CvImagePtr image_in;   //pointer to input image
cv_bridge::CvImagePtr image_out;  //for ros msg conversion 
cv::Mat cvImage_in;       //for processing, input at each step
cv::Mat cvImage_out;      //for processing, output at each step
int thresh;
int max_thresh;
int blockSize;
int apertureSize;
double k;


 public:
 harris_node(ros::NodeHandle& nh, ros::NodeHandle& nhPrivate):nh_(nh), nhPrivate_(nhPrivate), thresh(200), max_thresh(255), blockSize(2), apertureSize(3), k(0.04)
 {
    image_transport::ImageTransport it_(nh_);
    sub_ = it_.subscribe("front_cam/camera/image", 100, &harris_node::imageCb, this);
    pub_=it_.advertise("front_cam/camera/image_processed", 1);
 }

 void imageCb(const sensor_msgs::ImageConstPtr& image)
 {  

    try                         
    {
        imageIn_ = image;        
    }
    catch (cv_bridge::Exception& e)
    {
        ROS_ERROR("Conversion error: %s", e.what());
        return;
    }
 }

 void harris_detector()
 {
    image_in = cv_bridge::toCvCopy(imageIn_, enc::BGR8);
    cvImage_in = image_in->image;       
    cvtColor(cvImage_in, cvImage_out, CV_8UC1); 
    cvImage_in = cvImage_out;
    cornerHarris(cvImage_in, cvImage_out, blockSize, apertureSize, k, cv::BORDER_DEFAULT);    //Harris detector
    cvImage_in = cvImage_out;
    normalize(cvImage_in, cvImage_out, 0, 255, cv::NORM_MINMAX, CV_32FC1, cv::Mat());       //normalize
    cvImage_in = cvImage_out;
    convertScaleAbs (cvImage_in, cvImage_out); //scaled


    //Drawing circles around corner

    for(int j=0; j<cvImage_out.rows ; j++)
    {
        for(int i = 0; i<cvImage_out.cols; i++)
        {
            if((int) cvImage_out.at<float>(j,i) > thresh)
            {
                circle(cvImage_out, cv::Point(j,i),5,cv::Scalar(0),2,8,0);
            }
        }

    }
 }


 void spin()
 {
    ros::Rate rate(30);
    while (ros::ok())
    {
        spinOnce();
        rate.sleep();
    }
 }

 virtual void spinOnce()
 {
    harris_detector();
    spin();
 }
 };

 class harris_node_with_gui:public harris_node
 {
public:
harris_node_with_gui(ros::NodeHandle& nh, ros::NodeHandle& nhPrivate):   harris_node(nh, nhPrivate){}
void spinOnce()
{
    harris_node::spinOnce();
    cv::imshow("inputImage", cvImage_in);
    cv::imshow("Corners", cvImage_out); 
}
   };




 int main(int argc, char** argv)
 {
 ros::init(argc, argv, "image_processor"); 
 ros::NodeHandle nh;
 ros::NodeHandle nhPrivate("~");

 harris_node* node = 0;
 node = new harris_node_with_gui (nh, nhPrivate);
 node->spinOnce();
 }

gdb debugging shows Program received signal SIGSEGV, Segmentation fault.

on backtrace I get:

#0  0xb7fdd424 in __kernel_vsyscall ()
#1  0xb74b81df in raise () from /lib/i386-linux-gnu/libc.so.6
#2  0xb74bb825 in abort () from /lib/i386-linux-gnu/libc.so.6
#3  0xb74b1085 in ?? () from /lib/i386-linux-gnu/libc.so.6
#4  0xb74b1137 in __assert_fail () from /lib/i386-linux-gnu/libc.so.6
#5  0xb7f74555 in    cv_bridge::toCvCopy(boost::shared_ptr<sensor_msgs::Image_<std::allocator<void> > const> const&, std::string const&) ()
 from /opt/ros/hydro/lib/libcv_bridge.so
#6  0x080532bb in harris_node::harris_detector() ()
#7  0x0805372f in harris_node::spinOnce() ()
#8  0x08053778 in harris_node_with_gui::spinOnce() ()
#9  0x080536e1 in harris_node::spin() ()
#10 0x08050f2a in main ()

Any help is appreciated..


Edited

After I swap i and j the backtrace output is still the same but I get another error:

image_processing: /usr/include/boost/smart_ptr/shared_ptr.hpp:412:    boost::shared_ptr<T>::reference boost::shared_ptr<T>::operator*() const [with T = const    sensor_msgs::Image_<std::allocator<void> >, boost::shared_ptr<T>::reference = const   sensor_msgs::Image_<std::allocator<void> >&]: Assertion `px != 0' failed.

So I think I have initialized the pointers in the class to NULL value and this has ... (more)

edit retag flag offensive close merge delete

Comments

Please check where the segfault happens with gdb's back trace.

dornhege gravatar image dornhege  ( 2013-10-12 03:13:15 -0500 )edit

did you ever resolve your problem?

215 gravatar image 215  ( 2016-03-21 06:28:35 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2013-10-12 04:15:52 -0500

kalectro gravatar image

updated 2013-10-12 04:41:03 -0500

I would assume your error lies here

if((int) cvImage_out.at<float>(j,i) > thresh)
{
  circle(cvImage_out, cv::Point(i,j),5,cv::Scalar(0),2,8,0);
}

I did not read the full code but a quick look at it lets me guess that you access the image outside its boundaries. It looks like you need to swap i and j

Edit: Have a look at http://wiki.ros.org/cv_bridge/Tutorials/UsingCvBridgeToConvertBetweenROSImagesAndOpenCVImages for the right way to transform sensor_msgs::image to cvimage It looks like you just assign a const ptr from the message to a const ptr from a cvimage. This is most certainly not correct. Try something like this:

cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
edit flag offensive delete link more

Comments

Thanks I did the correction..but no solutions yet.

espee gravatar image espee  ( 2013-10-12 04:29:24 -0500 )edit

I did the following where imageIn_ is ImageConstPtr: image_in = cv_bridge::toCvCopy(imageIn_, enc::BGR8); Actually I followed the same tutorial.

espee gravatar image espee  ( 2013-10-12 04:52:46 -0500 )edit
0

answered 2013-10-12 16:28:33 -0500

Try adding this to you constructor:

imageIn_.reset (new sensor_msgs::Image);
edit flag offensive delete link more

Comments

that doesnt solve either.

espee gravatar image espee  ( 2013-10-12 17:50:34 -0500 )edit

I think the pointers in the object are initialized to NULL because of default constructor.. any ways to solve this issue?

espee gravatar image espee  ( 2013-10-12 17:52:40 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-10-12 03:09:12 -0500

Seen: 585 times

Last updated: Oct 12 '13