RMonica / elastic_bridge

ROS wrapper for ElasticFusion
10 stars 4 forks source link

external sensor pose tracking #2

Open Quitino opened 3 years ago

Quitino commented 3 years ago

Thank you very much for your work, I want to use the external tracking data to realize the rotation and translation of the point cloud. The odometer uses vins-mono, but I tried topic '/vins_estimator/camera_pose'、'\vins_estimator/odometry' changed in ‘elastic_node.cpp’:

m_ nh.param <std::string>("TF_ INPUT_ WORLD_ FRAME", m_ input_ world_ frame, "/world");
m_ nh.param <std::string>("TF_ INPUT_ CAMERA_ FRAME", m_ input_ camera_ frame, "/vins_ estimator/camera_ pose");

and changed in launch:

<!-- param name="PERIODIC_ WORLD_ PUBLICATION" type="int" value="90" / -->
<param name="PERIODIC_ WORLD_ PUBLICATION" type="int" value="60" />
<param name="TF_ POSE_ ALWAYS" type="bool" value="true" />
<param name="TF_ POSE_ FIRST" type="bool" value="false" />

Error information:

"[ERROR] [1617283912.216585338]: elastic_ bridge: could not read input TF: "vins_ estimator/camera_ pose" passed to lookupTransform argument target_ frame does not exist.

How can I correctly use external pose information for point cloud stitching? Thank you very much and look forward to your reply.

RMonica commented 3 years ago

I don't know much about vins-mono, but are you sure that /vins_estimator/camera_pose is a TF frame? It looks like a ROS topic to me.

You may check if the TF frame exists using tf_echo, for example:

rosrun tf tf_echo /world /vins_ estimator/camera_ pose

If the TF frame does not exists, you should create it. For example, you can create a small ROS node which receives messages from /vins_estimator/camera_pose and publishes them using a tf::TransformBroadcaster.