Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Unable to remove shape handle #25

Open
PARKBONG opened this issue Oct 9, 2023 · 3 comments
Open

Unable to remove shape handle #25

PARKBONG opened this issue Oct 9, 2023 · 3 comments
Assignees
Labels
question Further information is requested

Comments

@PARKBONG
Copy link

PARKBONG commented Oct 9, 2023

Hi, I tried to filter the robot from my simulated point cloud.
Here is my setup.
IsaacSim -> Topic -> filter -> RVIZ

Image
image

Topics from the simulator

bong@Bong:~/catkin_kinnect$ rostopic list
/Isaac/Depth_pcl # Input point cloud
/joint_states
/tf

my_launch.launch

<?xml version="1.0"?>
<launch>
    <include file="$(find robot_body_filter)/launch/franka_description.launch"/>

    <node name = "laser_filter" 
        pkg="sensor_filters" 
        type = "pointcloud2_filter_chain" 
        output = "screen">

        <rosparam command="load" file="$(find robot_body_filter)/launch/my_config.yaml" />
        <remap from="~input" to="/Isaac/Depth_pcl" />
        <remap from="~output" to="/Isaac/Depth_pcl_filtered_bong" />
    </node>
</launch>

panda_description.launch

<launch>
    <param name="franka_description" 
        textfile="$(find robot_body_filter)/Panda/panda.urdf"/> 
</launch>

my_config.yaml

cloud_filter_chain:
-   name: body_filter
    type: robot_body_filter/RobotBodyFilterPointCloud2
    params:
        frames/filtering: 'panda_link0'
        frames/output: 'world'
        sensor/min_distance: 0.05
        sensor/max_distance: 50.0
        body_model/inflation/scale: 1.1
        body_model/inflation/padding: 0.02
        filter/do_shadow_test: False
        body_model/robot_description_param: "franka_description"

command
$ roslaunch robot_body_filter bong_filter.launch

