Skip to content
Open
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
6 changes: 0 additions & 6 deletions config/mobile_servicing_system_control.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -196,9 +196,3 @@
constraints:
stopped_velocity_tolerance: 0.1
goal_time: 0.0

/gz_ros_control:
ros__parameters:
# P-gain across all joints in gazebo's position interface
# https://control.ros.org/humble/doc/gz_ros2_control/doc/index.html#notes-on-the-command-interface
position_proportional_gain: 0.05
46 changes: 23 additions & 23 deletions urdf/canadarm2.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@
</geometry>
</collision>
</link>

<!-- ******* Link 3 ******* -->
<link name="canadarm2_link_3">
<inertial>
Expand Down Expand Up @@ -150,7 +150,7 @@
</geometry>
</collision>
</link>

<!-- ******* Link 6 ******* -->
<link name="canadarm2_link_6">
<inertial>
Expand Down Expand Up @@ -195,17 +195,17 @@
<mesh filename="package://iss_description/meshes/canadarm2/link_7.dae" scale="1 1 1"/>
</geometry>
</collision>
</link>
</link>

<joint name="joint_pdgf" type="fixed">
<origin rpy="0 0 0" xyz="-1.4347 -0.19847 1.5901"/>
<parent link="${parent}"/>
<child link="pdgf"/>
</joint>


<joint name="joint_canadarm2_base" type="fixed">
<origin rpy="-0.35691983 0.0 -0.572468" xyz="0 0 0"/>
<origin rpy="-0.35691983 0.0 -0.572468" xyz="0 0 0"/>
<parent link="pdgf"/>
<child link="canadarm2_base"/>
</joint>
Expand All @@ -216,7 +216,7 @@
<parent link="canadarm2_base"/>
<child link="canadarm2_link_1"/>
<axis xyz="0 1 0"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

<!-- joint 2 -->
Expand All @@ -225,7 +225,7 @@
<parent link="canadarm2_link_1"/>
<child link="canadarm2_link_2"/>
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

<!-- joint 3 -->
Expand All @@ -234,45 +234,45 @@
<parent link="canadarm2_link_2"/>
<child link="canadarm2_link_3"/>
<axis xyz="0 1 0"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

<!-- joint 4 -->
<joint name="joint_canadarm2_4" type="revolute">
<origin rpy="0 0 0" xyz="-7.3435 -0.57517 0.004392"/>
<parent link="canadarm2_link_3"/>
<child link="canadarm2_link_4"/>
<axis xyz="0 1 0"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
</joint>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

<!-- joint 5 -->
<joint name="joint_canadarm2_5" type="revolute">
<origin rpy="0 0 0" xyz="0.004395 -0.57517 7.3435"/>
<parent link="canadarm2_link_4"/>
<child link="canadarm2_link_5"/>
<axis xyz="0 1 0"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
</joint>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

<!-- joint 6 -->
<joint name="joint_canadarm2_6" type="revolute">
<origin rpy="0 0 0" xyz="-0.28758 -0.3134 0.002192"/>
<parent link="canadarm2_link_5"/>
<child link="canadarm2_link_6"/>
<axis xyz="1 0 0"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
</joint>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

<!-- joint 7 -->
<joint name="joint_canadarm2_7" type="revolute">
<origin rpy="0 0 0" xyz="-0.31341 -0.002199 0.28759"/>
<parent link="canadarm2_link_6"/>
<child link="canadarm2_link_7"/>
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-3.1416" upper="3.1416" velocity="0.5"/>
</joint>
</xacro:macro>
<limit effort="10000.0" lower="-3.1416" upper="3.1416" velocity="1.0"/>
</joint>

</xacro:macro>

</robot>
22 changes: 11 additions & 11 deletions urdf/mobile_base_system.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<!-- MOBILE BASE SYSTEM -->
<xacro:macro name="mobile_base_system" params=" parent:='world' ">


<link name="root">
<inertial>
<origin xyz="0 0 0.0" rpy="0 0 0"/>
Expand Down Expand Up @@ -55,17 +55,17 @@
<link name="link_09_destiny"/>
<link name="link_14_s0_truss"/>

<!-- ************************* -->
<!-- Joints for common modules -->
<!-- ************************* -->

<!-- ************************* -->
<!-- Joints for common modules -->
<!-- ************************* -->

<joint name="joint_world" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="${parent}"/>
<child link="root"/>
</joint>

<!-- Joint for 02 Unity Node 1-->
<joint name="joint_02_unity" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
Expand All @@ -91,15 +91,15 @@

<!-- *********************************************** -->
<!-- Joint for Mobile base system w.r.t. to S0 Truss -->
<!-- *********************************************** -->
<!-- *********************************************** -->
<joint name="joint_mbs" type="prismatic">
<origin rpy="0 0 0" xyz="-2.8655 -5.17 -0.59547"/>
<axis xyz="1 0 0"/>
<parent link="link_14_s0_truss"/>
<child link="mobile_base_system"/>
<limit effort="1000.0" lower="-15.0" upper="42.0" velocity="0.5"/>
<limit effort="10000.0" lower="-15.0" upper="42.0" velocity="2.0"/>
</joint>
</xacro:macro>

</xacro:macro>

</robot>
Loading