unmannedlab / RELLIS-3D

RELLIS-3D: A Multi-modal Dataset for Off-Road Robotics
https://unmannedlab.github.io/research/RELLIS-3D
285 stars 49 forks source link

Stereo Camera - nerian/right/camera_info/P matrix Tx value #12

Open Prasheel24 opened 3 years ago

Prasheel24 commented 3 years ago

Hello Team,

First of all, I would like to appreciate your work on the Data set! Really useful for the tasks that we want to do.

However, I have failed trying to use the Full Stack Merged (00000_20210224.zip) with a ROS pkg called RTABMAP. My task is to develop an occupancy grid from the outdoor scenario which your data provides. In RTABMAP, I am following this tutorial -Stereo Outdoor Mapping which works well on their dataset. I believe the issue might be that the nerian left and right camera are not calibrated well.

Following the tutorial(Stereo Calibration), the P matrix elements for the left and right cameras should be something like - left/camera_info/P : [487.608731712861, 0.0, 318.1162109375, 0.0, 0.0, 487.608731712861, 249.44425201416, 0.0, 0.0, 0.0, 1.0, 0.0] right/camera_info/P : [487.608731712861, 0.0, 318.1162109375, -58.3626989865376, 0.0, 487.608731712861, 249.44425201416, 0.0, 0.0, 0.0, 1.0, 0.0] Because, RTABMAP assumes a horizontal left/right stereo setup where the Tx (or P(0,3)) is negative in the right camera info msg, i.e the stereo baseline (0.000000) should be positive (baseline=-Tx/fx).

But from the Full Stack merged data, I get the following /nerian/left/camera_info/P: [635.618713, 0.0, 414.684479, 0.0, 0.0, 635.954285, 292.338189, 0.0, 0.0, 0.0, 1.0, 0.0] /nerian/right/camera_info/P: [639.706055, 0.0, 388.850254, 0.0, 0.0, 641.632874, 290.169922, 0.0, 0.0, 0.0, 1.0, 0.0] I have read their forums where people faced a similar issue but as far as I can see, they got it resolved as the right camera Tx value was negative itself and had to perform some minor changes.

I believe this might be the issue but please do enlighten me for my exposure to working with cameras is limited to only RGB-D. I am currently looking at possible workarounds that I can do but if you could please guide me in some way possible that would be great!

Looking forward to hearing from you guys.!

maskjp commented 3 years ago

Hi, @Prasheel24,

Thank you for your interest in RELLIS-3D. The camera_info/P value in the rosbag is the calibration results in a mono way. You need the joint calibration results. Please find the calibration results through this link

Hope this helps!

maskjp commented 3 years ago

Hi, Prasheel,

We don't have a separate bag file, but we are trying to find a way that allows people to use the calibration results with the rosbag. But I don't know when we will be able to make it. I will appreciate that if you can contribute your solution. Thanks!


