Skip to content

Commit

Permalink
update robtos
Browse files Browse the repository at this point in the history
  • Loading branch information
MingshanHe committed Jul 1, 2023
1 parent 96a3270 commit 38123f1
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,8 @@
<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />

<!-- links: main serial chain -->
<link name="${prefix}base_link"/>
<link name="${prefix}base_link_inertia">
<link name="${prefix}base_link_inertia"/>
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
Expand Down Expand Up @@ -221,8 +221,8 @@

<!-- joints: main serial chain -->
<joint name="${prefix}base_link-base_link_inertia" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}base_link_inertia" />
<parent link="${prefix}base_link_inertia" />
<child link="${prefix}base_link" />
<!-- 'base_link' is REP-103 aligned (so X+ forward), while the internal
frames of the robot/controller have X+ pointing backwards.
Use the joint between 'base_link' and 'base_link_inertia' (a dummy
Expand All @@ -231,7 +231,7 @@
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
</joint>
<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link_inertia" />
<parent link="${prefix}base_link" />
<child link="${prefix}shoulder_link" />
<origin xyz="${shoulder_x} ${shoulder_y} ${shoulder_z}" rpy="${shoulder_roll} ${shoulder_pitch} ${shoulder_yaw}" />
<axis xyz="0 0 1" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
<arg name="physical_params" default="$(find ur_description)/config/ur5e/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur5e/visual_parameters.yaml"/>
<!-- 1. PositionJointInterface 2. EffortJointInterface -->
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface"/>
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>
<arg name="environment" default="empty" doc="Specify the virtual environment"/>
<arg name="gazebo_world" default="$(find ur_gazebo)/worlds/$(arg environment).world"/>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@
<link name="world"/>
<joint name="world_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<child link="base_link_inertia"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
</robot>

0 comments on commit 38123f1

Please sign in to comment.