34 #include <gtest/gtest.h> 37 #include <move_base_msgs/MoveBaseAction.h> 38 #include <planner_cspace_msgs/MoveWithToleranceAction.h> 39 #include <planner_cspace_msgs/PlannerStatus.h> 47 :
public ActionTestBase<planner_cspace_msgs::MoveWithToleranceAction, ACTION_TOPIC_TOLERANT_MOVE>
52 planner_cspace_msgs::MoveWithToleranceGoal goal;
54 goal.target_pose.header.frame_id =
"map";
55 goal.target_pose.pose.position.x = 2.1;
56 goal.target_pose.pose.position.y = 0.45;
57 goal.target_pose.pose.position.z = 0.0;
58 goal.target_pose.pose.orientation.x = 0.0;
59 goal.target_pose.pose.orientation.y = 0.0;
60 goal.target_pose.pose.orientation.z = 1.0;
61 goal.target_pose.pose.orientation.w = 0.0;
62 goal.continuous_movement_mode =
true;
63 goal.goal_tolerance_ang = 0.1;
64 goal.goal_tolerance_ang_finish = 0.05;
65 goal.goal_tolerance_lin = 0.2;
73 const geometry_msgs::TransformStamped map_to_robot =
75 return std::hypot(map_to_robot.transform.translation.x - goal.target_pose.pose.position.x,
76 map_to_robot.transform.translation.y - goal.target_pose.pose.position.y);
78 catch (std::exception&)
80 return std::numeric_limits<double>::max();
98 <<
"Action didn't get active: " <<
move_base_->getState().toString()
106 <<
"Action didn't succeeded: " <<
move_base_->getState().toString()
113 EXPECT_LT(dist_to_goal, goal.goal_tolerance_lin);
115 EXPECT_GT(dist_to_goal, 0.05);
117 EXPECT_EQ(
planner_status_->status, planner_cspace_msgs::PlannerStatus::DOING);
122 <<
"Navigation didn't finished: " <<
move_base_->getState().toString()
129 int main(
int argc,
char** argv)
131 testing::InitGoogleTest(&argc, argv);
132 ros::init(argc, argv,
"test_tolerant_action");
133 return RUN_ALL_TESTS();
planner_cspace_msgs::PlannerStatus::ConstPtr planner_status_
TEST_F(TolerantActionTest, GoalWithTolerance)
planner_cspace_msgs::MoveWithToleranceGoal createGoalInFree()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string statusString() const
ActionClientPtr move_base_
double getDistBetweenRobotAndGoal(const planner_cspace_msgs::MoveWithToleranceGoal &goal)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()