output
'''
SUMMARY

PARAMETERS

  • /franka_description: <?xml version="1....
  • /laser_filter/cloud_filter_chain: [{'name': 'body_f...
  • /rosdistro: noetic
  • /rosversion: 1.16.0

NODES
/
laser_filter (sensor_filters/pointcloud2_filter_chain)

ROS_MASTER_URI=http://localhost:11311

process[laser_filter-1]: started with pid [190082]
[ INFO] [1696841160.032105490]: body_filter: Parameter sensor/point_by_point not defined, assigning default: False
[ INFO] [1696841160.032654530]: body_filter: Parameter transforms/buffer_length not defined, assigning default: 60.000000 s
[ INFO] [1696841160.035163346]: body_filter: Parameter frames/fixed not defined, assigning default: base_link
[ INFO] [1696841160.035194406]: body_filter: Parameter frames/sensor not defined, assigning default:
[ INFO] [1696841160.035215213]: body_filter: Found parameter: frames/filtering, value: panda_link0
[ INFO] [1696841160.035235122]: body_filter: Found parameter: sensor/min_distance, value: 0.050000 m
[ INFO] [1696841160.035245575]: body_filter: Found parameter: sensor/max_distance, value: 50.000000 m
[ INFO] [1696841160.035257429]: body_filter: Found parameter: body_model/robot_description_param, value: franka_description
[ INFO] [1696841160.035268249]: body_filter: Parameter filter/keep_clouds_organized not defined, assigning default: True
[ INFO] [1696841160.035281483]: body_filter: Parameter filter/model_pose_update_interval not defined, assigning default: 0.000000 s
[ INFO] [1696841160.035291174]: body_filter: Parameter filter/do_clipping not defined, assigning default: True
[ INFO] [1696841160.035300561]: body_filter: Parameter filter/do_contains_test not defined, assigning default: True
[ INFO] [1696841160.035311135]: body_filter: Found parameter: filter/do_shadow_test, value: False
[ INFO] [1696841160.035320957]: body_filter: Parameter filter/max_shadow_distance not defined, assigning default: 50.000000 m
[ INFO] [1696841160.035330713]: body_filter: Parameter transforms/timeout/reachable not defined, assigning default: 0.100000 s
[ INFO] [1696841160.035340255]: body_filter: Parameter transforms/timeout/unreachable not defined, assigning default: 0.200000 s
[ INFO] [1696841160.035349261]: body_filter: Parameter transforms/require_all_reachable not defined, assigning default: False
[ INFO] [1696841160.035358272]: body_filter: Parameter bounding_sphere/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.035367396]: body_filter: Parameter bounding_box/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.035376599]: body_filter: Parameter oriented_bounding_box/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.035385675]: body_filter: Parameter local_bounding_box/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.035394693]: body_filter: Parameter bounding_sphere/compute not defined, assigning default: False
[ INFO] [1696841160.035403605]: body_filter: Parameter bounding_box/compute not defined, assigning default: False
[ INFO] [1696841160.035412584]: body_filter: Parameter oriented_bounding_box/compute not defined, assigning default: False
[ INFO] [1696841160.035421650]: body_filter: Parameter local_bounding_box/compute not defined, assigning default: False
[ INFO] [1696841160.035430456]: body_filter: Parameter bounding_sphere/debug not defined, assigning default: False
[ INFO] [1696841160.035439341]: body_filter: Parameter bounding_box/debug not defined, assigning default: False
[ INFO] [1696841160.035448430]: body_filter: Parameter oriented_bounding_box/debug not defined, assigning default: False
[ INFO] [1696841160.035457332]: body_filter: Parameter local_bounding_box/debug not defined, assigning default: False
[ INFO] [1696841160.035466156]: body_filter: Parameter bounding_sphere/marker not defined, assigning default: False
[ INFO] [1696841160.035474798]: body_filter: Parameter bounding_box/marker not defined, assigning default: False
[ INFO] [1696841160.035483629]: body_filter: Parameter oriented_bounding_box/marker not defined, assigning default: False
[ INFO] [1696841160.035492304]: body_filter: Parameter local_bounding_box/marker not defined, assigning default: False
[ INFO] [1696841160.035501465]: body_filter: Parameter local_bounding_box/frame_id not defined, assigning default: base_link
[ INFO] [1696841160.035510483]: body_filter: Parameter debug/pcl/inside not defined, assigning default: False
[ INFO] [1696841160.035519315]: body_filter: Parameter debug/pcl/clip not defined, assigning default: False
[ INFO] [1696841160.035528038]: body_filter: Parameter debug/pcl/shadow not defined, assigning default: False
[ INFO] [1696841160.035536825]: body_filter: Parameter debug/marker/contains not defined, assigning default: False
[ INFO] [1696841160.035545541]: body_filter: Parameter debug/marker/shadow not defined, assigning default: False
[ INFO] [1696841160.035554253]: body_filter: Parameter debug/marker/bounding_sphere not defined, assigning default: False
[ INFO] [1696841160.035562972]: body_filter: Parameter debug/marker/bounding_box not defined, assigning default: False
[ INFO] [1696841160.035572048]: body_filter: Found parameter: body_model/inflation/padding, value: 0.020000 m
[ INFO] [1696841160.035581013]: body_filter: Found parameter: body_model/inflation/scale, value: 1.100000
[ INFO] [1696841160.035590318]: body_filter: Parameter body_model/inflation/contains_test/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.035599664]: body_filter: Parameter body_model/inflation/contains_test/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.035609157]: body_filter: Parameter body_model/inflation/shadow_test/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.035619039]: body_filter: Parameter body_model/inflation/shadow_test/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.035628316]: body_filter: Parameter body_model/inflation/bounding_sphere/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.035637643]: body_filter: Parameter body_model/inflation/bounding_sphere/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.035646865]: body_filter: Parameter body_model/inflation/bounding_box/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.035656148]: body_filter: Parameter body_model/inflation/bounding_box/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.035711795]: body_filter: Parameter body_model/inflation/per_link/padding not defined, assigning default: {} m
[ INFO] [1696841160.035734865]: body_filter: Parameter body_model/inflation/per_link/scale not defined, assigning default: {}
[ INFO] [1696841160.035797128]: body_filter: Parameter ignored_links/bounding_sphere not defined, assigning default: []
[ INFO] [1696841160.035848156]: body_filter: Parameter ignored_links/bounding_box not defined, assigning default: []
[ INFO] [1696841160.035859205]: body_filter: Parameter ignored_links/contains_test not defined, assigning default: []
[ INFO] [1696841160.035913096]: body_filter: Parameter ignored_links/shadow_test not defined, assigning default: ["laser"]
[ INFO] [1696841160.035948658]: body_filter: Parameter ignored_links/everywhere not defined, assigning default: []
[ INFO] [1696841160.035959238]: body_filter: Parameter only_links not defined, assigning default: []
[ INFO] [1696841160.035969795]: body_filter: Parameter body_model/dynamic_robot_description/field_name not defined, assigning default: robot_model
[ INFO] [1696841160.424100000]: RobotBodyFilter: Successfully configured.
[ INFO] [1696841160.424144266]: Filtering data in frame panda_link0
[ INFO] [1696841160.424152895]: RobotBodyFilter: Filtering into the following categories:
[ INFO] [1696841160.424160504]: RobotBodyFilter: OUTSIDE
[ INFO] [1696841160.424169895]: RobotBodyFilter: CLIP
[ INFO] [1696841160.424178009]: RobotBodyFilter: INSIDE
[ INFO] [1696841160.424192773]: RobotBodyFilter: Filtering applied to all links.
[ INFO] [1696841160.424212166]: body_filter: Found parameter: frames/output, value: world
[ INFO] [1696841160.424227347]: body_filter: Parameter cloud/point_channels not defined, assigning default: ["vp_"]
[ INFO] [1696841160.424238427]: body_filter: Parameter cloud/direction_channels not defined, assigning default: ["normal_"]
[ INFO] [1696841160.424297291]: Configured filter chain of type sensor_msgs/PointCloud2 from namespace /laser_filter/cloud_filter_chain
[ WARN] [1696841160.576454380]: RobotBodyFilter: Old TF data received. Clearing TF buffer and reconfiguring laser filter. If you're replaying a bag file, make sure rosparam /use_sim_time is set to true
[ INFO] [1696841160.576495627]: body_filter: Parameter sensor/point_by_point not defined, assigning default: False
[ INFO] [1696841160.576516577]: body_filter: Parameter transforms/buffer_length not defined, assigning default: 60.000000 s
[ INFO] [1696841160.576539651]: body_filter: Parameter frames/fixed not defined, assigning default: base_link
[ INFO] [1696841160.576550873]: body_filter: Parameter frames/sensor not defined, assigning default:
[ INFO] [1696841160.576561644]: body_filter: Found parameter: frames/filtering, value: panda_link0
[ INFO] [1696841160.576573145]: body_filter: Found parameter: sensor/min_distance, value: 0.050000 m
[ INFO] [1696841160.576583281]: body_filter: Found parameter: sensor/max_distance, value: 50.000000 m
[ INFO] [1696841160.576593163]: body_filter: Found parameter: body_model/robot_description_param, value: franka_description
[ INFO] [1696841160.576604308]: body_filter: Parameter filter/keep_clouds_organized not defined, assigning default: True
[ INFO] [1696841160.576615768]: body_filter: Parameter filter/model_pose_update_interval not defined, assigning default: 0.000000 s
[ INFO] [1696841160.576626513]: body_filter: Parameter filter/do_clipping not defined, assigning default: True
[ INFO] [1696841160.576638044]: body_filter: Parameter filter/do_contains_test not defined, assigning default: True
[ INFO] [1696841160.576653591]: body_filter: Found parameter: filter/do_shadow_test, value: False
[ INFO] [1696841160.576668059]: body_filter: Parameter filter/max_shadow_distance not defined, assigning default: 50.000000 m
[ INFO] [1696841160.576680794]: body_filter: Parameter transforms/timeout/reachable not defined, assigning default: 0.100000 s
[ INFO] [1696841160.576694144]: body_filter: Parameter transforms/timeout/unreachable not defined, assigning default: 0.200000 s
[ INFO] [1696841160.576706825]: body_filter: Parameter transforms/require_all_reachable not defined, assigning default: False
[ INFO] [1696841160.576719375]: body_filter: Parameter bounding_sphere/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.576731442]: body_filter: Parameter bounding_box/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.576744147]: body_filter: Parameter oriented_bounding_box/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.576757132]: body_filter: Parameter local_bounding_box/publish_cut_out_pointcloud not defined, assigning default: False
[ INFO] [1696841160.576768636]: body_filter: Parameter bounding_sphere/compute not defined, assigning default: False
[ INFO] [1696841160.576780467]: body_filter: Parameter bounding_box/compute not defined, assigning default: False
[ INFO] [1696841160.576793408]: body_filter: Parameter oriented_bounding_box/compute not defined, assigning default: False
[ INFO] [1696841160.576805676]: body_filter: Parameter local_bounding_box/compute not defined, assigning default: False
[ INFO] [1696841160.576817073]: body_filter: Parameter bounding_sphere/debug not defined, assigning default: False
[ INFO] [1696841160.576829061]: body_filter: Parameter bounding_box/debug not defined, assigning default: False
[ INFO] [1696841160.576841898]: body_filter: Parameter oriented_bounding_box/debug not defined, assigning default: False
[ INFO] [1696841160.576853863]: body_filter: Parameter local_bounding_box/debug not defined, assigning default: False
[ INFO] [1696841160.576865707]: body_filter: Parameter bounding_sphere/marker not defined, assigning default: False
[ INFO] [1696841160.576879140]: body_filter: Parameter bounding_box/marker not defined, assigning default: False
[ INFO] [1696841160.576888557]: body_filter: Parameter oriented_bounding_box/marker not defined, assigning default: False
[ INFO] [1696841160.576895451]: body_filter: Parameter local_bounding_box/marker not defined, assigning default: False
[ INFO] [1696841160.576902579]: body_filter: Parameter local_bounding_box/frame_id not defined, assigning default: base_link
[ INFO] [1696841160.576909095]: body_filter: Parameter debug/pcl/inside not defined, assigning default: False
[ INFO] [1696841160.576915352]: body_filter: Parameter debug/pcl/clip not defined, assigning default: False
[ INFO] [1696841160.576921727]: body_filter: Parameter debug/pcl/shadow not defined, assigning default: False
[ INFO] [1696841160.576927592]: body_filter: Parameter debug/marker/contains not defined, assigning default: False
[ INFO] [1696841160.576934275]: body_filter: Parameter debug/marker/shadow not defined, assigning default: False
[ INFO] [1696841160.576940600]: body_filter: Parameter debug/marker/bounding_sphere not defined, assigning default: False
[ INFO] [1696841160.576946780]: body_filter: Parameter debug/marker/bounding_box not defined, assigning default: False
[ INFO] [1696841160.576954525]: body_filter: Found parameter: body_model/inflation/padding, value: 0.020000 m
[ INFO] [1696841160.576961083]: body_filter: Found parameter: body_model/inflation/scale, value: 1.100000
[ INFO] [1696841160.576968340]: body_filter: Parameter body_model/inflation/contains_test/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.576976462]: body_filter: Parameter body_model/inflation/contains_test/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.576983717]: body_filter: Parameter body_model/inflation/shadow_test/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.576991645]: body_filter: Parameter body_model/inflation/shadow_test/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.576999353]: body_filter: Parameter body_model/inflation/bounding_sphere/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.577011893]: body_filter: Parameter body_model/inflation/bounding_sphere/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.577024531]: body_filter: Parameter body_model/inflation/bounding_box/padding not defined, assigning default: 0.020000 m
[ INFO] [1696841160.577038060]: body_filter: Parameter body_model/inflation/bounding_box/scale not defined, assigning default: 1.100000
[ INFO] [1696841160.577058979]: body_filter: Parameter body_model/inflation/per_link/padding not defined, assigning default: {} m
[ INFO] [1696841160.577076487]: body_filter: Parameter body_model/inflation/per_link/scale not defined, assigning default: {}
[ INFO] [1696841160.577097718]: body_filter: Parameter ignored_links/bounding_sphere not defined, assigning default: []
[ INFO] [1696841160.577114336]: body_filter: Parameter ignored_links/bounding_box not defined, assigning default: []
[ INFO] [1696841160.577121999]: body_filter: Parameter ignored_links/contains_test not defined, assigning default: []
[ INFO] [1696841160.577139810]: body_filter: Parameter ignored_links/shadow_test not defined, assigning default: ["laser"]
[ INFO] [1696841160.577154102]: body_filter: Parameter ignored_links/everywhere not defined, assigning default: []
[ INFO] [1696841160.577162741]: body_filter: Parameter only_links not defined, assigning default: []
[ INFO] [1696841160.577170823]: body_filter: Parameter body_model/dynamic_robot_description/field_name not defined, assigning default: robot_model
[ERROR] [1696841160.578391209]: Tried to advertise a service that is already advertised in this node [/laser_filter/reload_model]
[ERROR] [1696841160.579650175]: Unable to remove shape handle 1
[ERROR] [1696841160.579756266]: Unable to remove shape handle 2
[ERROR] [1696841160.579774046]: Unable to remove shape handle 3
[ERROR] [1696841160.579784502]: Unable to remove shape handle 4
[ERROR] [1696841160.579794978]: Unable to remove shape handle 5
[ERROR] [1696841160.579805400]: Unable to remove shape handle 6
[ERROR] [1696841160.579816417]: Unable to remove shape handle 7
[ERROR] [1696841160.579827515]: Unable to remove shape handle 8
[ERROR] [1696841160.579838438]: Unable to remove shape handle 9
[ERROR] [1696841160.579849765]: Unable to remove shape handle 10
[ERROR] [1696841160.579860980]: Unable to remove shape handle 11
[ INFO] [1696841160.998669953]: RobotBodyFilter: Successfully configured.
[ INFO] [1696841160.998690817]: Filtering data in frame panda_link0
[ INFO] [1696841160.998696080]: RobotBodyFilter: Filtering into the following categories:
[ INFO] [1696841160.998700673]: RobotBodyFilter: OUTSIDE
[ INFO] [1696841160.998706212]: RobotBodyFilter: CLIP
[ INFO] [1696841160.998710752]: RobotBodyFilter: INSIDE
[ INFO] [1696841160.998715908]: RobotBodyFilter: Filtering applied to all links.
[ INFO] [1696841160.998729091]: body_filter: Found parameter: frames/output, value: world
[ INFO] [1696841160.998742088]: body_filter: Parameter cloud/point_channels not defined, assigning default: ["vp_"]
[ INFO] [1696841160.998750767]: body_filter: Parameter cloud/direction_channels not defined, assigning default: ["normal_"]
[ERROR] [1696841160.998781178]: Filtering data from time 257.183346746 failed.
[ WARN] [1696841160.999983595]: RobotBodyFilter: Old TF data received. Clearing TF buffer and reconfiguring laser filter. If you're replaying a bag file, make sure rosparam /use_sim_time is set to true
'''

