<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
+ <!--
<param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
+ -->
+ <param name="robot_description" command="$(find xacro)/xacro.py $(find wt_open_manipulator)/urdf/wild_thumper_with_manipulator.urdf.xacro use_nominal_extrinsics:=false"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" value="20.0" />
</node>
- <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen"/>
+ <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen">
+ <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro" />
+ </node>
<node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
<rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
<param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
</node>
- <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen" if="$(arg use_imu)">
+ <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen" respawn="true" if="$(arg use_imu)">
<param name="uid" value="6DdNSn"/>
</node>
--- /dev/null
+<?xml version="1.0"?>
+<robot name="wild_thumper_with_manipulator" xmlns:xacro="http://ros.org/wiki/xacro">
+ <xacro:property name="PI" value="3.1415926535897931" />
+ <xacro:include filename="$(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
+ <xacro:include filename="$(find wt_open_manipulator)/urdf/open_manipulator.urdf.xacro"/>
+
+ <joint name="open_manipulator_joint" type="fixed">
+ <parent link="mounting_plate"/>
+ <child link="link1"/>
+ <origin xyz="-0.075 0.0 0.045" rpy="0 0 ${PI}"/>
+ </joint>
+</robot>