32 #include <gtest/gtest.h> 36 #include <geometry_msgs/TwistStamped.h> 37 #include <nav_msgs/Odometry.h> 40 #include <std_srvs/Empty.h> 43 const double EPS = 0.01;
77 while ( (get_num_publishers == 0) && (
ros::Time::now() < start + timeout) ) {
81 return (get_num_publishers > 0);
96 FAIL() <<
"Something went wrong while executing test.";
107 FAIL() <<
"Something went wrong while executing test.";
124 ROS_INFO_STREAM(
"Callback received: pos.x: " << odom.pose.pose.position.x
125 <<
", orient.z: " << odom.pose.pose.orientation.z
126 <<
", lin_est: " << odom.twist.twist.linear.x
127 <<
", ang_est: " << odom.twist.twist.angular.z);
129 received_first_odom =
true;
134 ROS_INFO_STREAM(
"Callback received: lin: " << cmd_vel_out.twist.linear.x
135 <<
", ang: " << cmd_vel_out.twist.angular.z);
136 last_cmd_vel_out = cmd_vel_out;
#define ROS_DEBUG_STREAM_THROTTLE(rate, args)
geometry_msgs::TwistStamped getLastCmdVelOut()
bool hasReceivedFirstOdom() const
void cmdVelOutCallback(const geometry_msgs::TwistStamped &cmd_vel_out)
void publish(const boost::shared_ptr< M > &message) const
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
nav_msgs::Odometry getLastOdom()
void waitForOdomMsgs() const
nav_msgs::Odometry last_odom
ros::ServiceClient start_srv
const double VELOCITY_TOLERANCE
bool call(MReq &req, MRes &res)
void publish(geometry_msgs::Twist cmd_vel)
ros::Subscriber vel_out_sub
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
const double JERK_ANGULAR_VELOCITY_TOLERANCE
uint32_t getNumPublishers() const
bool isPublishingCmdVelOut(const ros::Duration &timeout=ros::Duration(1)) const
DiffDriveControllerTest()
const double JERK_LINEAR_VELOCITY_TOLERANCE
bool isControllerAlive() const
ros::ServiceClient stop_srv
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
~DiffDriveControllerTest()
void waitForController() const
const double ORIENTATION_TOLERANCE
geometry_msgs::TwistStamped last_cmd_vel_out
void odomCallback(const nav_msgs::Odometry &odom)
const double POSITION_TOLERANCE