Skip to content

Commit

Permalink
description: they're joint limits.
Browse files Browse the repository at this point in the history
Not joints limits.
  • Loading branch information
gavanderhoorn committed Jun 18, 2020
1 parent ba5ac32 commit c86d015
Show file tree
Hide file tree
Showing 11 changed files with 15 additions and 15 deletions.
4 changes: 2 additions & 2 deletions ur_description/launch/load_ur.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur parameters files -->
<arg name="joints_limits_params" doc="YAML file containing the joints limits values"/>
<arg name="joint_limit_params" doc="YAML file containing the joint limit values"/>
<arg name="kinematics_params" doc="YAML file containing the robot's kinematic parameters. These will be different for each robot as they contain the robot's calibration."/>
<arg name="physical_params" doc="YAML file containing the phycical parameters of the robots"/>
<arg name="visual_params" doc="YAML file containing the visual model of the robots"/>
Expand Down Expand Up @@ -29,7 +29,7 @@
to load it onto the parameter server.
-->
<param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur.xacro'
joints_limits_params:=$(arg joints_limits_params)
joint_limit_params:=$(arg joint_limit_params)
kinematics_params:=$(arg kinematics_params)
physical_params:=$(arg physical_params)
visual_params:=$(arg visual_params)
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur10.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur10 parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur10/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur10/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur10/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur10/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur10/visual_parameters.yaml"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur10e.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur10e parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur10e/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur10e/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur10e/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur10e/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur10e/visual_parameters.yaml"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur16e.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur10e parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur16e/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur16e/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur16e/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur16e/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur16e/visual_parameters.yaml"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur3.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur3 parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur3/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur3/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur3/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur3/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur3/visual_parameters.yaml"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur3e.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur3e parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur3e/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur3e/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur3e/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur3e/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur3e/visual_parameters.yaml"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur5.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur5 parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur5/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur5/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur5/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur5/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur5/visual_parameters.yaml"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/launch/load_ur5e.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<!--ur5e parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur5e/joint_limits.yaml"/>
<arg name="joint_limit_params" default="$(find ur_description)/config/ur5e/joint_limits.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur5e/default_kinematics.yaml"/>
<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"/>
Expand Down
4 changes: 2 additions & 2 deletions ur_description/urdf/inc/ur_common.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
This macro is NOT part of the public API of the ur_description pkg,
and as such should be considered to be for internal use only.
-->
<xacro:macro name="read_model_data" params="joints_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file">
<xacro:property name="__limits" value="${joints_limits_parameters_file['limits']}"/>
<xacro:macro name="read_model_data" params="joint_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file">
<xacro:property name="__limits" value="${joint_limits_parameters_file['limits']}"/>
<xacro:property name="__dh_parameters" value="${physical_parameters_file['dh_parameters']}"/>
<xacro:property name="__offsets" value="${physical_parameters_file['offsets']}"/>
<xacro:property name="__inertia_parameters" value="${physical_parameters_file['inertia_parameters']}" />
Expand Down
4 changes: 2 additions & 2 deletions ur_description/urdf/ur.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>

<!-- parameters -->
<xacro:arg name="joints_limits_params" default=""/>
<xacro:arg name="joint_limit_params" default=""/>
<xacro:arg name="kinematics_params" default=""/>
<xacro:arg name="physical_params" default=""/>
<xacro:arg name="visual_params" default=""/>
Expand All @@ -22,7 +22,7 @@
<!-- arm -->
<xacro:ur_robot
prefix=""
joints_limits_parameters_file="${load_yaml('$(arg joints_limits_params)')}"
joint_limits_parameters_file="${load_yaml('$(arg joint_limit_params)')}"
kinematics_parameters_file="${load_yaml('$(arg kinematics_params)')}"
physical_parameters_file="${load_yaml('$(arg physical_params)')}"
visual_parameters_file="${load_yaml('$(arg visual_params)')}"
Expand Down
4 changes: 2 additions & 2 deletions ur_description/urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@

<xacro:macro name="ur_robot" params="
prefix
joints_limits_parameters_file
joint_limits_parameters_file
kinematics_parameters_file
physical_parameters_file
visual_parameters_file
Expand All @@ -67,7 +67,7 @@
>
<!-- Load configuration data from the provided .yaml files -->
<xacro:read_model_data
joints_limits_parameters_file="${joints_limits_parameters_file}"
joint_limits_parameters_file="${joint_limits_parameters_file}"
kinematics_parameters_file="${kinematics_parameters_file}"
physical_parameters_file="${physical_parameters_file}"
visual_parameters_file="${visual_parameters_file}"/>
Expand Down

0 comments on commit c86d015

Please sign in to comment.