question

  1. At the 1st iteration of the process, there is only warning message:
    [ WARN] [1696841160.576454380]: RobotBodyFilter: Old TF data received. Clearing TF buffer and reconfiguring laser filter. If you're replaying a bag file, make sure rosparam /use_sim_time is set to true

  2. After the 1st iteration, the filter doesn't work.

[ERROR] [1696841160.578391209]: Tried to advertise a service that is already advertised in this node [/laser_filter/reload_model]
[ERROR] [1696841160.579650175]: Unable to remove shape handle 1
[ERROR] [1696841160.579756266]: Unable to remove shape handle 2
[ERROR] [1696841160.579774046]: Unable to remove shape handle 3
[ERROR] [1696841160.579784502]: Unable to remove shape handle 4
[ERROR] [1696841160.579794978]: Unable to remove shape handle 5
[ERROR] [1696841160.579805400]: Unable to remove shape handle 6
[ERROR] [1696841160.579816417]: Unable to remove shape handle 7
[ERROR] [1696841160.579827515]: Unable to remove shape handle 8
[ERROR] [1696841160.579838438]: Unable to remove shape handle 9
[ERROR] [1696841160.579849765]: Unable to remove shape handle 10
[ERROR] [1696841160.579860980]: Unable to remove shape handle 11
[ INFO] [1696841160.998669953]: RobotBodyFilter: Successfully configured.
[ INFO] [1696841160.998690817]: Filtering data in frame panda_link0
[ INFO] [1696841160.998696080]: RobotBodyFilter: Filtering into the following categories:
[ INFO] [1696841160.998700673]: RobotBodyFilter: 	OUTSIDE
[ INFO] [1696841160.998706212]: RobotBodyFilter: 	CLIP
[ INFO] [1696841160.998710752]: RobotBodyFilter: 	INSIDE
[ INFO] [1696841160.998715908]: RobotBodyFilter: Filtering applied to all links.
[ INFO] [1696841160.998729091]: body_filter: Found parameter: frames/output, value: world
[ INFO] [1696841160.998742088]: body_filter: Parameter cloud/point_channels not defined, assigning default: ["vp_"]
[ INFO] [1696841160.998750767]: body_filter: Parameter cloud/direction_channels not defined, assigning default: ["normal_"]
[ERROR] [1696841160.998781178]: Filtering data from time 257.183346746 failed.

