Skip to content

Commit

Permalink
Add acceleration limit parameter (#3)
Browse files Browse the repository at this point in the history
* Add ros2 control hardware parameter acceleration limit and pass
parameter from top level

* Fix xacro logic for acc limit
  • Loading branch information
eeberhard authored Dec 22, 2021
1 parent 04868a8 commit 4568bf5
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 2 deletions.
3 changes: 2 additions & 1 deletion ur_description/urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
use_fake_hardware:=false fake_sensor_commands:=false
use_tcp_fts_sensor:=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)}
robot_ip">
robot_ip acceleration_limit">

<ros2_control name="${name}" type="system">
<hardware>
Expand All @@ -17,6 +17,7 @@
<xacro:unless value="${use_fake_hardware}">
<plugin>robot_interface/universal_robots/UniversalRobotsInterface</plugin>
<param name="robot_ip">${robot_ip}</param>
<param name="acceleration_limit">${acceleration_limit}</param>
</xacro:unless>
</hardware>
<joint name="${prefix}shoulder_pan_joint">
Expand Down
2 changes: 2 additions & 0 deletions ur_description/urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<xacro:arg name="prefix" default="ur5_" />
<xacro:arg name="connected_to" default="" />
<xacro:arg name="robot_ip" default="" />
<xacro:arg name="acceleration_limit" default="30.0" />
<xacro:arg name="transmission_hw_interface" default=""/>
<xacro:arg name="safety_limits" default="false"/>
<xacro:arg name="safety_pos_margin" default="0.15"/>
Expand All @@ -28,6 +29,7 @@
prefix="$(arg prefix)"
robot_ip="$(arg robot_ip)"
connected_to="$(arg connected_to)"
acceleration_limit="$(arg acceleration_limit)"
joint_limits_parameters_file="${model_config_path}/joint_limits.yaml"
kinematics_parameters_file="${model_config_path}/default_kinematics.yaml"
physical_parameters_file="${model_config_path}/physical_parameters.yaml"
Expand Down
4 changes: 3 additions & 1 deletion ur_description/urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
prefix
connected_to:=''
robot_ip
acceleration_limit
joint_limits_parameters_file
kinematics_parameters_file
physical_parameters_file
Expand Down Expand Up @@ -86,7 +87,8 @@
use_tcp_fts_sensor="$(arg use_tcp_fts_sensor)"
initial_positions="${initial_positions}"
fake_sensor_commands="$(arg fake_sensor_commands)"
robot_ip="$(arg robot_ip)"/>
robot_ip="$(arg robot_ip)"
acceleration_limit="$(arg acceleration_limit)"/>

<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
Expand Down

0 comments on commit 4568bf5

Please sign in to comment.