Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix xacro warnings in Jade #251

Merged
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
4 changes: 2 additions & 2 deletions ur10_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

<!-- Load universal robot description format (URDF) -->
<group if="$(arg load_robot_description)">
<param unless="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur10_robot.urdf.xacro'" />
<param if="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur10_joint_limited_robot.urdf.xacro'" />
<param unless="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur10_robot.urdf.xacro'" />
<param if="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur10_joint_limited_robot.urdf.xacro'" />
</group>

<!-- The semantic description that corresponds to the URDF -->
Expand Down
4 changes: 2 additions & 2 deletions ur3_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

<!-- Load universal robot description format (URDF) -->
<group if="$(arg load_robot_description)">
<param unless="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur3_robot.urdf.xacro'" />
<param if="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro'" />
<param unless="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur3_robot.urdf.xacro'" />
<param if="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro'" />
</group>

<!-- The semantic description that corresponds to the URDF -->
Expand Down
4 changes: 2 additions & 2 deletions ur5_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

<!-- Load universal robot description format (URDF) -->
<group if="$(arg load_robot_description)">
<param unless="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur5_robot.urdf.xacro'" />
<param if="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro'" />
<param unless="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur5_robot.urdf.xacro'" />
<param if="$(arg limited)" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro'" />
</group>

<!-- The semantic description that corresponds to the URDF -->
Expand Down
4 changes: 2 additions & 2 deletions ur_description/launch/ur10_upload.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@
<launch>
<arg name="limited" default="false"/>

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur10_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur10_joint_limited_robot.urdf.xacro'" />
<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur10_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur10_joint_limited_robot.urdf.xacro'" />
</launch>
4 changes: 2 additions & 2 deletions ur_description/launch/ur3_upload.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@
<launch>
<arg name="limited" default="false"/>

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur3_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro'" />
<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur3_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro'" />
</launch>
4 changes: 2 additions & 2 deletions ur_description/launch/ur5_upload.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@
<launch>
<arg name="limited" default="false"/>

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur5_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro.py '$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro'" />
<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur5_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro'" />
</launch>
2 changes: 1 addition & 1 deletion ur_description/urdf/common.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<gazebo>
<plugin name="ros_control" filename="libgazebo_ros_control.so">
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="ur_arm_gazebo" params="prefix">
<!-- nothing to do here at the moment -->
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur.transmission.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="ur_arm_transmission" params="prefix">

Expand Down
64 changes: 31 additions & 33 deletions ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,61 +1,59 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<!--
Author: Kelsey Hawkins
Contributers: Jimmy Da Silva, Ajit Krisshna N L, Muhammad Asif Rana
Author: Kelsey Hawkins
Contributers: Jimmy Da Silva, Ajit Krisshna N L, Muhammad Asif Rana
-->

<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />

<property name="pi" value="3.14159265" />

<!-- Inertia parameters -->
<property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
<property name="shoulder_mass" value="7.778" />
<property name="upper_arm_mass" value="12.93" />
<property name="forearm_mass" value="3.87" />
<property name="wrist_1_mass" value="1.96" />
<property name="wrist_2_mass" value="1.96" />
<property name="wrist_3_mass" value="0.202" />
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="7.778" />
<xacro:property name="upper_arm_mass" value="12.93" />
<xacro:property name="forearm_mass" value="3.87" />
<xacro:property name="wrist_1_mass" value="1.96" />
<xacro:property name="wrist_2_mass" value="1.96" />
<xacro:property name="wrist_3_mass" value="0.202" />

<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<property name="shoulder_cog" value="0.00008 0.00244 -0.037" />
<property name="upper_arm_cog" value="0.00001 0.15061 0.38757" />
<property name="forearm_cog" value="-0.00012 0.06112 0.1984" />
<property name="wrist_1_cog" value="-0.00021 -0.00112 0.02269" />
<property name="wrist_2_cog" value="-0.00021 0.00112 0.002269" />
<property name="wrist_3_cog" value="0 -0.001156 -0.00149" />
<xacro:property name="shoulder_cog" value="0.00008 0.00244 -0.037" />
<xacro:property name="upper_arm_cog" value="0.00001 0.15061 0.38757" />
<xacro:property name="forearm_cog" value="-0.00012 0.06112 0.1984" />
<xacro:property name="wrist_1_cog" value="-0.00021 -0.00112 0.02269" />
<xacro:property name="wrist_2_cog" value="-0.00021 0.00112 0.002269" />
<xacro:property name="wrist_3_cog" value="0 -0.001156 -0.00149" />

<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<property name="ur10_d1" value="0.1273" />
<property name="ur10_a2" value="-0.612" />
<property name="ur10_a3" value="-0.5723" />
<property name="ur10_d4" value="0.163941" />
<property name="ur10_d5" value="0.1157" />
<property name="ur10_d6" value="0.0922" />
<xacro:property name="ur10_d1" value="0.1273" />
<xacro:property name="ur10_a2" value="-0.612" />
<xacro:property name="ur10_a3" value="-0.5723" />
<xacro:property name="ur10_d4" value="0.163941" />
<xacro:property name="ur10_d5" value="0.1157" />
<xacro:property name="ur10_d6" value="0.0922" />

