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