Closed knazneen123 closed 2 years ago
what operating system are you running on?
I am using Distributor ID: Ubuntu Description: Ubuntu 20.04.4 LTS Release: 20.04 Codename: focal
ROS : noetic
OpenCV : 4.5.4
Where does OpenCV 4.5.4 come from? Ubuntu 20.04 ships with OpenCV 4.2. Can you try compiling with OpenCV 4.2?
I built OpenCV 4.5.4 from source in my system as it was latest stable build and all other slam models were working in Ubuntu 20.04 with opencv 4.5.4 only tagslam gives error. Sure as you suggested I will try adding opencv 4.2 and see if it runs or not, thanks for your support!
OK, that explains why I did not get these errors in testing. From the assertion it looks like something pretty fundamental is wrong, like the shape of the input arrays:
[ERROR] [1651135912.026418853]: /tagslam: OpenCV(4.5.4) ../modules/calib3d/src/solvepnp.cpp:771: error: (-215:Assertion
failed) (rsize == Size(1, 3) || rsize == Size(3, 1)) && (tsize == Size(1, 3) || tsize == Size(3, 1)) in function 'solvePnPGeneric'
Can you go into init_pose.cpp and before line 397 (where solvePnP()) is called print out rvec.cols, rvec.rows, tvec.cols, tvec.rows. They should be 3 and 1. Thanks!
Hey, the size of vectors seems correct following is the output
rvec rows : 3; rvec cols : 1; tvec rows : 3; tvec cols : 1
Hmm, then why is it throwing that assertion error? Is it even bombing out in line 397? I don't know of another place that's calling solvePnP(). Is the size of one of the other inputs bad? Also, instead of D0 can you pass in an empty cv::Mat()?
Yes even i don't know exactly which line is causing the error, do you know any other debugging method or how we can use gdb to debug ros program and get the line causing error. Also, i will try the method you suggested and update you on monday, really appreciate your support
There are some ways to catch exceptions in gdb but I usually just put a print statement before and after the offending line.
yes even i do that writing print statements helps alot in debugging but in this case the line of error is unknown and even the file causing the error, do you think it's the init_pose.cc?
That's the only place I found in the whole source tree where an opencv routine related to pnp is called.
Hey, even tried passing D0 as empty and also tried initializing it in another way cv::Mat1d D0(4, 4, 0.0); still same error I also verified the data stored in mat passed in solvePnp function, I am getting these values wp : -0.06 imu : -0.141978 eye : 1 D0 : 0 rvec : 2.19572 tvec : 0.00669117 even these values seems correct
Hey so after removing the default opencv 4.2 which gets installed with ros-noetic by referring this link https://zhuanlan-zhihu-com.translate.goog/p/400316912?_x_tr_sl=zh-CN&_x_tr_tl=en&_x_tr_hl=en&_x_tr_pto=sc and reinstalling opencv 4..5.4 and setting ldconfig path for this version it is now working
Hey,
I am trying to run the below command to test tagslam but its giving me this error, is it related to OpenCv version as I am using 4.5.4
roslaunch tagslam tagslam.launch bag:=
rospack find tagslam
/example/example.bag... logging to /home/nazneen/.ros/log/d404ce2a-c6ce-11ec-ab04-453ce003fbd4/roslaunch-nazneen-miko-34089.log Checking log directory for disk usage. This may take a while. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://192.168.29.51:40993/
SUMMARY
CLEAR PARAMETERS
PARAMETERS
NODES / tagslam (tagslam/tagslam_node)
ROS_MASTER_URI=http://192.168.29.51:11311
process[tagslam-1]: started with pid [34104] [ INFO] [1651135910.779493611]: optimizer mode: fast [ INFO] [1651135910.780733171]: added body grasp_lab with 1 tags [ INFO] [1651135910.780763812]: added body rig with 0 tags [ INFO] [1651135910.782309041]: found 1 cameras [ INFO] [1651135910.782848906]: camera cam0 has known pose! [ INFO] [1651135910.782911460]: no distance measurements found! [ INFO] [1651135910.782944772]: no coordinate measurements found! [ INFO] [1651135910.782971388]: no plane measurements found! [ INFO] [1651135912.013876392]: reading from bag: /home/nazneen/rosProjects/tagslam_root/src/tagslam/example/example.bag [ INFO] [1651135912.014693582]: number of tag topics: 1 [ INFO] [1651135912.014774603]: number of image topics: 0 [ INFO] [1651135912.014827431]: number of odom topics: 0 [ INFO] [1651135912.018673844]: frame 0 [1558997717.191335649] cam: cam0 sees tags: [ INFO] [1651135912.018875830]: frame 1 [1558997717.689639795] cam: cam0 sees tags: [ INFO] [1651135912.019256175]: frame 2 [1558997718.187753357] cam: cam0 sees tags: [ INFO] [1651135912.019372318]: frame 3 [1558997718.685203212] cam: cam0 sees tags: [ INFO] [1651135912.020334872]: new tag 3 attached to grasp_lab [ INFO] [1651135912.020691273]: frame 4 [1558997719.179919103] cam: cam0 sees tags: 3 [ INFO] [1651135912.021231730]: [1558997719.179919103] subgraph err: 0, subgraph sum: 0 [ INFO] [1651135912.021342170]: graph after update: opt fac: 4 unopt fac: 1 opt vals: 4 unopt vals: 2 [ INFO] [1651135912.021724933]: frame 5 [1558997719.676376045] cam: cam0 sees tags: 3 0 [ERROR] [1651135912.026418853]: /tagslam: OpenCV(4.5.4) ../modules/calib3d/src/solvepnp.cpp:771: error: (-215:Assertion failed) (rsize == Size(1, 3) || rsize == Size(3, 1)) && (tsize == Size(1, 3) || tsize == Size(3, 1)) in function 'solvePnPGeneric'
[tagslam-1] process has died [pid 34104, exit code 255, cmd /home/nazneen/rosProjects/tagslam_root/devel/lib/tagslam/tagslam_node name:=tagslam log:=/home/nazneen/.ros/log/d404ce2a-c6ce-11ec-ab04-453ce003fbd4/tagslam-1.log]. log file: /home/nazneen/.ros/log/d404ce2a-c6ce-11ec-ab04-453ce003fbd4/tagslam-1*.log all processes on machine have died, roslaunch will exit shutting down processing monitor... ... shutting down processing monitor complete