Skip to content

Commit

Permalink
updated xacro tags
Browse files Browse the repository at this point in the history
  • Loading branch information
Michael Equi committed Mar 15, 2019
1 parent 1f85e3a commit baecad8
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
8 changes: 4 additions & 4 deletions realsense2_description/urdf/_r410.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ This is the URDF model for the Intel RealSense 410 camera, in it's
aluminum peripherial evalution case.
-->

<robot name="sensor_r410" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="sensor_r410" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
Expand All @@ -17,7 +17,7 @@ aluminum peripherial evalution case.
<xacro:property name="r410_cam_depth_to_right_ir_offset" value="0.0275"/>

<!-- The following values model the aluminum peripherial case for the
R410 camera, with the camera joint represented by the actual
R410 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="r410_cam_width" value="0.099"/>
<xacro:property name="r410_cam_height" value="0.035"/>
Expand Down Expand Up @@ -65,7 +65,7 @@ aluminum peripherial evalution case.
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257" />
</inertial>
</link>

<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<origin xyz="${r410_cam_depth_px} ${r410_cam_depth_py} ${r410_cam_depth_pz}" rpy="0 0 0"/>
Expand All @@ -80,7 +80,7 @@ aluminum peripherial evalution case.
<child link="camera_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>

<!-- camera left IR joints and links -->
<joint name="camera_left_ir_joint" type="fixed">
<origin xyz="0 ${r410_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
Expand Down
8 changes: 4 additions & 4 deletions realsense2_description/urdf/_r430.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ This is the URDF model for the Intel RealSense 430 camera, in it's
aluminum peripherial evaluation case.
-->

<robot name="sensor_r430" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="sensor_r430" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
Expand All @@ -18,7 +18,7 @@ aluminum peripherial evaluation case.
<xacro:property name="r430_cam_depth_to_fisheye_offset" value="0.042"/>

<!-- The following values model the aluminum peripherial case for the
R430 camera, with the camera joint represented by the actual
R430 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="r430_cam_width" value="0.105"/>
<xacro:property name="r430_cam_height" value="0.039"/>
Expand Down Expand Up @@ -66,7 +66,7 @@ aluminum peripherial evaluation case.
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257" />
</inertial>
</link>

<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<origin xyz="${r430_cam_depth_px} ${r430_cam_depth_py} ${r430_cam_depth_pz}" rpy="0 0 0"/>
Expand All @@ -81,7 +81,7 @@ aluminum peripherial evaluation case.
<child link="camera_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>

<!-- camera left IR joints and links -->
<joint name="camera_left_ir_joint" type="fixed">
<origin xyz="0 ${r430_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
Expand Down
2 changes: 1 addition & 1 deletion realsense2_description/urdf/test_r410_camera.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot name="realsense2_camera" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="realsense2_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find realsense2_description)/urdf/_r410.urdf.xacro"/>

<link name="base_link" />
Expand Down
2 changes: 1 addition & 1 deletion realsense2_description/urdf/test_r430_camera.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot name="realsense2_camera" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="realsense2_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find realsense2_description)/urdf/_r430.urdf.xacro"/>

<link name="base_link" />
Expand Down

0 comments on commit baecad8

Please sign in to comment.