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

trying to run vslam_system on mono video data

asked 2011-06-19 03:29:12 -0600

rajat gravatar image

updated 2011-06-19 03:29:36 -0600

i am trying to run vslam_system[mono] on my video stream everything seems to go fine, but when the images are published on mono_vslam_node for processing , i get this , i guess the error has something to do Pose-estimator , can anybody provide me the solution to get rid of this error .

process[mono_vslam_node-2]: started with pid [3244]
process[vo_tracks_view-3]: started with pid [3245]
[OK] Loaded RTC, quantization=4 bits
[OK] RTC: overall 24816/9011200 (0.275%) zeros in float leaves
      overall 464923/9011200 (5.159%) zeros in uint8 leaves
[INFO] [1308495150.180861213]: In callback, seq = 12
[INFO] [1308495150.704369647]: In callback, seq = 28

called PoseEstimator2d::estimate for frames 0 and 1
Number of points: 2224, number of matches: 1313
extractPnPData: frame1.pts.size() = 2224
extractPnPData: good points 0
Running SFM

Final error: 74.159839
Dumping SFM returned r
-0.000004 
0.000117 
0.000001 
Dumping SFM return T
-0.458278  
-0.118424 
-3.801803 
The number of epipolar inliers: 1164
1164 points before filtering
612 points left after filtering
sba got 612 points
Node projection matrix
786.36       0 311.642      -0
0 787.335 250.515      -0
0       0       1      -0
Node projection matrix
786.323  -0.00216096      311.735     -1545.17
-0.0284843      787.334      250.518     -1045.65
-0.000117487 -3.89499e-06            1      -3.8018
Added 612 points, 612 tracks
sba.tracks.size = 612
mono_vslam_node:            

/opt/ros/diamondback/stacks/geometry/eigen/include/Eigen/src/Core/Assign.h:510: Derived&  Eigen::DenseBase<Derived>::lazyAssign(const Eigen::DenseBase<OtherDerived>&) [with OtherDerived = Eigen::CwiseUnaryOp<Eigen::internal::scalar_quotient1_op<double>, const Eigen::Block<Eigen::Matrix<double, 3, 1, 0, 3, 1>, -0x00000000000000001, 1, false, true> >, Derived = Eigen::Matrix<double, 3, 1, 0, 3, 1>]: Assertion `rows() == other.rows() && cols() == other.cols()' failed.

[mono_vslam_node-2] process has died [pid 3244, exit code -6].
log files: /home/rajat/.ros/log/46362692-9a80-11e0-b777-0024216e1c6f/mono_vslam_node-2*.log

why is the good points 0 and i can't understand what this line is trying to say

/opt/ros/diamondback/stacks/geometry/eigen/include/Eigen/src/Core/Assign.h:510: Derived& Eigen::DenseBase<derived>::lazyAssign(const Eigen::DenseBase<otherderived>&) [with OtherDerived = Eigen::CwiseUnaryOp<eigen::internal::scalar_quotient1_op<double>, const Eigen::Block<eigen::matrix<double, 3,="" 1,="" 0,="" 3,="" 1="">, -0x00000000000000001, 1, false, true> >, Derived = Eigen::Matrix<double, 3,="" 1,="" 0,="" 3,="" 1="">]: Assertion `rows() == other.rows() && cols() == other.cols()' failed.

and the log file does not have a entry related to this error .

edit retag flag offensive close merge delete

Comments

please point me in right direction .
rajat gravatar image rajat  ( 2011-06-19 23:35:44 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2011-09-02 11:10:15 -0600

Helen gravatar image

vslam is unsupported experimental research code, and more specifically, the monocular pose estimation only works for specific types of camera motions (i.e., will not work on a dataset with unconstrained motion).

Unfortunately, there are no current plans to improve the functionality of monocular vslam. However, patches are welcome.

edit flag offensive delete link more

Comments

Is it still, five years later?

Hendrik Wiese gravatar image Hendrik Wiese  ( 2016-06-27 00:42:05 -0600 )edit
0

answered 2011-08-20 05:16:32 -0600

RobotRocks gravatar image

Hi Rajat, I had the same problem running vslam_system on monocular cameras. I've been searching in the code, and I think that the error is in the function calcNodeErr from the file planarSFM.cpp:

inline double calcNodeErr(sba::Proj& prj, const sba::Node &nd, const sba::Point &pt)
{
  Eigen::Vector3d p1 = nd.w2i * pt;
  prj.err = p1.head(2)/p1(2);
  if (p1(2) <= 0.0)
  {
    prj.err = Vector3d(0.0,0.0,0.0);
    return 0.0;
  }
  //    printf("Projection: %f %f, gt: %f %f, ", prj.err(0), prj.err(1), prj.kp(0), prj.kp(1));
  prj.err -= prj.kp;
  //  printf("dist: %f\n", prj.err.squaredNorm());
  return prj.err.squaredNorm();
}

The second assignment:

prj.err = p1.head(2)/p1(2);

was causing problems. Modify the code with something like this and it will work:

inline double calcNodeErr(sba::Proj& prj, const sba::Node &nd, const sba::Point &pt)
{
  Eigen::Vector3d p1 = nd.w2i * pt;
  //prj.err = p1.head(2)/p1(2); //<--That's the problem
  if (p1(2) <= 0.0)
  {
    prj.err = Vector3d(0.0,0.0,0.0);
    return 0.0;
  }
  //SOLUTION:
  else
     prj.err = Vector3d(p1(0)/p1(2),p1(1)/p1(2),0.0); //this seems to work

  //    printf("Projection: %f %f, gt: %f %f, ", prj.err(0), prj.err(1), prj.kp(0), prj.kp(1));
  prj.err -= prj.kp;
  //  printf("dist: %f\n", prj.err.squaredNorm());
  return prj.err.squaredNorm();
}

I have solved this problem, but the entire code isn't still working. I'm having other problems like:

-The SFM is very slow, it expends a lot of time calulcating the SFM. I think that the problem is the RANSAC algorithm, that needs 10000 iterations to be processed. Somebody have the same problem?

-In every image matching, the result is a bad image match, I think this is caused why the vo finds 0 inliers. I don't know how to solve this. Somebody have any idea?

Thanks

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-06-19 03:29:12 -0600

Seen: 575 times

Last updated: Sep 02 '11