Hello babe1031,
since you haven't mentioned which type of messages are you receiving from the depth sensor, I will cover both of the options.
- messages of type
sensor_msgs::PointCloud2
- messages of type
sensor_msgs::Image
If you have a topic on which point cloud messages are published from the depth sensor, you should just remap octomap_server
cloud topic to yours.
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server">
<remap from="cloud_in" to="<your_point_cloud_topic>"/>
</node>
However, you should also provide a transform between the map
frame and the frame of the point cloud. This is also stated on the octomap_server site:
You need to remap this topic to your
sensor data and provide a tf transform
between the sensor data and the static
map frame.
The thing you need to know about the transform is that it can not be a static one. If you just provide a static transform between the point cloud frame id and the map frame, all of your measurements would integrate in one spot - where you set the static transform to. Therefore, it is important to have an odometry
algorithm that would give you more information about the current position of the robot, and then you could publish a transform based on the current position of the robot.
If you just want to check if all the topics are mapped correctly, you could just give it a try with a static publisher to see what I meant in the previous paragraph.
<node pkg="tf" type="static_transform_publisher" name="tf_pub"
args="0 0 0 0 0 0 1 map camera_color_optical_frame 10"/>
If you are receiving just depth images, luckily, there is depth_image_proc package that enables you to create a point cloud based on a depth image and camera info message.
If you have any further questions, feel free to ask.
Have you tried rtabmap? It also creates a 3D map of the environment. The tutorials for rtabmap are pretty elaborate. Maybe those can help you with octomap also