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

Add openni_description package. #58

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ notifications:
- [email protected]
env:
matrix:
- ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true
- ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu USE_DEB=true
- ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true NOT_TEST_INSTALL=true
- ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu USE_DEB=true NOT_TEST_INSTALL=true
- ROS_DISTRO="indigo" PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=1
- ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true
- ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu USE_DEB=true
Expand Down
15 changes: 15 additions & 0 deletions openni_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
cmake_minimum_required(VERSION 2.8.3)
project(openni_description)

find_package(catkin REQUIRED)

catkin_package()

install(DIRECTORY model DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} USE_SOURCE_PERMISSIONS)
if (CATKIN_ENABLE_TESTING)
find_package(catkin REQUIRED COMPONENTS rostest)
if("$ENV{ROS_DISTRO}" STRGREATER "jade")
add_rostest(test/sample_kobuki.test)
endif()
endif ()
165 changes: 165 additions & 0 deletions openni_description/mesh/kinect.dae

Large diffs are not rendered by default.

Binary file added openni_description/mesh/kinect.jpg
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 openni_description/mesh/kinect.tga
Binary file not shown.
69 changes: 69 additions & 0 deletions openni_description/model/kinect.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
<?xml version="1.0"?>
<robot name="sensor_openni" xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:include filename="$(find openni_description)/model/kinect_gazebo.urdf.xacro" />

<!-- Parameterised in part by the values in turtlebot_properties.urdf.xacro -->
<xacro:macro name="sensor_kinect" params="parent cam_px cam_py cam_pz cam_or cam_op cam_oy">
<joint name="camera_rgb_joint" type="fixed">
<origin xyz="${cam_px} ${cam_py} ${cam_pz}" rpy="${cam_or} ${cam_op} ${cam_oy}"/>
<parent link="${parent}"/>
<child link="camera_rgb_frame" />
</joint>
<link name="camera_rgb_frame"/>

<joint name="camera_rgb_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_rgb_frame" />
<child link="camera_rgb_optical_frame" />
</joint>
<link name="camera_rgb_optical_frame"/>

<joint name="camera_joint" type="fixed">
<origin xyz="-0.031 ${-cam_py} -0.016" rpy="0 0 0"/>
<parent link="camera_rgb_frame"/>
<child link="camera_link"/>
</joint>
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${M_PI/2}"/>
<geometry>
<mesh filename="package://openni_description/mesh/kinect.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.07271 0.27794 0.073"/>
</geometry>
</collision>
<inertial>
<mass value="0.564" />
<origin xyz="0 0 0" />
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0"
iyy="0.000498940" iyz="0.0"
izz="0.003879257" />
</inertial>
</link>

