35 #include <gtest/gtest.h> 39 #include <geometry_msgs/TwistStamped.h> 40 #include <nav_msgs/Odometry.h> 41 #include <control_msgs/JointTrajectoryControllerState.h> 44 #include <std_srvs/Empty.h> 47 const double EPS = 0.01;
84 while ( (get_num_publishers == 0) && (
ros::Time::now() < start + timeout) ) {
88 return (get_num_publishers > 0);
104 FAIL() <<
"Something went wrong while executing test.";
115 FAIL() <<
"Something went wrong while executing test.";
134 ROS_INFO_STREAM(
"Callback received: pos.x: " << odom.pose.pose.position.x
135 <<
", orient.z: " << odom.pose.pose.orientation.z
136 <<
", lin_est: " << odom.twist.twist.linear.x
137 <<
", ang_est: " << odom.twist.twist.angular.z);
139 received_first_odom =
true;
145 ROS_DEBUG_STREAM(
"Joint trajectory controller state callback received:\n" <<
146 joint_traj_controller_state);
148 last_joint_traj_controller_state = joint_traj_controller_state;
153 ROS_INFO_STREAM(
"Callback received: lin: " << cmd_vel_out.twist.linear.x
154 <<
", ang: " << cmd_vel_out.twist.angular.z);
155 last_cmd_vel_out = cmd_vel_out;
bool hasReceivedFirstOdom() const
geometry_msgs::TwistStamped getLastCmdVelOut()
bool isControllerAlive() const
void cmdVelOutCallback(const geometry_msgs::TwistStamped &cmd_vel_out)
void waitForController() const
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
nav_msgs::Odometry getLastOdom()
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)
control_msgs::JointTrajectoryControllerState getLastJointTrajectoryControllerState()
uint32_t getNumPublishers() const
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
ros::Subscriber vel_out_sub
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
const double JERK_ANGULAR_VELOCITY_TOLERANCE
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber joint_traj_controller_state_sub
bool isPublishingCmdVelOut(const ros::Duration &timeout=ros::Duration(1)) const
DiffDriveControllerTest()
#define ROS_DEBUG_STREAM(args)
const double JERK_LINEAR_VELOCITY_TOLERANCE
bool isPublishingJointTrajectoryControllerState()
ros::ServiceClient stop_srv
#define ROS_INFO_STREAM(args)
void waitForOdomMsgs() const
~DiffDriveControllerTest()
control_msgs::JointTrajectoryControllerState last_joint_traj_controller_state
void jointTrajectoryControllerStateCallback(const control_msgs::JointTrajectoryControllerState &joint_traj_controller_state)
const double ORIENTATION_TOLERANCE
uint32_t getNumSubscribers() const
geometry_msgs::TwistStamped last_cmd_vel_out
void odomCallback(const nav_msgs::Odometry &odom)
const double POSITION_TOLERANCE