- (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
- if pitch > 30*pi/180:
- val = (100.0/60)*abs(pitch)*180/pi
- self.set_motor_handicap(int(val), 0)
- elif pitch < -30*pi/180:
- val = (100.0/60)*abs(pitch)*180/pi
- self.set_motor_handicap(0, int(val))
- else:
- self.set_motor_handicap(0, 0)
+ 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)