Could you give me some advice? I tried to find the error message "Unable to remove shape handle," but I have no idea how to handle it.

Thanks!

@peci1 peci1 self-assigned this Oct 9, 2023
@peci1 peci1 added the question Further information is requested label Oct 9, 2023
@peci1
Copy link
Owner

peci1 commented Oct 9, 2023

Hi, you need to provide proper time. It seems you are running the simulation in a way that it timestamps data with its simulation time which starts at time 0 (e.g. 'data from time 257.18'). However, the ROS nodes do not know about this time, so they run in real time (e.g. 1696841160, which is the unix timestamp of current time).

Gazebo simulator provides a topic called /clock where it publishes the simulation time, and you can then add <param name="/use_sim_time" value="true" /> to your launch file to tell ROS to use this time. However, I don't see the /clock topic in the list of topics provided by Isaac. You will need to figure out how to configure Isaac to publish the /clock topic. I have no experience with Isaac so I can't help with that.

@PARKBONG
Copy link
Author

PARKBONG commented Oct 9, 2023

You Are Awesome.
Adding a /clock topic and setting a <param name="/use_sim_time" value="true" /> works.

But I would like to ask two more questions.

Question 1: Time-latency
https://github.com/peci1/robot_body_filter/assets/39259734/9264dd46-5b16-4659-bdcc-e716da4a8ba6

