]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
urdf: Rotate manipulator by 180°
authorErik Andresen <erik@vontaene.de>
Sat, 16 May 2020 11:48:46 +0000 (13:48 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 16 May 2020 11:48:46 +0000 (13:48 +0200)
launch/wild_thumper.launch
scripts/wt_node.py
urdf/wild_thumper_with_manipulator.urdf.xacro

index ec21d0b80b5ff615e116e5294f2851c7ee8ca1d2..e6b426cb88290f11831b36b40b8f35257b80f7a3 100644 (file)
@@ -51,6 +51,7 @@
                <param name="yaw_offset" value="0.0"/>
                <param name="zero_altitude" value="true"/>
                <param name="broadcast_utm_transform" value="true"/>
+               <param name="transform_timeout" value="0.2"/>
 
                <remap from="/imu/data" to="imu"/>
                <remap from="/gps/fix" to="fix" />
index 2969d613c7f11a06e81ac6efe17d740f059cf80f..bffabce5d178bb9fec2954587565c3363fa2fea3 100755 (executable)
@@ -58,7 +58,6 @@ class WTBase:
                sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
                reset_val = self.get_reset()
                rospy.loginfo("Reset Status: 0x%x" % reset_val)
-               ir_count = 0
                sonar_count = 0
                i2c_write_reg(0x50, 0xA4, struct.pack("B", 1)) # enable Watchdog
                while not rospy.is_shutdown():
@@ -69,13 +68,6 @@ class WTBase:
                        self.get_odom()
                        self.get_power()
 
-                       if ir_count == 0:
-                               self.get_dist_left()
-                               ir_count+=1
-                       else:
-                               self.get_dist_right()
-                               ir_count=0
-
                        if sonar_count == 0:
                                self.get_dist_forward_left()
                                self.update_dist_backward()
index 2462a8c0431ff6d48f1ec6afa5fb730a18a32a64..1451f50962551526d8ad73ed607e65d56c69e5d5 100644 (file)
@@ -7,6 +7,6 @@
        <joint name="open_manipulator_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="open_manipulator_base"/>
-               <origin xyz="-0.075 0.0 0.045" rpy="0 0 ${PI}"/>
+               <origin xyz="-0.075 0.0 0.045" rpy="0 0 0"/>
        </joint>
 </robot>