Hi Mathieu
I want to be able to add landmarks to the graph without detecting anything, and regardless to the frames injected to rtabmap. The idea is something like a message with landmark_id and position. When this message arrives, rtabmap will find the nearest node and attach the landmark id to this node. I tried to follow the logic done when rtabmap detects markers by itself, but seems like I'm missing something. I added landmark with negative id to the node signature's landmarks list, _landmarksIndex and _landmarksSize, and added the landmark itself to _optimizedPoses. Still I don't see the landmark and the link between the node and the landmark in the saved db (I do see landmarks detected by rtabmap). In addition, can you explain the difference between landmarks and labels? I understand label is set to an existing node, so there's just one position (of the node) and landmark is linked to a node and has its own position. Is that correct? How would you represent docking station or any other important place that you want to mark for the robot after mapping? As a landmark or a label? Is there a difference if the robot was in this 'important place' or not? Thanks ahead Keren |
Administrator
|
If SensorData has landmarks, they are added to new created nodes here: https://github.com/introlab/rtabmap/blob/e2f037189a6963296dc3752ee51437d0ea5676dc/corelib/src/Memory.cpp#L5928-L5989 You don't have to add manually to optimizedPoses. yep, landmark can be used for loop closure detection too. After mapping, I would use label, to say from that localization in the map, the docking station can be detected. You can use set_label service with the node id you want. |
Thanks.
In case of adding a label after mapping, I will need to know the node id. I can label the closest node (with node_id=0, right?). But what happens if the closest node is not so close? Can I add a new node? Also, the location is of the node, not the location of the station. Any way to add the station location? Thanks! |
Administrator
|
Hi,
That is a workflow that is not directly natively supported. As a workaround, some saved that kind of data (e.g., zones, places...) in a side file or in a new Table in the same database, linking to node_id they want, and possibly set a transform field. Another node can save/read data from rtabmap database at the same time rtabmap is using it. We should just make sure you don't play in same Tables at the same time. With node_id=0, it will label the latest added node in mapping mode, or the closest node (inside RGBD/LocalRadius of current position) in localization mode. Another workaround is to to call "get_nodes_in_radius" to know which is the closest node of request position, then add a landmark link directly in the database file in Link table with from_id=closest node and to_id= negative unique id. The next time rtabmap reloads the database, the place will be shown as a landmark with corresponding id in the graph. You may have to clear opt_poses and opt_ids in Admin table before relaunching rtabmap to make sure the graph is re-optimized with the new constraint. cheers, Mathieu |
This post was updated on .
Thanks Mathieu.
Additional question. I have QR codes which are located on the floor and detected externally to rtabmap. In mapping mode, whenever the robot goes over a QR code, rtabmap gets a message with the QR id and the robot's absolute position (and I can get more than one message per QR, with different locations as the robot proceeds). I want to set those QR codes as landmarks. Currently whenever I get a QR code message, I add the data to tags_ in the message callback, and it is then processed by landmarksFromROS and added as a landmark. It looks like I'm getting something close to what I need, but not precise. Probably because I get the robot position and not the QR position. Is landmarks the right way to handle this kind of message or is there a better way? If I know ahead the QR codes position, should I add them as markerPrior? |
Administrator
|
Hi,
With tags, usually the detector will report the relative pose of the tag in the sensor frame detecting it. For example in case of a camera, the pose is in general in camera optical frame. rtabmap will take care to transform that pose in base frame of the robot using TF. If you know the exact position of the tag in the building, you can indeed use Marker/Priors parameter (with Optimizer/PriorsIgnored=false to use them). See this post as example. The whole map will be aligned with coordinates of your building frame (in which the global position of the tags are). cheers, Mathieu |
Free forum by Nabble | Edit this page |