<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="crane">
<xacro:arg name="ignition" default="false"/>
+ <xacro:arg name="payload" default="payload.xacro"/>
<xacro:include filename="material.xacro"/>
<xacro:include filename="base.xacro"/>
<limit lower="${-base_height}" upper="0" effort="100.0" velocity="100.0"/>
</xacro:hook>
+ <xacro:include filename="$(arg payload)"/>
+
<xacro:include filename="ros2_control.xacro"/>
<xacro:include filename="gazebo_control.xacro"/>
</robot>
--- /dev/null
+<?xml version="1.0" ?>
+<!--******************************************************************************
+ Crane Description
+ Payload Description
+ Copyright (C) 2024 Walter Fetter Lages <w.fetter@ieee.org>
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Geneal Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see
+ <http://www.gnu.org/licenses/>.
+
+*******************************************************************************-->
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+ <xacro:arg name="ignition" default="false"/>
+
+ <xacro:include filename="prismatic.xacro"/>
+
+ <xacro:property name="payload_radius" value="5e-2"/>
+ <xacro:property name="payload_length" value="10e-2"/>
+
+ <xacro:property name="payload_mass" value="5"/>
+
+ <xacro:cylinder name="payload"
+ length="${payload_length}"
+ radius="${payload_radius}"
+ mass="${payload_mass}"
+ parent="hook_link">
+ <origin xyz="0 0 ${-payload_length/2}"/>
+ </xacro:cylinder>
+</robot>
</geometry>
</collision>
<inertial>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <mass value="${mass}" />
+ <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+ <mass value="${mass}"/>
<inertia ixx="${mass/12*(length*length+height*height)}"
ixy="0.0" ixz="0.0"
iyy="${mass/12*(width*width+height*height)}"
</geometry>
</collision>
<inertial>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <mass value="${mass}" />
+ <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+ <mass value="${mass}"/>
<inertia ixx="${mass/12*(length*length+height*height)}"
ixy="0.0" ixz="0.0"
iyy="${mass/12*(width*width+height*height)}"
<material>Gazebo/Grey</material>
</gazebo>
</xacro:macro>
+
+ <xacro:macro name="cylinder" params="name length radius mass parent *origin">
+ <link name="${name}_link">
+ <visual>
+ <geometry>
+ <cylinder length="${length}" radius="${radius}"/>
+ </geometry>
+ <material name="red">
+ <cylinder rgba="0.7 0.0 0.0 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box length="${length}" radius="${radius}"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+ <mass value="${mass}"/>
+ <inertia ixx="${mass/12*(3*radius*radius+length*length)}"
+ ixy="0.0" ixz="0.0"
+ iyy="${mass/12*(3*radius*radius+length*length)}"
+ iyz="0.0"
+ izz="${mass/12*radius*radius}"/>
+ </inertial>
+ </link>
+
+ <joint name="${name}_joint" type="fixed">
+ <xacro:insert_block name="origin"/>
+ <parent link="${parent}" />
+ <child link="${name}_link" />
+ </joint>
+
+ <gazebo reference="${name}_link">
+ <material>Gazebo/Red</material>
+ </gazebo>
+ </xacro:macro>
</robot>