Go to the documentation of this file.
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;
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);
145 ROS_DEBUG_STREAM(
"Joint trajectory controller state callback received:\n" <<
146 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);
void cmdVelOutCallback(const geometry_msgs::TwistStamped &cmd_vel_out)
~DiffDriveControllerTest()
void odomCallback(const nav_msgs::Odometry &odom)
bool hasReceivedFirstOdom() const
geometry_msgs::TwistStamped getLastCmdVelOut()
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
void jointTrajectoryControllerStateCallback(const control_msgs::JointTrajectoryControllerState &joint_traj_controller_state)
ros::Subscriber vel_out_sub
bool isPublishingCmdVelOut(const ros::Duration &timeout=ros::Duration(1)) const
#define ROS_DEBUG_STREAM(args)
void publish(const boost::shared_ptr< M > &message) const
void waitForController() const
uint32_t getNumPublishers() const
bool isPublishingJointTrajectoryControllerState()
DiffDriveControllerTest()
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
control_msgs::JointTrajectoryControllerState getLastJointTrajectoryControllerState()
const double JERK_ANGULAR_VELOCITY_TOLERANCE
nav_msgs::Odometry last_odom
void publish(geometry_msgs::Twist cmd_vel)
bool isControllerAlive() const
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
ros::ServiceClient stop_srv
geometry_msgs::TwistStamped last_cmd_vel_out
#define ROS_INFO_STREAM(args)
void waitForOdomMsgs() const
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::ServiceClient start_srv
const double JERK_LINEAR_VELOCITY_TOLERANCE
control_msgs::JointTrajectoryControllerState last_joint_traj_controller_state
nav_msgs::Odometry getLastOdom()
const double VELOCITY_TOLERANCE
const double ORIENTATION_TOLERANCE
const double POSITION_TOLERANCE
ros::Subscriber joint_traj_controller_state_sub