From: Erik Andresen Date: Sat, 13 Jun 2015 17:45:41 +0000 (+0200) Subject: added 3dsensor X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=commitdiff_plain;h=37ec2a1056b61c00cefc44bca9bb5eb7d782a6e1 added 3dsensor --- diff --git a/launch/3dsensor.launch b/launch/3dsensor.launch new file mode 100644 index 0000000..8276bb6 --- /dev/null +++ b/launch/3dsensor.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/package.xml b/package.xml index 6911afe..2093ebd 100644 --- a/package.xml +++ b/package.xml @@ -45,7 +45,10 @@ roscpp std_msgs image_transport + openni2_camera hector_sensors_description + openni2_launch + depthimage_to_laserscan diff --git a/scripts/move_base.py b/scripts/move_base.py index 6c066f3..0beaf26 100755 --- a/scripts/move_base.py +++ b/scripts/move_base.py @@ -24,6 +24,7 @@ class MoveBase: self.set_speed(0, 0) rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction + self.handicap_last = (-1, -1) self.run() def run(self): @@ -42,18 +43,18 @@ class MoveBase: rate.sleep() def set_motor_handicap(self, front, aft): # percent - i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft)) + 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): (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) if pitch > 30*pi/180: - val = (100/90)*abs(pitch)*180/pi - print "aft handicap", val - self.set_motor_handicap(0, val) + val = (100.0/65)*abs(pitch)*180/pi + self.set_motor_handicap(0, int(val)) elif pitch < -30*pi/180: - val = (100/90)*abs(pitch)*180/pi - print "front handicap", val - self.set_motor_handicap(val, 0) + val = (100.0/65)*abs(pitch)*180/pi + self.set_motor_handicap(int(val), 0) else: self.set_motor_handicap(0, 0)