From: Erik Andresen <erik@vontaene.de>
Date: Sat, 16 May 2020 11:48:46 +0000 (+0200)
Subject: urdf: Rotate manipulator by 180°
X-Git-Url: https://defiant.homedns.org/gitweb/?a=commitdiff_plain;h=cfa8a79b92972e17fb955c79d5c6337ec49a4538;p=ros_wild_thumper.git

urdf: Rotate manipulator by 180°
---

diff --git a/launch/wild_thumper.launch b/launch/wild_thumper.launch
index ec21d0b..e6b426c 100644
--- a/launch/wild_thumper.launch
+++ b/launch/wild_thumper.launch
@@ -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" />
diff --git a/scripts/wt_node.py b/scripts/wt_node.py
index 2969d61..bffabce 100755
--- a/scripts/wt_node.py
+++ b/scripts/wt_node.py
@@ -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()
diff --git a/urdf/wild_thumper_with_manipulator.urdf.xacro b/urdf/wild_thumper_with_manipulator.urdf.xacro
index 2462a8c..1451f50 100644
--- a/urdf/wild_thumper_with_manipulator.urdf.xacro
+++ b/urdf/wild_thumper_with_manipulator.urdf.xacro
@@ -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>