- #pr.disable()
- #pr.dump_stats("/tmp/test.stats")
-
- def send_odometry(self):
- current_time = rospy.Time.now()
- lPos, fAngle, lSpeed = self.command("get engine pose")
-
- # since all odometry is 6DOF we'll need a quaternion created from yaw
- odom_quat = tf.transformations.quaternion_from_euler(0, 0, fAngle)
-
- # first, we'll publish the transform over tf
- self.tf_broadcaster.sendTransform((lPos[0], lPos[1], 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 = lPos[0]
- odom.pose.pose.position.y = lPos[1]
- 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 = lSpeed[0]
- odom.twist.twist.linear.y = 0.0
- odom.twist.twist.angular.z = lSpeed[1]
-
- # publish the message
- self.pub_odom.publish(odom)
-
- # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
- def cmdVelReceived(self, msg):
- trans = msg.linear.x
- rot = msg.angular.z