Skip to content

Commit

Permalink
renamed files to account for package name change
Browse files Browse the repository at this point in the history
  • Loading branch information
jupidity committed Aug 2, 2017
1 parent a306fad commit a5c3869
Show file tree
Hide file tree
Showing 2 changed files with 240 additions and 0 deletions.
78 changes: 78 additions & 0 deletions urdf/obj_recognition.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/obj_recognition</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>

<!--base_link-->
<gazebo reference="base_link">
<material>Gazebo/White</material>
</gazebo>

<!--link_1-->
<gazebo reference="link_1">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Orange</material>
</gazebo>

<!--link_2-->
<gazebo reference="link_2">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/White</material>
</gazebo>

<!--camera_link-->
<gazebo reference="camera_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Grey</material>
</gazebo>

<!--RGBD camera -->
<gazebo reference="camera_rgb_frame">
<sensor type="depth" name="camera">
<always_on>true</always_on>
<visualize>false</visualize>
<update_rate>15.0</update_rate>
<camera name="front">
<horizontal_fov>1.047197</horizontal_fov>
<image>
<!-- openni_kinect plugin works only with BGR8 -->
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.01</near>
<far>9</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.1</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<cameraName>camera</cameraName>
<imageTopicName>/camera/rgb/image_raw</imageTopicName>
<cameraInfoTopicName>/camera/rgb/camera_info</cameraInfoTopicName>
<depthImageTopicName>/camera/depth_registered/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>/camera/depth_registered/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>/camera/depth_registered/points</pointCloudTopicName>
<frameName>camera_rgb_optical_frame</frameName>
<pointCloudCutoff>0.35</pointCloudCutoff>
<pointCloudCutoffMax>4.5</pointCloudCutoffMax>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>

</robot>
162 changes: 162 additions & 0 deletions urdf/obj_recognition.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,162 @@
<?xml version="1.0"?>
<robot name="obj_recognition" xmlns:xacro="http://www.ros.org/wiki/xacro">

<!--Define constants-->
<xacro:property name="PI" value="3.14159"/>
<xacro:property name="mass1" value="10" />
<xacro:property name="mass2" value="1" />
<xacro:property name="width1" value="0.1" /> <!--link_1 radius-->
<xacro:property name="width2" value="0.1" /> <!--link_2 radius-->
<xacro:property name="length0" value="0.1" /> <!--link_1 length-->
<xacro:property name="length1" value="1.5" /> <!--link_2 length-->
<xacro:property name="length2" value="0.1" /> <!--link_3 length-->
<xacro:property name="mass_camera" value="0.2" />

<!--Import gazebo elements-->
<xacro:include filename="$(find obj_recognition)/urdf/obj_recognition.gazebo.xacro" />

<!--Links-->
<link name="world"/>

<link name="link_1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${width1} ${width1} ${length1}"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${width1} ${width1} ${length1}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${mass1}"/>
<inertia
ixx="${mass1 / 12.0 * (width1*width1 + length1*length1)}" ixy="0.0" ixz="0.0"
iyy="${mass1 / 12.0 * (length1*length1 + width1*width1)}" iyz="0.0"
izz="${mass1 / 12.0 * (width1*width1 + width1*width1)}"/>
</inertial>
</link>

<link name="link_2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${width2} ${width2} ${length2}"/>
</geometry>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${width2} ${width2} ${length2}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${mass2}"/>
<inertia
ixx="${mass2 / 12.0 * (width2*width2 + length2*length2)}" ixy="0.0" ixz="0.0"
iyy="${mass2 / 12.0 * (length2*length2 + width2*width2)}" iyz="0.0"
izz="${mass2 / 12.0 * (width2*width2 + width2*width2)}"/>
</inertial>
</link>


<!-- RGBD camera -->
<link name="camera_link">
<collision>
<origin xyz="-0.016 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.036 0.18 0.04"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://obj_recognition/meshes/asus_xtion.dae"/>
</geometry>
</visual>
<inertial>
<mass value="${mass_camera}" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
</inertial>
</link>

<!--Joints-->
<joint name="fixed_base_joint" type="fixed">
<parent link="world"/>
<child link="link_1"/>
<origin xyz="0 0 ${length1/2}" rpy="0 0 0"/>
</joint>

<joint name="pan_joint" type="continuous">
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 0 1"/>
<origin xyz="0 0 ${length1/2+length2/2}" rpy="0 0 -${pi/2}"/>
</joint>

<joint name="tilt_joint" type="continuous">
<origin xyz="0.05 0 ${length2/2+0.02}" rpy="0 0.5 0" />
<parent link="link_2" />
<child link="camera_link" />
<axis xyz="0 1 0"/>
</joint>
<link name="camera_rgb_frame" />
<joint name="camera_rgb_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.022 0" />
<parent link="camera_link" />
<child link="camera_rgb_frame" />
</joint>
<link name="camera_rgb_optical_frame" />
<joint name="camera_rgb_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0" />
<parent link="camera_rgb_frame" />
<child link="camera_rgb_optical_frame" />
</joint>
<link name="camera_depth_frame" />
<joint name="camera_depth_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.049 0" />
<parent link="camera_link" />
<child link="camera_depth_frame" />
</joint>
<link name="camera_depth_optical_frame" />
<joint name="camera_depth_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
</joint>

<!--Transmission and actuators-->
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="pan_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="tilt_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>

0 comments on commit a5c3869

Please sign in to comment.