33 #include <gtest/gtest.h> 37 #include <geometry_msgs/Twist.h> 38 #include <nav_msgs/Odometry.h> 41 #include <std_srvs/Empty.h> 44 const double EPS = 0.01;
87 ROS_INFO_STREAM(
"Callback reveived: pos.x: " << odom.pose.pose.position.x
88 <<
", orient.z: " << odom.pose.pose.orientation.z
89 <<
", lin_est: " << odom.twist.twist.linear.x
90 <<
", ang_est: " << odom.twist.twist.angular.z);
void odomCallback(const nav_msgs::Odometry &odom)
nav_msgs::Odometry getLastOdom()
void publish(const boost::shared_ptr< M > &message) const
nav_msgs::Odometry last_odom
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
const double VELOCITY_TOLERANCE
bool call(MReq &req, MRes &res)
void publish(geometry_msgs::Twist cmd_vel)
~AckermannSteeringControllerTest()
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
ros::ServiceClient start_srv
ros::ServiceClient stop_srv
const double JERK_ANGULAR_VELOCITY_TOLERANCE
uint32_t getNumPublishers() const
const double JERK_LINEAR_VELOCITY_TOLERANCE
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
const double ANGULAR_VELOCITY_TOLERANCE
const double ORIENTATION_TOLERANCE
AckermannSteeringControllerTest()
const double POSITION_TOLERANCE