]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
configuration with manipulator
authorErik Andresen <erik@vontaene.de>
Thu, 2 Apr 2020 05:22:51 +0000 (07:22 +0200)
committerErik Andresen <erik@vontaene.de>
Thu, 2 Apr 2020 05:22:51 +0000 (07:22 +0200)
launch/wild_thumper.launch
urdf/wild_thumper_with_manipulator.urdf.xacro [new file with mode: 0644]

index 834a5881c80f59bce59aff9befcfd9c5027a0c7e..ec21d0b80b5ff615e116e5294f2851c7ee8ca1d2 100644 (file)
@@ -6,12 +6,17 @@
 
        <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
 
 
        <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 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="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"/>
 
        <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
                <rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
@@ -22,7 +27,7 @@
                <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
        </node>
 
                <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>
 
                <param name="uid" value="6DdNSn"/>
        </node>
 
diff --git a/urdf/wild_thumper_with_manipulator.urdf.xacro b/urdf/wild_thumper_with_manipulator.urdf.xacro
new file mode 100644 (file)
index 0000000..3144258
--- /dev/null
@@ -0,0 +1,12 @@
+<?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>