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 #include <std_srvs/Empty.h>
00041
00042
00043 const double EPS = 0.01;
00044 const double POSITION_TOLERANCE = 0.01;
00045 const double VELOCITY_TOLERANCE = 0.02;
00046 const double JERK_LINEAR_VELOCITY_TOLERANCE = 0.10;
00047 const double JERK_ANGULAR_VELOCITY_TOLERANCE = 0.05;
00048 const double ORIENTATION_TOLERANCE = 0.03;
00049
00050 class AckermannControllerTest : public ::testing::Test
00051 {
00052 public:
00053
00054 AckermannControllerTest()
00055 : cmd_twist_pub(nh.advertise<geometry_msgs::Twist>("cmd_vel", 100))
00056 , odom_sub(nh.subscribe("odom", 100, &AckermannControllerTest::odomCallback, this))
00057 , start_srv(nh.serviceClient<std_srvs::Empty>("start"))
00058 , stop_srv(nh.serviceClient<std_srvs::Empty>("stop"))
00059 {
00060 }
00061
00062 ~AckermannControllerTest()
00063 {
00064 odom_sub.shutdown();
00065 }
00066
00067 nav_msgs::Odometry getLastOdom(){ return last_odom; }
00068 void publish(geometry_msgs::Twist cmd_vel){ cmd_twist_pub.publish(cmd_vel); }
00069 bool isControllerAlive(){ return (odom_sub.getNumPublishers() > 0) && (cmd_twist_pub.getNumSubscribers() > 0); }
00070
00071 void start(){ std_srvs::Empty srv; start_srv.call(srv); }
00072 void stop(){ std_srvs::Empty srv; stop_srv.call(srv); }
00073
00074 private:
00075 ros::NodeHandle nh;
00076 ros::Publisher cmd_twist_pub;
00077 ros::Subscriber odom_sub;
00078 nav_msgs::Odometry last_odom;
00079
00080 ros::ServiceClient start_srv;
00081 ros::ServiceClient stop_srv;
00082
00083 void odomCallback(const nav_msgs::Odometry& odom)
00084 {
00085 ROS_INFO_STREAM("Callback reveived: pos.x: " << odom.pose.pose.position.x
00086 << ", orient.z: " << odom.pose.pose.orientation.z
00087 << ", lin_est: " << odom.twist.twist.linear.x
00088 << ", ang_est: " << odom.twist.twist.angular.z);
00089 last_odom = odom;
00090 }
00091 };
00092
00093 inline tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion& quat)
00094 {
00095 return tf::Quaternion(quat.x, quat.y, quat.z, quat.w);
00096 }
00097