发件人: Prasheel Renkuntla @.> 发送时间: 2021年7月14日 19:45 收件人: unmannedlab/RELLIS-3D @.> 抄送: maskjp @.>; Mention @.> 主题: Re: [unmannedlab/RELLIS-3D] Stereo Camera - nerian/right/camera_info/P matrix Tx value (#12)

Thanks @maskjphttps://github.com/maskjp! Do you have a separate bag file in an outdoor scenario with these camera parameters published. I am not quite sure if publishing them on a separate topic would not conflict with the timestamps. As far as I have seen, RTABMAP does not let these parameters set in a launch file but instead subscribes onto a topic to be consistent with timestamps. I am looking for workarounds and will keep you posted. But please do let me know if you come across such rosbags.

― You are receiving this because you were mentioned. Reply to this email directly, view it on GitHubhttps://github.com/unmannedlab/RELLIS-3D/issues/12#issuecomment-880160982, or unsubscribehttps://github.com/notifications/unsubscribe-auth/ACW7NVBOOEJWT5CIN7LB6XLTXXSLZANCNFSM5AKALTJQ.

Prasheel24 commented 3 years ago

Thank you. I republished these parameters from a yaml file onto a new topic (hoping only the D,K,R,P were different).

Now I am facing another issue though which I have posted on the rtabmap forum. Hoping to get some help from there.

But, please do let me know if my consideration of the new calibrated params is correct, i.e, only these are republished from each of the cameras- M, D, R, P. This is my yaml file

image_height: 592
frame_id: nerian_left
M1: [6.5446097578519868e+02, 0., 4.0838789584433096e+02, 0., 6.5406762994100598e+02, 2.9848072034310803e+02, 0., 0., 1.]
D1: [-6.5815841014726942e-02, 1.0923061909816000e-01, 3.1579177506356319e-04, 9.8548771229215099e-04, -4.7917064148919955e-02]
R1: [9.9999925375956933e-01, -1.2212287491046930e-03, -3.2873192220899390e-05, 1.2211933552632847e-03, 9.9999869678944830e-01, -1.0559858872126445e-03, 3.4162749704327199e-05, 1.0559449546693562e-03, 9.9999944190642387e-01]
P1: [6.4520563312293916e+02, 0., 3.9747498321533203e+02, 0., 0., 6.4520563312293916e+02, 2.9611025238037109e+02, 0., 0., 0., 1., 0.]
Q: [1., 0., 0., -3.9747498321533203e+02, 0., 1., 0., -2.9611025238037109e+02, 0., 0., 0., 6.4520563312293916e+02, 0., 0., 4.0011830826006447e+00, 0.]
T: [-2.4991953054342320e-01, -2.0922712224442989e-04, -1.7970925913971287e-03]
R: [9.9997177418288619e-01, -2.0735360018986067e-03, -7.2215847277191563e-03, 2.0583114620939757e-03, 9.9999564506800664e-01, -2.1149938407033458e-03, 7.2259387940812768e-03, 2.1000698726544482e-03, 9.9997168735673414e-01]

This is my publisher-

import rospy
import yaml
from sensor_msgs.msg import CameraInfo
from std_msgs.msg import Header
from sensor_msgs.msg import RegionOfInterest

VERBOSE=False

class left_info:

    def __init__(self):
        '''Initialize ros publisher, ros subscriber'''
        # topic where we publish
        self.left_pub = rospy.Publisher("nerian_left_info_new", CameraInfo, queue_size=10)
        # self.bridge = CvBridge()

        # subscribed Topic
        self.left_sub = rospy.Subscriber("nerian/left/camera_info",
            CameraInfo, self.callback,  queue_size = 10)
        if VERBOSE :
            print "subscribed to /nerian/left/camera_info"

    def callback(self, ros_data):
        '''Callback function of subscribed topic. 
        Here images get converted and features detected'''
        if VERBOSE :
            print 'received image from "%s"' % ros_data.header.frame_id

        calib_data = yaml.load(self.yaml_data, Loader=yaml.FullLoader)
        camera_info_msg = CameraInfo()
        # head = Header()
        # roint = RegionOfInterest()
        # width = calib_data["image_width"]
        # height = calib_data["image_height"]
        # frame_id = calib_data["frame_id"]    

        camera_info_msg.header = ros_data.header
        camera_info_msg.height = ros_data.height
        camera_info_msg.width = ros_data.width
        camera_info_msg.distortion_model = ros_data.distortion_model
        camera_info_msg.K = calib_data["M1"]
        camera_info_msg.D = calib_data["D1"]
        camera_info_msg.R = calib_data["R1"]
        camera_info_msg.P = calib_data["P1"]
        camera_info_msg.binning_x = ros_data.binning_x
        camera_info_msg.binning_y = ros_data.binning_y
        camera_info_msg.roi = ros_data.roi

        #### Create CompressedIamge ####
        # msg = CompressedImage()
        # msg.header.stamp = rospy.Time.now()
        # msg.format = "jpeg"
        # msg.data = np.array(cv2.imencode('.jpg', image_np)[1]).tostring()
        # Publish new image
        self.left_pub.publish(camera_info_msg)

        #self.subscriber.unregister()

if __name__ == '__main__':
    '''Initializes and cleanup ros node'''
    try:
        ri = left_info()
        calib_yaml = rospy.get_param("/nerian_stereo_left")
        ri.yaml_data = calib_yaml

        rospy.init_node('left_info_publisher', anonymous=True)
        rospy.spin()
    except rospy.ROSInterruptException:
        pass

Also, I saw that the header frame_id for topic /nerian/right/camera_info was nerian_left. Is it the parent frame?

Thanks, Prasheel

phil0stine commented 3 years ago

I saw that the header frame_id for topic /nerian/right/camera_info was nerian_left. Is it the parent frame?

This is by convention for stereo cameras, as described here. The P matrix in the right camera's CameraInfo message is defined in reference to the left camera's coordinate frame, hence the frame_id is also nerian_left.

We have also written a small script to that publishes the new CameraInfo messages for a stereo setup; as soon as @maskjp pushes it you can verify that it works the same as yours.

maskjp commented 3 years ago

Hi, @Prasheel24,

I pushed the script that @phil0stine wrote here. Please take a look at it.

You can run the following command to test the script and use rviz or stereo_view to visualize the results.

roscore
python stereo_camerainfo_pub.py
ROS_NAMESPACE=nerian rosrun stereo_image_proc stereo_image_proc
rosbag play <bag-name> /nerian/left/camera_info:=/nerian/left/camera_info_mono /nerian/right/camera_info:=/nerian/right/camera_info_mono --clock

Best wishes!