My setup is working because of your help.
How can I increase the processing speed? Ignoring the robot mesh out-to-interest region is the best option?

Question 2.: Best way to multiple processing
My Task: pick up an object on the table using a robot
My current objective is to clear out the 1.background 2. robot and 3. table from the point cloud to capture only the object.

Background: by setting a bounding box
robot: by the current setting that the movie shows
table: by setting the same point cloud filter, using a table urdf.

  1. what is the best option to clear out static objects, like table?
  2. Should I launch three point cloud filters to clear out the background, table, and robot?
  3. Three pointcloud processes need to be connected, will the order affect performance?

Again, as a beginner in this kind of ROS project, I appreciate your kind and fast help.
Thanks!

@peci1
Copy link
Owner

peci1 commented Oct 9, 2023

You Are Awesome. Adding a /clock topic and setting a <param name="/use_sim_time" value="true" /> works.

I'm glad it worked!

Question 1: Time-latency https://github.com/peci1/robot_body_filter/assets/39259734/9264dd46-5b16-4659-bdcc-e716da4a8ba6

My setup is working because of your help. How can I increase the processing speed? Ignoring the robot mesh out-to-interest region is the best option?

The most slowing down thing is doing pointcloud-mesh collisions checks. There are two ways (which can even be combined):

  1. Use primitive shapes (boxes, cylinders, spheres) as collision objects instead of meshes. This may require you creating an alternative URDF model with different <collision> elements. Or have a look around if panda hasn't released a simplified model.
  2. Number of links that are considered during the filtering. Refer to parameters ignored_links/everywhere and only_links in the readme. If you know some links cannot ever be seen by the camera, just remove them from the filter.
  3. (bonus point :) ) Shadow filtering. But you have that turned off.

