39 #include <gtest/gtest.h> 43 #include <geometry_msgs/Twist.h> 44 #include <nav_msgs/Odometry.h> 47 #include <std_srvs/Empty.h> 48 #include <controller_manager_msgs/ListControllers.h> 51 const double EPS = 0.01;
69 ,
ctrl_name(
"ackermann_steering_bot_controller")
102 controller_manager_msgs::ListControllers srv;
105 auto ctrl_list = srv.response.controller;
106 auto is_running = [
this](
const controller_manager_msgs::ControllerState& ctrl)
108 return ctrl.name ==
ctrl_name && ctrl.state ==
"running";
110 bool running = std::any_of(ctrl_list.begin(), ctrl_list.end(), is_running);
112 return running && subscribing;
134 ROS_INFO_STREAM(
"Callback reveived: 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);
138 std::lock_guard<std::mutex> lock(odom_mutex);
void odomCallback(const nav_msgs::Odometry &odom)
void assertQuaternionValid(const tf::Quaternion &q)
nav_msgs::Odometry getLastOdom()
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
void publish(const boost::shared_ptr< M > &message) const
const double JERK_LINEAR_VELOCITY_TOLERANCE
#define ROS_INFO_STREAM(args)
const double ANGULAR_VELOCITY_TOLERANCE
ros::ServiceClient list_ctrls_srv
const double ORIENTATION_TOLERANCE
uint32_t getNumSubscribers() const
AckermannSteeringControllerTest()
const double POSITION_TOLERANCE