Moveit! self_filter from octomap working for robotiq gripper but not UR5/UR10 body
System: Ubuntu 16.04 / ROS Kinetic / Nuvo-5095GC-022 / Universal Robots UR10 Packages: freenect_stack, geometry2, libfreenect, perception_pcl, trac_ik, universal_robot, ur_modern_driver
Hi,
Some background: As part of a dynamic collision avoidance project I'm trying to achieve full visibility of a live scene using multiple Kinect cameras. In the current setup I have two Xbox Kinect V1s, each producing a working point cloud. The cameras are positioned with a 90deg offset and the frames have been linked using tf2, so the points match up relatively well in 3D (cameras are intrinsically calibrated). From there i have used the two point clouds to create an octomap that the robot plans to avoid.
Now that i've got the live octomap sorted i'm running into problems with the integrated self_filter function inside Moveit!, in that only the gripper is being filtered from the scene regardless of the padding/offset values used. If i view the filtered_cloud topic as a point cloud 2, it clearly illustrates the problem.
It's almost like the robot urdf is being ignored due to the addition of the end effector?
UPDATE (01/11/2018). Observations:
- Removal of the second Octomap updater plugin does not resolve the problem
- * I've noticed that the Octomap is not clearing correctly. If I move the Kinect, the map is 'filled' with new blocks but old blocks are not removed, meaning that they have to be cleared manually. This is likely to be the cause but I have no idea why this might be happening, i'll look into it when I can.
- If I copy the UR10 sensor.yaml and launch files into the UR5 package, the Octomap behaves as expected (clearing correctly, self_filter operational). I think the only difference is that the UR10 has a gripper attached with all gripper joints set as passive, the UR5 has no gripper attached.
Any ideas?
My sensors.yaml file looks like:
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /camera/depth_registered/points
max_range: 5.0
point_subsample: 1 # As expected. Every 1 in point_subsample read
padding_offset: 0.1
padding_scale: 1.0 # Scale of voxels
filtered_cloud_topic: filtered_cloud
shape_padding: 0.5
shape_scale: 1.0
self_see_default_padding: 0.1
self_see_default_scale: 1.0
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /camera2/depth_registered/points
max_range: 5.0
point_subsample: 1 # As expected. Every 1 in point_subsample read
padding_offset: 0.1
padding_scale: 0.1 # Scale of voxels
filtered_cloud_topic: filtered2_cloud
shape_padding: 0.3
shape_scale: 1.0
self_see_default_padding: 0.5
self_see_default_scale: 1.0
And my urdf:
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!--
Author: Kelsey Hawkins
Contributers: Jimmy Da Silva, Ajit Krisshna N L, Muhammad Asif Rana
-->
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />
<!-- Robotiq -->
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_85_gripper.urdf.xacro" />
<xacro:robotiq_85_gripper parent="ee_link" prefix="gripper">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:robotiq_85_gripper>
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius ...
Please attach your images directly to the question. I've given you enough karma to do that.
Also: please consider accepting answers for your previous questions (if you feel they have been answered of course).
I'm not sure, but if you remove one of the octomap updater plugins, does it then work?
It doesn't, no. I've noticed that I'm getting the error 'Dropping first 1 trajectory point(s) out of ##, as they occur before the current time. First valid point will be reached in...' in the gazebo launch terminal, not sure if this will contribute? For some reason it works with ur5 and no gripper!