ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
It looks like http://wiki.ros.org/urdf/Tutorials/Using%20urdf%20with%20robot_state_publisher#Launch_File is outdated but the basic approach is valid- TODO fix it.
It should look like this:
<?xml version="1.0"?>
<launch>
<arg name="model" default="model.urdf"/>
<param name="robot_description" textfile="$(arg model)" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
</launch>
And the urdf I had to add an inertia-less base_link:
<?xml version="1.0"?>
<robot name="r2d2">
<link name="base_link">
</link>
<joint name="basec" type="fixed">
<origin xyz="0 0 0" />
<parent link="base_link"/>
<child link="main_axis"/>
</joint>
<link name="main_axis">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.01" length=".5" />
</geometry>
<material name="gray">
<color rgba=".2 .2 .2 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.01" length=".5" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<link name="leg1">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="leg1connect" type="fixed">
<origin xyz="0 .30 0" />
<parent link="main_axis"/>
<child link="leg1"/>
</joint>
<link name="leg2">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="leg2connect" type="fixed">
<origin xyz="0 -.30 0" />
<parent link="main_axis"/>
<child link="leg2"/>
</joint>
<link name="body">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -0.2" />
<geometry>
<cylinder radius=".20" length=".6"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0 0 0.2" />
<geometry>
<cylinder radius=".20" length=".6"/>
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="tilt" type="revolute">
<parent link="main_axis"/>
<child link="body"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit upper="0" lower="-.5" effort="10" velocity="10" />
</joint>
<link name="head">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<geometry>
<sphere radius=".4" />
</geometry>
<material name="white" />
</visual>
<collision>
<origin/>
<geometry>
<sphere radius=".4" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="swivel" type="continuous">
<origin xyz="0 0 0.1" />
<axis xyz="0 0 1" />
<parent link="body"/>
<child link="head"/>
</joint>
<link name="rod">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.1" />
<geometry>
<cylinder radius=".02" length=".2" />
</geometry>
<material name="gray" />
</visual>
<collision>
<origin/>
<geometry>
<cylinder radius=".02" length=".2" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="periscope" type="prismatic">
<origin xyz=".12 0 .15" />
<axis xyz="0 0 1" />
<limit upper="0" lower="-.5" effort="10" velocity="10" />
<parent link="head"/>
<child link="rod"/>
</joint>
<link name="box">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<geometry>
<box size=".05 .05 .05" />
</geometry>
<material name="blue" >
<color rgba="0 0 1 1" />
</material>
</visual>
<collision>
<origin/>
<geometry>
<box size=".05 .05 .05" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="boxconnect" type="fixed">
<origin xyz="0 0 0" />
<parent link="rod"/>
<child link="box"/>
</joint>
</robot>
2 | No.2 Revision |
It looks like http://wiki.ros.org/urdf/Tutorials/Using%20urdf%20with%20robot_state_publisher#Launch_File is outdated but the basic approach is valid- TODO fix it.
It should look like this:
<?xml version="1.0"?>
<launch>
<arg name="model" default="model.urdf"/>
<param name="robot_description" textfile="$(arg model)" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
>
<param name="use_gui" value="true" />
</node>
</launch>
And the urdf I had to add an inertia-less base_link:
<?xml version="1.0"?>
<robot name="r2d2">
<link name="base_link">
</link>
<joint name="basec" type="fixed">
<origin xyz="0 0 0" />
<parent link="base_link"/>
<child link="main_axis"/>
</joint>
<link name="main_axis">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.01" length=".5" />
</geometry>
<material name="gray">
<color rgba=".2 .2 .2 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.01" length=".5" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<link name="leg1">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="leg1connect" type="fixed">
<origin xyz="0 .30 0" />
<parent link="main_axis"/>
<child link="leg1"/>
</joint>
<link name="leg2">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="leg2connect" type="fixed">
<origin xyz="0 -.30 0" />
<parent link="main_axis"/>
<child link="leg2"/>
</joint>
<link name="body">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -0.2" />
<geometry>
<cylinder radius=".20" length=".6"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0 0 0.2" />
<geometry>
<cylinder radius=".20" length=".6"/>
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="tilt" type="revolute">
<parent link="main_axis"/>
<child link="body"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit upper="0" lower="-.5" effort="10" velocity="10" />
</joint>
<link name="head">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<geometry>
<sphere radius=".4" />
</geometry>
<material name="white" />
</visual>
<collision>
<origin/>
<geometry>
<sphere radius=".4" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="swivel" type="continuous">
<origin xyz="0 0 0.1" />
<axis xyz="0 0 1" />
<parent link="body"/>
<child link="head"/>
</joint>
<link name="rod">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.1" />
<geometry>
<cylinder radius=".02" length=".2" />
</geometry>
<material name="gray" />
</visual>
<collision>
<origin/>
<geometry>
<cylinder radius=".02" length=".2" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="periscope" type="prismatic">
<origin xyz=".12 0 .15" />
<axis xyz="0 0 1" />
<limit upper="0" lower="-.5" effort="10" velocity="10" />
<parent link="head"/>
<child link="rod"/>
</joint>
<link name="box">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<geometry>
<box size=".05 .05 .05" />
</geometry>
<material name="blue" >
<color rgba="0 0 1 1" />
</material>
</visual>
<collision>
<origin/>
<geometry>
<box size=".05 .05 .05" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="boxconnect" type="fixed">
<origin xyz="0 0 0" />
<parent link="rod"/>
<child link="box"/>
</joint>
</robot>
3 | No.3 Revision |
It looks like http://wiki.ros.org/urdf/Tutorials/Using%20urdf%20with%20robot_state_publisher#Launch_File is outdated but the basic approach is valid- TODO fix it.
It should look like this:
<?xml version="1.0"?>
<launch>
<arg name="model" default="model.urdf"/>
default="$(find r2d2)/model.urdf"/>
<param name="robot_description" textfile="$(arg model)" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >
<param name="use_gui" value="true" />
</node>
</launch>
And the urdf I had to add an inertia-less base_link:base_link (and made the file extension .urdf instead of .xml):
<?xml version="1.0"?>
<robot name="r2d2">
<link name="base_link">
</link>
<joint name="basec" type="fixed">
<origin xyz="0 0 0" />
<parent link="base_link"/>
<child link="main_axis"/>
</joint>
<link name="main_axis">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.01" length=".5" />
</geometry>
<material name="gray">
<color rgba=".2 .2 .2 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.01" length=".5" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<link name="leg1">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="leg1connect" type="fixed">
<origin xyz="0 .30 0" />
<parent link="main_axis"/>
<child link="leg1"/>
</joint>
<link name="leg2">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -.3" />
<geometry>
<box size=".20 .10 .8" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="leg2connect" type="fixed">
<origin xyz="0 -.30 0" />
<parent link="main_axis"/>
<child link="leg2"/>
</joint>
<link name="body">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -0.2" />
<geometry>
<cylinder radius=".20" length=".6"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0 0 0.2" />
<geometry>
<cylinder radius=".20" length=".6"/>
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="tilt" type="revolute">
<parent link="main_axis"/>
<child link="body"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit upper="0" lower="-.5" effort="10" velocity="10" />
</joint>
<link name="head">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<geometry>
<sphere radius=".4" />
</geometry>
<material name="white" />
</visual>
<collision>
<origin/>
<geometry>
<sphere radius=".4" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="swivel" type="continuous">
<origin xyz="0 0 0.1" />
<axis xyz="0 0 1" />
<parent link="body"/>
<child link="head"/>
</joint>
<link name="rod">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<origin xyz="0 0 -.1" />
<geometry>
<cylinder radius=".02" length=".2" />
</geometry>
<material name="gray" />
</visual>
<collision>
<origin/>
<geometry>
<cylinder radius=".02" length=".2" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="periscope" type="prismatic">
<origin xyz=".12 0 .15" />
<axis xyz="0 0 1" />
<limit upper="0" lower="-.5" effort="10" velocity="10" />
<parent link="head"/>
<child link="rod"/>
</joint>
<link name="box">
<inertial>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
<origin/>
</inertial>
<visual>
<geometry>
<box size=".05 .05 .05" />
</geometry>
<material name="blue" >
<color rgba="0 0 1 1" />
</material>
</visual>
<collision>
<origin/>
<geometry>
<box size=".05 .05 .05" />
</geometry>
<contact_coefficients mu="0" kp="1000.0" kd="1.0"/>
</collision>
</link>
<joint name="boxconnect" type="fixed">
<origin xyz="0 0 0" />
<parent link="rod"/>
<child link="box"/>
</joint>
</robot>