Skip to content
Closed
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
66 changes: 66 additions & 0 deletions urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,17 @@
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<xacro:if value="${sim_ignition}">
<!-- initial PID values for the IgnitionSystem and simulation -->
<param name="p_vel">4000.0</param>
<param name="i_vel">250.0</param>
<param name="d_vel">1.0</param>
<param name="iMax_vel">15.0</param>
<param name="iMin_vel">-15.0</param>
<param name="cmdMax_vel">150.0</param>
<param name="cmdMin_vel">-150.0</param>
<param name="cmdOffset_vel">0.0</param>
</xacro:if>
</joint>
<joint name="${prefix}shoulder_lift_joint">
<command_interface name="position">
Expand All @@ -91,6 +102,17 @@
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<xacro:if value="${sim_ignition}">
<!-- initial PID values for the IgnitionSystem and simulation -->
<param name="p_vel">100000.0</param>
<param name="i_vel">1600.0</param>
<param name="d_vel">2.5</param>
<param name="iMax_vel">45.0</param>
<param name="iMin_vel">-45.0</param>
<param name="cmdMax_vel">150.0</param>
<param name="cmdMin_vel">-150.0</param>
<param name="cmdOffset_vel">0.0</param>
</xacro:if>
</joint>
<joint name="${prefix}elbow_joint">
<command_interface name="position">
Expand All @@ -107,6 +129,17 @@
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<xacro:if value="${sim_ignition}">
<!-- initial PID values for the IgnitionSystem and simulation -->
<param name="p_vel">10000.0</param>
<param name="i_vel">450.0</param>
<param name="d_vel">2.0</param>
<param name="iMax_vel">30.0</param>
<param name="iMin_vel">-30.0</param>
<param name="cmdMax_vel">150.0</param>
<param name="cmdMin_vel">-150.0</param>
<param name="cmdOffset_vel">0.0</param>
</xacro:if>
</joint>
<joint name="${prefix}wrist_1_joint">
<command_interface name="position">
Expand All @@ -123,6 +156,17 @@
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<xacro:if value="${sim_ignition}">
<!-- initial PID values for the IgnitionSystem and simulation -->
<param name="p_vel">3000.0</param>
<param name="i_vel">175.0</param>
<param name="d_vel">0.5</param>
<param name="iMax_vel">7.0</param>
<param name="iMin_vel">-7.0</param>
<param name="cmdMax_vel">28.0</param>
<param name="cmdMin_vel">-28.0</param>
<param name="cmdOffset_vel">0.0</param>
</xacro:if>
</joint>
<joint name="${prefix}wrist_2_joint">
<command_interface name="position">
Expand All @@ -139,6 +183,17 @@
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<xacro:if value="${sim_ignition}">
<!-- initial PID values for the IgnitionSystem and simulation -->
<param name="p_vel">2500.0</param>
<param name="i_vel">150.0</param>
<param name="d_vel">0.3</param>
<param name="iMax_vel">6.0</param>
<param name="iMin_vel">-6.0</param>
<param name="cmdMax_vel">28.0</param>
<param name="cmdMin_vel">-28.0</param>
<param name="cmdOffset_vel">0.0</param>
</xacro:if>
</joint>
<joint name="${prefix}wrist_3_joint">
<command_interface name="position">
Expand All @@ -155,6 +210,17 @@
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<xacro:if value="${sim_ignition}">
<!-- initial PID values for the IgnitionSystem and simulation -->
<param name="p_vel">2000.0</param>
<param name="i_vel">10.0</param>
<param name="d_vel">0.2</param>
<param name="iMax_vel">5.0</param>
<param name="iMin_vel">-5.0</param>
<param name="cmdMax_vel">28.0</param>
<param name="cmdMin_vel">-28.0</param>
<param name="cmdOffset_vel">0.0</param>
</xacro:if>
</joint>

<xacro:unless value="${sim_gazebo or sim_ignition}">
Expand Down
15 changes: 8 additions & 7 deletions urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@
fake_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
force_abs_paths:=false
headless_mode:=false
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
use_tool_communication:=false
Expand All @@ -96,7 +97,7 @@
kinematics_parameters_file="${kinematics_parameters_file}"
physical_parameters_file="${physical_parameters_file}"
visual_parameters_file="${visual_parameters_file}"
force_abs_paths="${sim_gazebo or sim_ignition}"/>
force_abs_paths="${force_abs_paths}"/>


<!-- ros2 control include -->
Expand Down Expand Up @@ -288,7 +289,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_pan_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_pan_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="21.75" friction="3.48"/>
</joint>
<joint name="${prefix}shoulder_lift_joint" type="revolute">
<parent link="${prefix}shoulder_link" />
Expand All @@ -300,7 +301,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_lift_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_lift_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="21.75" friction="3.48"/>
</joint>
<joint name="${prefix}elbow_joint" type="revolute">
<parent link="${prefix}upper_arm_link" />
Expand All @@ -312,7 +313,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${elbow_joint_lower_limit + safety_pos_margin}" soft_upper_limit="${elbow_joint_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="21.75" friction="3.48"/>
</joint>
<joint name="${prefix}wrist_1_joint" type="revolute">
<parent link="${prefix}forearm_link" />
Expand All @@ -324,7 +325,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_1_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_1_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="3.0" friction="0.48"/>
</joint>
<joint name="${prefix}wrist_2_joint" type="revolute">
<parent link="${prefix}wrist_1_link" />
Expand All @@ -336,7 +337,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_2_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_2_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="3.0" friction="0.48"/>
</joint>
<joint name="${prefix}wrist_3_joint" type="revolute">
<parent link="${prefix}wrist_2_link" />
Expand All @@ -348,7 +349,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_3_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_3_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="3.0" friction="0.48"/>
</joint>

<link name="${prefix}ft_frame"/>
Expand Down