]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
fix odometry error when going straight
authorfdila <federicadilauro1998@gmail.com>
Tue, 14 Apr 2020 12:22:58 +0000 (14:22 +0200)
committerfdila <federicadilauro1998@gmail.com>
Tue, 14 Apr 2020 12:22:58 +0000 (14:22 +0200)
utils/catkin_ws/src/serial_bridge/scripts/serial_receiver.py

index 86459e94da219573097c136bde5c752e7fdb0062..e39e2256a30f9c5677daca88a058db34c9c6db6b 100755 (executable)
@@ -94,11 +94,10 @@ def serial_receiver():
                     odom_values = rotation_matrix.dot(translate_icc_matrix) + translate_back_matrix
                     
                 elif(d_time > 0):
-                    odom_values = numpy.array([odom_values[0]+cos(odom_values[2])*(lin_vel/d_time), 
-                                                odom_values[1]+sin(odom_values[2])*(lin_vel/d_time), 
+                    odom_values = numpy.array([odom_values[0]+(cos(odom_values[2])*(lin_vel*d_time)), 
+                                                odom_values[1]+(sin(odom_values[2])*(lin_vel*d_time)), 
                                                 odom_values[2]])
-
-            
+              
                 current_time = rospy.Time.now()
                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, odom_values[2])
                 odom_broadcaster.sendTransform((odom_values[0], odom_values[1], 0.), odom_quat, current_time, "base_link", "odom")