From: Erik Andresen Date: Mon, 12 Oct 2015 18:46:16 +0000 (+0200) Subject: ekf: gps fixes X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=commitdiff_plain;h=2ee98f31c1f2527cdb4e190e37d9f6ad9e246859 ekf: gps fixes --- diff --git a/launch/robot_localization.launch b/launch/robot_localization.launch index 683c021..a6e408d 100644 --- a/launch/robot_localization.launch +++ b/launch/robot_localization.launch @@ -78,7 +78,7 @@ making this parameter required for each sensor. --> [true, true, false, false, false, true, true, true, false, false, false, true, true, true, false] [false, false, false, true, true, true, false, false, false, true, true, true, true, true, true] - [true, true, true, false, false, false, true, true, true, false, false, false, true, true, true] + [true, true, true, false, false, false, false, false, false, false, false, false, false, false, false] - + - + diff --git a/launch/wild_thumper.launch b/launch/wild_thumper.launch index 567d95a..0529577 100644 --- a/launch/wild_thumper.launch +++ b/launch/wild_thumper.launch @@ -36,15 +36,14 @@ - - - + + + - diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 4064fb8..5056107 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -65,10 +65,10 @@ class MoveBase: (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) if pitch > 30*pi/180: val = (100.0/65)*abs(pitch)*180/pi - self.set_motor_handicap(0, int(val)) + self.set_motor_handicap(int(val), 0) elif pitch < -30*pi/180: val = (100.0/65)*abs(pitch)*180/pi - self.set_motor_handicap(int(val), 0) + self.set_motor_handicap(0, int(val)) else: self.set_motor_handicap(0, 0)