Also, if you're building this package from source, make sure you build it in release or relwithdebinfo modes. Debug mode is super slow.

I'm not sure how fast your camera is, but generally, the 30 FPS depth cameras are pretty tough to process. If your application allows, you could also consider decreasing the FPS of the camera to get more predictable filtered FPS (i.e. not to overload the filter). The filter itself cannot parallelize processing more, but in an extreme case, I can imagine you could write a nodelet that sends the pointclouds to e.g. 5 filters running side by side, but all publishing to the same output topic. This way, each of the 5 filters could be processing some data at the same time. The latency would stay the same, but the rate would increase.

Question 2.: Best way to multiple processing My Task: pick up an object on the table using a robot My current objective is to clear out the 1.background 2. robot and 3. table from the point cloud to capture only the object.

Background: by setting a bounding box robot: by the current setting that the movie shows table: by setting the same point cloud filter, using a table urdf.

1. what is the best option to clear out static objects, like `table`?

If you have it in the same URDF as the arm, that's fine, you can just leave it there. If not, you can either run a second instance of this filter, or use a plain pcl_ros/CropBox nodelet to filter out the table.

2. Should I launch three point cloud filters to clear out the background, table, and robot?

The fewer filters, the better.

3. Three pointcloud processes need to be connected, will the order affect performance?

robot_body_filter can do basic pointcloud clipping using parameters sensor/min_distance and sensor/max_distance. This is automatically done before the other more expensive tests. If you know something more about your pointcloud, e.g. a bounding box of the scene of interest, I suggest running first a CropBox filter to get just the area of interest, and after that running robot_body_filter. If you use CropBox for filtering out the table, also do it before this filter. Generally, the more things you filter out using simpler filters, the better. robot_body_filter is usually the most expensive one. But it only acts on points that have not yet been filtered out.

Also, if you're building a filtering pipeline, be sure to use nodelets and not nodes.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants