Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00029
00030 #include <cmath>
00031
00032 #include <gtest/gtest.h>
00033
00034 #include <ros/ros.h>
00035
00036 #include <geometry_msgs/Twist.h>
00037 #include <nav_msgs/Odometry.h>
00038 #include <tf/tf.h>
00039
00040
00041 const double EPS = 0.01;
00042 const double POSITION_TOLERANCE = 0.01;
00043 const double VELOCITY_TOLERANCE = 0.02;
00044 const double ORIENTATION_TOLERANCE = 0.03;
00045
00046 class DiffDriveControllerTest : public ::testing::Test
00047 {
00048 public:
00049
00050 DiffDriveControllerTest()
00051 : cmd_pub(nh.advertise<geometry_msgs::Twist>("cmd_vel", 100)),
00052 odom_sub(nh.subscribe("odom", 100, &DiffDriveControllerTest::odomCallback, this))
00053 {
00054 }
00055
00056 ~DiffDriveControllerTest()
00057 {
00058 odom_sub.shutdown();
00059 }
00060
00061 nav_msgs::Odometry getLastOdom(){ return last_odom; }
00062 void publish(geometry_msgs::Twist cmd_vel){ cmd_pub.publish(cmd_vel); }
00063 bool isControllerAlive(){ return (odom_sub.getNumPublishers() > 0) && (cmd_pub.getNumSubscribers() > 0); }
00064
00065 private:
00066 ros::NodeHandle nh;
00067 ros::Publisher cmd_pub;
00068 ros::Subscriber odom_sub;
00069 nav_msgs::Odometry last_odom;
00070
00071 void odomCallback(const nav_msgs::Odometry& odom)
00072 {
00073 ROS_INFO_STREAM("Callback reveived: pos.x: " << odom.pose.pose.position.x
00074 << ", orient.z: " << odom.pose.pose.orientation.z
00075 << ", lin_est: " << odom.twist.twist.linear.x
00076 << ", ang_est: " << odom.twist.twist.angular.z);
00077 last_odom = odom;
00078 }
00079 };
00080
00081 inline tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion& quat)
00082 {
00083 return tf::Quaternion(quat.x, quat.y, quat.z, quat.w);
00084 }
00085