ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Noisy points from point cloud causes Moveit! to fail

asked 2022-01-25 08:15:27 -0500

zkytony gravatar image

As shown in the screenshot below, some of the points (green) from the Kinect2 camera point cloud (kinect2/sd/points) are really close to the robot, due to sensor noise.

image description

These points overlap with the gripper, and causes Moveit! to keep output the following message:

Motion plan was found but it seems to be too costly and looking around did not help.

and the plan was in state ABORTED.

When I turn off the OctoMap layer for Moveit!, the arm can execute the motion plan smoothly.

How can I either remove these noisy points or tell Moveit! to not worry about these points?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-01-25 16:41:02 -0500

zkytony gravatar image

updated 2022-01-25 16:45:24 -0500

Never mind. It is actually straightforward to filter out those points, using the PassThrough filter and the StatisticalOutlierRemoval filter from pcl_ros. Pasting my launch file below for a reference in case someone runs into the same issue.

<launch>
  <node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" />

  <node pkg="nodelet" type="nodelet"
        name="pass_through_z"
        args="load pcl/PassThrough pcl_manager">
    <param name="filter_field_name" value="z" />
    <param name="filter_limit_min" value="0.25" />
    <param name="filter_limit_max" value="3.0" />
    <param name="filter_limit_negative" value="False" />
    <remap from="~input" to="/kinect2/sd/points"/>
    <remap from="~output" to="/kinect2/sd/filtered_passthrough_z"/>
  </node>

  <node pkg="nodelet" type="nodelet"
        name="statistical_filter"
        args="load pcl/StatisticalOutlierRemoval pcl_manager">
    <param name="mean_k" value="100" />
    <param name="stddev" value="0.1" />
    <remap from="~input" to="/kinect2/sd/filtered_passthrough_z"/>
    <remap from="~output" to="/kinect2/sd/filtered_points"/>
  </node>
</launch>

See screenshot below for the point cloud after filtering.

image description

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2022-01-25 08:15:27 -0500

Seen: 84 times

Last updated: Jan 25 '22