Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Problem with malloc(): memory corruption #95

Open
amadoantonini opened this issue Jun 18, 2015 · 4 comments
Open

Problem with malloc(): memory corruption #95

amadoantonini opened this issue Jun 18, 2015 · 4 comments

Comments

@amadoantonini
Copy link

Hello,
I'm having this issue when I run SVO in ROS, both with a recorded bag file and with a live camera.
The error message I'm getting is the following:

*** Error in `/home/amado/catkin_ws/devel/lib/svo_ros/vo': malloc(): memory corruption: 0x00000000018d96f0 ***

and then it crashes.
In the case of the test file, the error occurs when I start playing the bag.
I have tried it in 3 different computers (with the bag file recorded in one of them) and all give the same error. I have successfully run SVO with the given test file (airground_rig_xxxxx) so the only things I'm changing that result in the error are: the calibration (.yaml) file and the bag file of course. For the calibration file I'm using the pinhole model (replacing the atan model that the given test file uses).

Please, any ideas on where the problem is/how to fix it?
I'll be happy to give more details if needed.

@amadoantonini
Copy link
Author

It looks like there's an issue with the image size. The camera I'm using records at 648 x 488 pixels.
I found that if I resize the video to 640 x 480 then it runs fine.
Any suggestions on what might go wrong with 648 x 488?

@theclakuh
Copy link

Hi,

I have the same problem. The parameters of the svo_ros node are set to the camera resolution.

PARAMETERS

  • /rosdistro: indigo
  • /rosversion: 1.11.16
  • /svo/cam_cx: 328.046456
  • /svo/cam_cy: 226.471844
  • /svo/cam_d0: -0.363501
  • /svo/cam_d1: 0.165011
  • /svo/cam_d2: 0.000571
  • /svo/cam_d3: -0.000577
  • /svo/cam_fx: 588.481298
  • /svo/cam_fy: 587.819899
  • /svo/cam_height: 484
  • /svo/cam_model: Pinhole
  • /svo/cam_topic: /image_raw
  • /svo/cam_width: 644
  • /svo/grid_size: 30
  • /svo/loba_num_iter: 0
  • /svo/max_n_kfs: 10

Also the camera calibration result says that the image resolution is 644x484 which is the resolution configured in the camera model (camera_pinhole.yaml) file, too:
cam_model: Pinhole cam_width: 644 cam_height: 484 cam_fx: 588.481298 cam_fy: 587.819899 cam_cx: 328.046456 cam_cy: 226.471844 cam_d0: -0.363501 cam_d1: 0.165011 cam_d2: 0.000571 cam_d3: -0.000577

Did I miss to fit any parameters or other configurations?
Could you find any solution to your problem?

Thanks in advance.

@amadoantonini
Copy link
Author

Hi

I actually found a solution to this issue. It was caused when making the image pyramid when the image had an odd number of columns.

I fixed it by modifying the file rpg_vikit/vikit_common/src/vision.cpp
Line 91 previously read:
const int stride = in.step.p[0];
I changed it to:
const int stride = in.step.p[0]/2*2;

Best

On Feb 17, 2016, at 7:03 AM, codierknecht notifications@github.com wrote:

Hi,

I have the same problem. The parameters of the svo_ros node are set to the camera resolution.

PARAMETERS

/rosdistro: indigo
/rosversion: 1.11.16
/svo/cam_cx: 328.046456
/svo/cam_cy: 226.471844
/svo/cam_d0: -0.363501
/svo/cam_d1: 0.165011
/svo/cam_d2: 0.000571
/svo/cam_d3: -0.000577
/svo/cam_fx: 588.481298
/svo/cam_fy: 587.819899
/svo/cam_height: 484
/svo/cam_model: Pinhole
/svo/cam_topic: /image_raw
/svo/cam_width: 644
/svo/grid_size: 30
/svo/loba_num_iter: 0
/svo/max_n_kfs: 10
Also the camera calibration result says that the image resolution is 644x484 which is the resolution configured in the camera model (camera_pinhole.yaml) file, too:
cam_model: Pinhole
cam_width: 644
cam_height: 484
cam_fx: 588.481298
cam_fy: 587.819899
cam_cx: 328.046456
cam_cy: 226.471844
cam_d0: -0.363501
cam_d1: 0.165011
cam_d2: 0.000571
cam_d3: -0.000577

Did I miss to fit any parameters or other configurations?
Could you find any solution to your problem?

Thanks in advance.


Reply to this email directly or view it on GitHub #95 (comment).

@theclakuh
Copy link

I have no idea why, but it works. I hope this is pushed soon. Now I have to find out why there are not enough features found after the initialization of the second keyframe.

If you are on stackoverflow, please copy your answer to my question there so I can mark it as solved.

Thank you.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants