forked from xtdrone/XTDrone
modify for robotic arm
This commit is contained in:
parent
f4b47b6792
commit
7a82693469
|
@ -696,18 +696,14 @@
|
|||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.015 0.1 0.02</size>
|
||||
</box>
|
||||
<box size="0.015 0.1 0.02" />
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.015 0.1 0.02</size>
|
||||
</box>
|
||||
<box size="0.015 0.1 0.02" />
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
|
|
|
@ -202,7 +202,10 @@
|
|||
</xacro:if>
|
||||
|
||||
<!-- Instantiate a VI sensor. -->
|
||||
<xacro:vi_sensor_macro namespace="$(arg name)" parent_link="base_link">
|
||||
<!-- <xacro:vi_sensor_macro namespace="$(arg name)" parent_link="base_link">
|
||||
<origin xyz="0.2 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||
</xacro:vi_sensor_macro>
|
||||
</xacro:vi_sensor_macro> -->
|
||||
|
||||
<xacro:include filename="$(find le_arm)/urdf/sensors/camera.urdf.xacro"/>
|
||||
|
||||
</robot>
|
||||
|
|
|
@ -5,7 +5,7 @@ This link is the base of the arm in which arm is placed
|
|||
<robot name="camera" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<joint name="camera_joint" type="fixed">
|
||||
<origin xyz="0.3 0 0.7" rpy="0 1.57 0"/>
|
||||
<origin xyz="0.05 0 -0.07" rpy="0 1.57 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="camera_link"/>
|
||||
</joint>
|
||||
|
@ -15,7 +15,7 @@ This link is the base of the arm in which arm is placed
|
|||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://le_arm/meshes/sensors/camera.STL" />
|
||||
<mesh filename="package://le_arm/meshes/sensors/camera.STL" scale="0.1 0.1 0.1" />
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
|
@ -30,9 +30,9 @@ This link is the base of the arm in which arm is placed
|
|||
<inertial>
|
||||
<mass value="0.00001" />
|
||||
<origin xyz="0 0 0" />
|
||||
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
|
||||
iyy="0.001" iyz="0.0"
|
||||
izz="0.001" />
|
||||
<inertia ixx="0.00001" ixy="0.0" ixz="0.0"
|
||||
iyy="0.00001" iyz="0.0"
|
||||
izz="0.00001" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
|
|
Loading…
Reference in New Issue