ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I realised a simple solution here was to fake additional 3D scans and pass these as a point cloud to the MoveIt sensor manager. This allows the octomap occupancy tool to work correctly. This in turn provides collision checking. Working as expected now. Here's my code for anyone else looking to do similar.
void fakeProfile(PointCloud::Ptr cloud)
{
PointCloud add_cloud(*cloud);
for(int j = 0; j < 10; j++)
{
PointCloud temp_cloud(*cloud);
for (int i = 0; i < cloud->points.size(); i++)
{
temp_cloud.points[i].x += double(j);
}
add_cloud += temp_cloud;
}
*cloud += add_cloud;
}
And then using the standard moveit sensors.yaml,
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /extended_profile
max_range: 25.0
point_subsample: 1
padding_offset: 0.1
padding_scale: 1.0
filtered_cloud_topic: filtered_cloud
2 | No.2 Revision |
I realised a simple solution here was to fake additional 3D scans and pass these as a point cloud to the MoveIt sensor manager. This allows the octomap occupancy tool to work correctly. This in turn provides collision checking. Working as expected now. Here's my code for anyone else looking to do similar.
void fakeProfile(PointCloud::Ptr cloud)
{
PointCloud add_cloud(*cloud);
for(int j = 0; j < 10; j++)
{
PointCloud temp_cloud(*cloud);
for (int i = 0; i < cloud->points.size(); i++)
{
temp_cloud.points[i].x += double(j);
}
add_cloud += temp_cloud;
}
*cloud += add_cloud;
}
And then using the standard moveit sensors.yaml,
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /extended_profile
max_range: 25.0
point_subsample: 1
padding_offset: 0.1
padding_scale: 1.0
filtered_cloud_topic: filtered_cloud
Edit: The result is shown below, the nearest points are the real scan, the subsequent ones are the faked scans. In my use case, I can guarantee that the area ahead of the robot is clear so only a vertical scan is needed. The scan used here is of my office walls rather than the real work area, hence the square shape.
And here's the resulting octomap. I need to refine it a little further, the robot does keep finding ways to reach through the gaps in the scans but that's easily resolved.