Skip to content

Commit

Permalink
More documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
Abishalini committed Nov 20, 2020
1 parent 5f5a53e commit a752fa7
Show file tree
Hide file tree
Showing 7 changed files with 96 additions and 23 deletions.
Binary file added doc/mesh_filter/Filtered_Depth.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/mesh_filter/MeshFilter.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/mesh_filter/Model_Depth.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
115 changes: 93 additions & 22 deletions doc/mesh_filter/mesh_filter_tutorial.rst
Original file line number Diff line number Diff line change
@@ -1,37 +1,108 @@
Mesh Filter with UR5 and Kinect Sensor
======================================
Mesh Filter with UR5 and Kinect
===============================

The mesh filter takes in a point cloud, tf of robot and a URDF and published a modified point cloud with the point cloud subtracted that overlaps with the current robot state.
The mesh filter takes in a point cloud, tf of robot and a URDF and publishes a modified point cloud with the point cloud subtracted that overlaps with the current robot state.

Getting Started
---------------
Clone the universal_robot repository into your workspace
<https://github.com/ros-industrial/universal_robot>
We require UR urdf files from the above repository

* Follow the instructions for :moveit_website:`installing MoveIt<install>`
first if you have not already done that.

* Clone the `Universal Robot package <https://github.com/ros-industrial/universal_robot>`_ to your workspace for Melodic.

* Install `Gazebo <http://gazebosim.org/tutorials?tut=install_ubuntu&cat=install>`_


Running the Demo
+++++++++++++++++
-----------------

Roslaunch the launch file to run the code directly from moveit_tutorials: ::

roslaunch moveit_tutorials mesh_filter.launch

The above command opens a UR5 arm with Kinect sensor on Gazebo and Rviz

.. image:: MeshFilter.gif

Topic /filtered/depth produces the modified point cloud with points subtracted that overlaps with the robot state.

.. image:: Filtered_Depth.png

Topic /model/depth gives the points that overlap with the current robot state

.. image:: Model_Depth.png

Check out the mesh filter code `here <https://github.com/ros-planning/moveit/blob/master/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp>`_


How to add sensor to arm in simulation
--------------------------------------

Include sensor plugin in a .gazebo file. In this tutorial, a kinect sensor plugin is added to ur5_sensor.gazebo ::

<gazebo reference="camera_depth_frame">
<sensor name="kinect_camera" type="depth">
<update_rate>20</update_rate>
<camera>
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>B8G8R8</format>
</image>
<clip>
<near>0.05</near>
<far>3</far>
</clip>
</camera>
<plugin name="kinect_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.1</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<cameraName>camera_ir</cameraName>
<imageTopicName>/camera/color/image_raw</imageTopicName>
<cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>/camera/depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
<frameName>camera_depth_optical_frame</frameName>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
<pointCloudCutoff>0.16</pointCloudCutoff>
<pointCloudCutoffMax>10.0</pointCloudCutoffMax>
</plugin>
</sensor>
</gazebo>


Attach sensor to `base urdf <https://github.com/ros-industrial/universal_robot/blob/melodic-devel/ur_description/urdf/ur5.urdf.xacro>`_ of UR5 using links and joints as shown in ur5_sensor.urdf.xacro ::
<!-- ur5 -->
<xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />

<!-- Attach UR5 to table -->
<joint name="table_joint" type="fixed">
<parent link="table"/>
<child link="base_link"/>
</joint>

How to add sensor to arm
-------------------------
Include sensor plugin in ur5_sensor.gazebo and build on top of base urdf using links and joints in ur5_sensor.urdf.xacro
This tutorial adds a Kinect but any other sensor can be added (e.g Hokuyo Lidar)
<!-- Attach Kinect to table -->
<joint type="fixed" name="table_camera_joint">
<origin xyz="0.15 -1 0.1" rpy="0 0 1.57"/>
<child link="camera_rgb_frame"/>
<parent link="table"/>
<axis xyz="0 0 0" rpy="0 0 0"/>
<limit effort="10000" velocity="1000"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>

What is in the mesh_filter launch file?
---------------------------------------
mesh_filter launch file contains the following commands :

roslaunch moveit_tutorials test_gazebo.launch
rosrun topic_tools relay /camera/depth/image_raw /depth
rosrun topic_tools relay /camera/color/camera_info /camera_info
rosrun nodelet nodelet manager __name:=nodelet_manager
rosrun nodelet nodelet load mesh_filter/DepthSelfFiltering nodelet_manager

Mesh Filter reference code - <https://github.com/ros-planning/moveit/blob/master/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp>

What is a nodelet?
-------------------
References
----------
`Understanding ROS Nodelets <https://medium.com/@waleedmansoor/understanding-ros-nodelets-c43a11c8169e>`_
Empty file removed doc/mesh_filter/package.xml
Empty file.
2 changes: 1 addition & 1 deletion doc/mesh_filter/urdf/ur5_sensor.gazebo
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<robot>
<gazebo reference="camera_depth_frame">
<gazebo reference="camera_depth_frame">
<sensor name="kinect_camera" type="depth">
<update_rate>20</update_rate>
<camera>
Expand Down
2 changes: 2 additions & 0 deletions doc/mesh_filter/urdf/ur5_sensor.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,13 @@
<child link="table"/>
</joint>

<!-- Attach UR5 to table -->
<joint name="table_joint" type="fixed">
<parent link="table"/>
<child link="base_link"/>
</joint>

<!-- Attach Kinect to table -->
<joint type="fixed" name="table_camera_joint">
<origin xyz="0.15 -1 0.1" rpy="0 0 1.57"/>
<child link="camera_rgb_frame"/>
Expand Down

0 comments on commit a752fa7

Please sign in to comment.