<!-- Arbitrary offsets for shoulder/elbow joints -->
<property name="shoulder_offset" value="0.220941" /> <!-- measured from model -->
<property name="elbow_offset" value="-0.1719" /> <!-- measured from model -->
<xacro:property name="shoulder_offset" value="0.220941" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.1719" /> <!-- measured from model -->

<!-- link lengths used in model -->
<property name="shoulder_height" value="${ur10_d1}" />
<property name="upper_arm_length" value="${-ur10_a2}" />
<property name="forearm_length" value="${-ur10_a3}" />
<property name="wrist_1_length" value="${ur10_d4 - elbow_offset - shoulder_offset}" />
<property name="wrist_2_length" value="${ur10_d5}" />
<property name="wrist_3_length" value="${ur10_d6}" />
<xacro:property name="shoulder_height" value="${ur10_d1}" />
<xacro:property name="upper_arm_length" value="${-ur10_a2}" />
<xacro:property name="forearm_length" value="${-ur10_a3}" />
<xacro:property name="wrist_1_length" value="${ur10_d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${ur10_d5}" />
<xacro:property name="wrist_3_length" value="${ur10_d6}" />

<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
izz="${0.5 * mass * radius * radius}" />
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur10_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur10" >

<!-- common stuff -->
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur10_robot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur10" >

<!-- common stuff -->
Expand Down
60 changes: 29 additions & 31 deletions ur_description/urdf/ur3.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<!--
Author: Felix Messmer
Expand All @@ -8,53 +8,51 @@
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />

<property name="pi" value="3.14159265" />

<!-- Inertia parameters -->
<property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
<property name="shoulder_mass" value="2.0" />
<property name="upper_arm_mass" value="3.42" />
<property name="forearm_mass" value="1.26" />
<property name="wrist_1_mass" value="0.8" />
<property name="wrist_2_mass" value="0.8" />
<property name="wrist_3_mass" value="0.35" />
<xacro:property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="2.0" />
<xacro:property name="upper_arm_mass" value="3.42" />
<xacro:property name="forearm_mass" value="1.26" />
<xacro:property name="wrist_1_mass" value="0.8" />
<xacro:property name="wrist_2_mass" value="0.8" />
<xacro:property name="wrist_3_mass" value="0.35" />

<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<property name="shoulder_cog" value="0.0 -0.02 0.0" />
<property name="upper_arm_cog" value="0.13 0.0 0.1157" />
<property name="forearm_cog" value="0.05 0.0 0.0238" />
<property name="wrist_1_cog" value="0.0 0.0 0.01" />
<property name="wrist_2_cog" value="0.0 0.0 0.01" />
<property name="wrist_3_cog" value="0.0 0.0 -0.02" />
<xacro:property name="shoulder_cog" value="0.0 -0.02 0.0" />
<xacro:property name="upper_arm_cog" value="0.13 0.0 0.1157" />
<xacro:property name="forearm_cog" value="0.05 0.0 0.0238" />
<xacro:property name="wrist_1_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_2_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_3_cog" value="0.0 0.0 -0.02" />

<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<property name="ur3_d1" value="0.1519" />
<property name="ur3_a2" value="-0.24365" />
<property name="ur3_a3" value="-0.21325" />
<property name="ur3_d4" value="0.11235" />
<property name="ur3_d5" value="0.08535" />
<property name="ur3_d6" value="0.0819" />
<xacro:property name="ur3_d1" value="0.1519" />
<xacro:property name="ur3_a2" value="-0.24365" />
<xacro:property name="ur3_a3" value="-0.21325" />
<xacro:property name="ur3_d4" value="0.11235" />
<xacro:property name="ur3_d5" value="0.08535" />
<xacro:property name="ur3_d6" value="0.0819" />

<!-- Arbitrary offsets for shoulder/elbow joints -->
<property name="shoulder_offset" value="0.1198" /> <!-- measured from model -->
<property name="elbow_offset" value="-0.0925" /> <!-- measured from model -->
<xacro:property name="shoulder_offset" value="0.1198" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.0925" /> <!-- measured from model -->

<!-- link lengths used in model -->
<property name="shoulder_height" value="${ur3_d1}" />
<property name="upper_arm_length" value="${-ur3_a2}" />
<property name="forearm_length" value="${-ur3_a3}" />
<property name="wrist_1_length" value="${ur3_d4 - elbow_offset - shoulder_offset}" />
<property name="wrist_2_length" value="${ur3_d5}" />
<property name="wrist_3_length" value="${ur3_d6}" />
<xacro:property name="shoulder_height" value="${ur3_d1}" />
<xacro:property name="upper_arm_length" value="${-ur3_a2}" />
<xacro:property name="forearm_length" value="${-ur3_a3}" />
<xacro:property name="wrist_1_length" value="${ur3_d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${ur3_d5}" />
<xacro:property name="wrist_3_length" value="${ur3_d6}" />

<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<insert_block name="origin" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
izz="${0.5 * mass * radius * radius}" />
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur3_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur3" >

<!-- common stuff -->
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur3_robot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur3" >

<!-- common stuff -->
Expand Down
Loading