X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_roboint.git;a=blobdiff_plain;f=scripts%2Frobo_explorer.py;fp=scripts%2Frobo_explorer.py;h=3a302cc40df33d504aa146d0a6da7b954a892de8;hp=33114931a7ec6f9b5ae29b434b9f743cedbed303;hb=416ac5d02482b1f9ca9534f1eccf067a585ecf86;hpb=5bd3f425969181c6de15a3f8b32bf72ab5c83772 diff --git a/scripts/robo_explorer.py b/scripts/robo_explorer.py index 3311493..3a302cc 100755 --- a/scripts/robo_explorer.py +++ b/scripts/robo_explorer.py @@ -4,7 +4,7 @@ import rospy import tf import tf.broadcaster import tf.transformations -from math import sin, cos, pi +from math import * from geometry_msgs.msg import Twist, TransformStamped, Point32 from sensor_msgs.msg import LaserScan from nav_msgs.msg import Odometry @@ -92,8 +92,8 @@ class RoboExplorer: def send_odometry(self, msg, current_time): # speeds dt = (current_time - self.last_time).to_sec() - vx = (self.x - self.x_last) / dt - vy = (self.y - self.y_last) / dt + vx = sqrt((self.x - self.x_last)**2 + (self.y - self.y_last)**2) / dt + vy = 0.0 valpha = (self.alpha - self.alpha_last) / dt self.x_last = self.x self.y_last = self.y