<!-- The fixed joints & links below are usually published by static_transformers launched by the OpenNi launch
files. However, for Gazebo simulation we need them, so we add them here.
(Hence, don't publish them additionally!) -->
<joint name="camera_depth_joint" type="fixed">
<origin xyz="0 ${2 * -cam_py} 0" rpy="0 0 0" />
<parent link="camera_rgb_frame" />
<child link="camera_depth_frame" />
</joint>
<link name="camera_depth_frame"/>

<joint name="camera_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>

<!-- Kinect sensor for simulation -->
<sim_3dsensor_kinect/>
</xacro:macro>
</robot>
42 changes: 42 additions & 0 deletions openni_description/model/kinect_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
<?xml version="1.0"?>
<robot name="kinect_gazebo" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- Microsoft Kinect / ASUS Xtion PRO Live for simulation -->
<xacro:macro name="sim_3dsensor_kinect">
<gazebo reference="camera_link">
<sensor type="depth" name="camera">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>8.0</far>
</clip>
</camera>
<plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>camera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<frameName>camera_depth_optical_frame</frameName>
<baseline>0.1</baseline>
<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.4</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
42 changes: 42 additions & 0 deletions openni_description/model/turtlebot_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
<?xml version="1.0"?>
<robot name="turtlebot_gazebo" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Microsoft Kinect / ASUS Xtion PRO Live for simulation -->
<xacro:macro name="turtlebot_sim_3dsensor">
<gazebo reference="camera_link">
<sensor type="depth" name="camera">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>8.0</far>
</clip>
</camera>
<plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>camera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<frameName>camera_depth_optical_frame</frameName>
<baseline>0.1</baseline>
<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.4</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
20 changes: 20 additions & 0 deletions openni_description/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<package>
<name>openni_description</name>
<version>1.9.8</version>
<description>Model files of OpenNI device.</description>
<author email="[email protected]">Isaac I.Y. Saito</author>
<maintainer email="[email protected]">Isaac I.Y. Saito</maintainer>
<license>BSD</license>

<url type="website">http://www.ros.org/wiki/openni_description</url>
<url type="repository">https://github.com/ros-drivers/openni_camera</url>
<url type="bugtracker">https://github.com/ros-drivers/openni_camera/issues</url>

<buildtool_depend>catkin</buildtool_depend>
<run_depend>urdf</run_depend>
<run_depend>xacro</run_depend>
<test_depend>kobuki_description</test_depend>
<test_depend>liburdfdom-tools</test_depend>
<test_depend>rostest</test_depend>
<test_depend>turtlebot_description</test_depend>
</package>
4 changes: 4 additions & 0 deletions openni_description/test/sample_kobuki.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<node pkg="xacro" type="xacro" name="kobuki_urdf_generation" args="$(find openni_description)/test/sample_kobuki.urdf.xacro -o sample_kobuki.urdf" />
<test pkg="openni_description" type="test_openni_desc.py" test-name="test_openni_descriptioner" />
</launch>
13 changes: 13 additions & 0 deletions openni_description/test/sample_kobuki.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0"?>
<robot name="turtlebot" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_common_library.urdf.xacro" />
<xacro:include filename="$(find kobuki_description)/urdf/kobuki.urdf.xacro" />
<xacro:include filename="$(find turtlebot_description)/urdf/stacks/hexagons.urdf.xacro" />
<xacro:include filename="$(find openni_description)/model/kinect.urdf.xacro" />
<xacro:include filename="$(find openni_description)/test/turtlebot_properties.urdf.xacro"/>

<sensor_kinect parent="base_link" cam_px="${cam_px}" cam_py="${cam_py}" cam_pz="${cam_pz}" cam_or="${cam_or}" cam_op="${cam_op}" cam_oy="${cam_oy}" />

<kobuki />
<stack_hexagons parent="base_link" />
</robot>
39 changes: 39 additions & 0 deletions openni_description/test/test_openni_desc.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
#!/usr/bin/env python
# -*- coding: utf-8 -*-

PKG = 'openni_description'

import os
import subprocess
import unittest

import rospkg
import xacro


class TestOpenniDescription(unittest.TestCase):

def setUp(self):
pass

def tearDown(self):
True

def test_urdf_turtlebot(self):
"""
Check if check_urdf command passes with the urdf that is generated in
the .test file this test case is called from.
"""
resulted_urdf_file_relpath = "./sample_kobuki.urdf"
kobuki_xacro_file_path = rospkg.RosPack().get_path('openni_description') + "/test/sample_kobuki.urdf.xacro"
self.assertTrue(os.path.isfile(kobuki_xacro_file_path))
xacro_output_memory = xacro.process_file(kobuki_xacro_file_path)
xacro_output_file = xacro.open_output(resulted_urdf_file_relpath)
xacro_output_file.write(xacro_output_memory.toprettyxml(indent=' '))
xacro_output_file.close()
self.assertTrue(os.path.isfile(resulted_urdf_file_relpath))
self.assertEqual(0, subprocess.call(["check_urdf", resulted_urdf_file_relpath]))

if __name__ == '__main__':
import rostest
rostest.rosrun(PKG, 'test_openni_description', TestOpenniDescription)
31 changes: 31 additions & 0 deletions openni_description/test/turtlebot_properties.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!--
These properties must be observed by any machine
that wants to be defined as a turtlebot. Refer
to the REP for more details.

http://www.ros.org/reps/rep-0119.html
-->

<!--
======================================================================
- REP 119 : Rgb camera link relative to the Base link
======================================================================
Base link is currently defined as the rotational centre on the bottom
of the base mould. For both create and kobuki this is actually exactly
the same 3d world point.

This may cause an issue with a base with much different floor clearance.
Should we be using base_footprint for this specification instead?

Note: REP needs to be updated with the information below
(currently in development and awaiting feedback)
-->
<xacro:property name="cam_px" value="-0.087" />
<xacro:property name="cam_py" value="-0.0125"/>
<xacro:property name="cam_pz" value="0.2870" />
<xacro:property name="cam_or" value="0" />
<xacro:property name="cam_op" value="0" />
<xacro:property name="cam_oy" value="0" />
</robot>