Comments (3)
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.
from robot_body_filter.
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):
- 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. - Number of links that are considered during the filtering. Refer to parameters
ignored_links/everywhere
andonly_links
in the readme. If you know some links cannot ever be seen by the camera, just remove them from the filter. - (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 thetable
using arobot
My current objective is to clear out the1.background
2. robot
and3. 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.
from robot_body_filter.
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.
- what is the best option to clear out static objects, like
table
? - Should I launch three point cloud filters to clear out the background, table, and robot?
- 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!
from robot_body_filter.
Related Issues (19)
- Why should the user set the sensor_frame HOT 5
- Reloading robot model HOT 3
- Problem reloading robot model HOT 2
- TF frames watchdog reachability check breaks our self-filter HOT 11
- TF watchdog for sensor frame breaks filter HOT 11
- Cmake error HOT 7
- transformWithChannels should differentiate between point-like and direction-like channels
- Seg fault when calling configure for robot_body_filter/RobotBodyFilterPointCloud2 HOT 19
- noetic support HOT 7
- Warnings for unset parameters HOT 4
- Question: Shortest distance from point to robot manipulator? HOT 2
- Per link padding and scaling not working HOT 6
- Cannot build robot_body_filter in ros-melodic ubuntu18.04 HOT 3
- Conflict with non-released updates in geometric_shapes@noetic-devel HOT 11
- ROS2 plans HOT 6
- [Noetic] error: redefinition of ‘class bodies::OBB’ HOT 5
- Timing issue PointCloud and Collision geometry HOT 14
- process has died during runtime,please help HOT 13
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from robot_body_filter.