+ def send_odometry(self, msg, current_time):
+ # speeds
+ dt = (current_time - self.last_time).to_sec()
+ vx = sqrt((self.x - self.x_last)**2 + (self.y - self.y_last)**2) / dt
+ if (msg.output[0]-msg.output[1] + msg.output[2]-msg.output[3]) < 0:
+ # moving backward
+ vx*=-1
+ valpha = (self.alpha - self.alpha_last) / dt
+ self.x_last = self.x
+ self.y_last = self.y
+ self.alpha_last = self.alpha
+
+ # since all odometry is 6DOF we'll need a quaternion created from yaw
+ odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
+
+ # first, we'll publish the transform over tf
+ self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
+
+ # next, we'll publish the odometry message over ROS
+ odom = Odometry()
+ odom.header.stamp = current_time
+ odom.header.frame_id = "/odom"
+
+ # set the position
+ odom.pose.pose.position.x = self.x
+ odom.pose.pose.position.y = self.y
+ odom.pose.pose.position.z = 0.0
+ odom.pose.pose.orientation.x = odom_quat[0]
+ odom.pose.pose.orientation.y = odom_quat[1]
+ odom.pose.pose.orientation.z = odom_quat[2]
+ odom.pose.pose.orientation.w = odom_quat[3]
+
+ # set the velocity
+ odom.child_frame_id = "base_link"
+ odom.twist.twist.linear.x = vx
+ odom.twist.twist.linear.y = 0.0
+ odom.twist.twist.angular.z = valpha
+
+ # publish the message
+ self.pub_odom.publish(odom)
+
+ def send_range(self, msg, current_time):
+ # ultra sonic range finder
+ scan = Range()