35 #include <gtest/gtest.h> 39 #include <geometry_msgs/Twist.h> 40 #include <four_wheel_steering_msgs/FourWheelSteering.h> 41 #include <nav_msgs/Odometry.h> 44 #include <std_srvs/Empty.h> 47 const double EPS = 0.01;
74 void publish(geometry_msgs::Twist cmd_vel)
78 void publish_4ws(four_wheel_steering_msgs::FourWheelSteering cmd_vel)
98 FAIL() <<
"Something went wrong while executing test.";
109 FAIL() <<
"Something went wrong while executing test.";
124 ROS_INFO_STREAM(
"Callback reveived: 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;
ros::ServiceClient stop_srv
void publish_4ws(four_wheel_steering_msgs::FourWheelSteering cmd_vel)
void publish(geometry_msgs::Twist cmd_vel)
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
const double VELOCITY_TOLERANCE
bool call(MReq &req, MRes &res)
uint32_t getNumPublishers() const
FourWheelSteeringControllerTest()
nav_msgs::Odometry last_odom
void waitForOdomMsgs() const
void waitForController() const
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
bool isControllerAlive() const
ros::Publisher cmd_twist_pub
const double JERK_ANGULAR_VELOCITY_TOLERANCE
void publish(const boost::shared_ptr< M > &message) const
void odomCallback(const nav_msgs::Odometry &odom)
bool hasReceivedFirstOdom() const
const double JERK_LINEAR_VELOCITY_TOLERANCE
#define ROS_INFO_STREAM(args)
~FourWheelSteeringControllerTest()
const double ORIENTATION_TOLERANCE
uint32_t getNumSubscribers() const
nav_msgs::Odometry getLastOdom()
ros::ServiceClient start_srv
const double POSITION_TOLERANCE
ros::Publisher cmd_4ws_pub