+ def execute_dyn_reconf(self, config, level):
+ self.bClipRangeSensor = config["range_sensor_clip"]
+ self.range_sensor_max = config["range_sensor_max"]
+ self.range_sensor_fov = config["range_sensor_fov"]
+ 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"]
+ self.bStayDocked = config["stay_docked"]
+
+ return config
+
+ def imuReceived(self, msg):
+ if self.rollover_protect and (any(self.cur_vel) or self.bMotorManual):
+ (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, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
+ rospy.logwarn("Running forward rollver protection")
+ elif pitch < -self.rollover_protect_limit*pi/180:
+ self.bMotorManual = True
+ i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
+ rospy.logwarn("Running backward rollver protection")
+ elif self.bMotorManual:
+ i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
+ self.bMotorManual = False
+ self.cmd_vel = (0, 0)
+ rospy.logwarn("Rollver protection done")
+