]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
rollover protection: replace handicap with reverse motor
[ros_wild_thumper.git] / scripts / wt_node.py
index 7fdf0444aead981ff55cedb43609cc122f75e001..3d3adefb058a7d15d1bd70b6352004f187ecf018 100755 (executable)
@@ -14,6 +14,8 @@ from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
 from sensor_msgs.msg import Imu, Range
 from wild_thumper.msg import LedStripe
+from dynamic_reconfigure.server import Server
+from wild_thumper.cfg import WildThumperConfig
 
 WHEEL_DIST = 0.248
 
@@ -55,6 +57,7 @@ class MoveBase:
                        self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                else:
                        self.tf_broadcaster = None
+               self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf)
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
                self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16)
@@ -62,12 +65,14 @@ class MoveBase:
                self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
                self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
                self.cmd_vel = None
+               self.bMotorManual = False
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
-               self.handicap_last = (-1, -1)
+               i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
                self.pStripe = LPD8806(1, 0, 12)
                rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
                rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
+               rospy.Subscriber("imu", Imu, self.imuReceived)
                self.run()
        
        def run(self):
@@ -77,8 +82,9 @@ class MoveBase:
                rospy.loginfo("Reset Status: 0x%x" % reset_val)
                i = 0
                while not rospy.is_shutdown():
+                       rospy.logdebug("Loop alive")
                        #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
-                       self.get_tle_err()
+                       self.get_motor_err()
                        self.get_odom()
                        self.get_voltage()
                        if i % 2:
@@ -93,6 +99,32 @@ class MoveBase:
                                self.cmd_vel = None
                        rate.sleep()
 
+       def execute_dyn_reconf(self, config, level):
+               self.bClipRangeSensor = config["range_sensor_clip"]
+               self.range_sensor_max = config["range_sensor_max"]
+               self.odom_covar_xy = config["odom_covar_xy"]
+               self.odom_covar_angle = config["odom_covar_angle"]
+               self.rollover_protect = config["rollover_protect"]
+               self.rollover_protect_limit = config["rollover_protect_limit"]
+               self.rollover_protect_pwm = config["rollover_protect_pwm"]
+
+               return config
+
+       def imuReceived(self, msg):
+               if self.rollover_protect:
+                       (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
+                       if pitch > self.rollover_protect_limit*pi/180:
+                               self.bMotorManual = True
+                               i2c_write_reg(0x50, 0x3, struct.pack(">h", self.rollover_protect_pwm))
+                               i2c_write_reg(0x50, 0x7, struct.pack(">h", self.rollover_protect_pwm))
+                       elif pitch < -self.rollover_protect_limit*pi/180:
+                               self.bMotorManual = True
+                               i2c_write_reg(0x50, 0x1, struct.pack(">h", -self.rollover_protect_pwm))
+                               i2c_write_reg(0x50, 0x5, struct.pack(">h", -self.rollover_protect_pwm))
+                       elif self.bMotorManual:
+                               i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
+                               self.bMotorManual = False
+
        def get_reset(self):
                reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
 
@@ -121,7 +153,7 @@ class MoveBase:
                return reset
 
 
-       def get_tle_err(self):
+       def get_motor_err(self):
                err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
                
                msg = DiagnosticArray()
@@ -131,10 +163,16 @@ class MoveBase:
                stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
                stat.message = "0x%02x" % err
 
-               stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
-               stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
-               stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
-               stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
+               # Diag
+               stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
+               stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
+               stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
+               stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
+               # Stall
+               stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
+               stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
+               stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
+               stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
 
                msg.status.append(stat)
                self.pub_diag.publish(msg)
@@ -177,24 +215,19 @@ class MoveBase:
                odom.pose.pose.orientation.y = odom_quat[1]
                odom.pose.pose.orientation.z = odom_quat[2]
                odom.pose.pose.orientation.w = odom_quat[3]
-               odom.pose.covariance[0] = 1e-3 # x
-               odom.pose.covariance[7] = 1e-3 # y
-               odom.pose.covariance[14] = 1e6 # z
-               odom.pose.covariance[21] = 1e6 # rotation about X axis
-               odom.pose.covariance[28] = 1e6 # rotation about Y axis
-               odom.pose.covariance[35] = 0.03 # rotation about Z axis
+               odom.pose.covariance[0] = self.odom_covar_xy # x
+               odom.pose.covariance[7] = self.odom_covar_xy # y
+               odom.pose.covariance[14] = 99999 # z
+               odom.pose.covariance[21] = 99999 # rotation about X axis
+               odom.pose.covariance[28] = 99999 # rotation about Y axis
+               odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
 
                # set the velocity
                odom.child_frame_id = "base_footprint"
                odom.twist.twist.linear.x = speed_trans
                odom.twist.twist.linear.y = 0.0
                odom.twist.twist.angular.z = speed_rot
-               odom.twist.covariance[0] = 1e-3 # x
-               odom.twist.covariance[7] = 1e-3 # y
-               odom.twist.covariance[14] = 1e6 # z
-               odom.twist.covariance[21] = 1e6 # rotation about X axis
-               odom.twist.covariance[28] = 1e6 # rotation about Y axis
-               odom.twist.covariance[35] = 0.03 # rotation about Z axis
+               odom.twist.covariance = odom.pose.covariance
 
                # publish the message
                self.pub_odom.publish(odom)
@@ -204,7 +237,10 @@ class MoveBase:
                i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
 
        def cmdVelReceived(self, msg):
-               self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
+               if not self.bMotorManual:
+                       rospy.logdebug("Set new cmd_vel:", msg.linear.x, msg.angular.z)
+                       self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
+                       rospy.logdebug("Set new cmd_vel done")
 
        # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
        def get_dist_ir(self, num):
@@ -232,6 +268,8 @@ class MoveBase:
                return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
 
        def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
+               if self.bClipRangeSensor and dist > max_range:
+                       dist = max_range
                msg = Range()
                msg.header.stamp = rospy.Time.now()
                msg.header.frame_id = frame_id
@@ -257,13 +295,13 @@ class MoveBase:
        def get_dist_forward(self):
                if self.pub_range_fwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
-                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
+                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
                        self.start_dist_srf(0x5) # get next value
 
        def get_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x17)
-                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
+                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
                        self.start_dist_srf(0x7) # get next value
        
        def led_stripe_received(self, msg):