+ 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.pitch_handicap_enable = config["pitch_handicap_enable"]
+ self.pitch_handicap_limit = config["pitch_handicap_limit"]
+ self.pitch_handicap_strength = config["pitch_handicap_strength"]
+
+ if not self.pitch_handicap_enable:
+ self.set_motor_handicap(0, 0)
+
+ return config
+
+ def set_motor_handicap(self, front, aft): # percent
+ if front > 100: front = 100
+ if aft > 100: aft = 100
+ if self.handicap_last != (front, aft):
+ i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
+ self.handicap_last = (front, aft)
+
+ def imuReceived(self, msg):
+ if self.pitch_handicap_enable:
+ (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
+ if pitch > self.pitch_handicap_limit*pi/180:
+ val = (100.0/self.pitch_handicap_strength)*abs(pitch)*180/pi
+ self.set_motor_handicap(int(val), 0)
+ elif pitch < -self.pitch_handicap_limit*pi/180:
+ val = (100.0/self.pitch_handicap_strength)*abs(pitch)*180/pi
+ self.set_motor_handicap(0, int(val))
+ else:
+ self.set_motor_handicap(0, 0)
+