26 #include "wait_behavior_tester.hpp"
28 using namespace std::chrono_literals;
29 using namespace std::chrono;
31 namespace nav2_system_tests
34 WaitBehaviorTester::WaitBehaviorTester()
36 initial_pose_received_(false)
38 node_ = rclcpp::Node::make_shared(
"wait_behavior_test");
40 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
41 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
43 client_ptr_ = rclcpp_action::create_client<Wait>(
44 node_->get_node_base_interface(),
45 node_->get_node_graph_interface(),
46 node_->get_node_logging_interface(),
47 node_->get_node_waitables_interface(),
51 node_->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
"initialpose", 10);
53 subscription_ = node_->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
54 "amcl_pose", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
55 std::bind(&WaitBehaviorTester::amclPoseCallback,
this, std::placeholders::_1));
58 WaitBehaviorTester::~WaitBehaviorTester()
65 void WaitBehaviorTester::activate()
68 throw std::runtime_error(
"Trying to activate while already active");
71 rclcpp::executors::SingleThreadedExecutor executor;
72 executor.add_node(node_);
73 while (!initial_pose_received_) {
74 RCLCPP_WARN(node_->get_logger(),
"Initial pose not received");
76 std::this_thread::sleep_for(100ms);
81 std::this_thread::sleep_for(10s);
84 RCLCPP_ERROR(node_->get_logger(),
"Action client not initialized");
89 if (!client_ptr_->wait_for_action_server(10s)) {
90 RCLCPP_ERROR(node_->get_logger(),
"Action server not available after waiting");
95 RCLCPP_INFO(this->node_->get_logger(),
"Wait action server is ready");
99 void WaitBehaviorTester::deactivate()
102 throw std::runtime_error(
"Trying to deactivate while already inactive");
107 bool WaitBehaviorTester::behaviorTest(
108 const float wait_time)
111 RCLCPP_ERROR(node_->get_logger(),
"Not activated");
116 std::this_thread::sleep_for(5s);
118 auto start_time = node_->now();
119 auto goal_msg = Wait::Goal();
120 goal_msg.time = rclcpp::Duration(wait_time, 0.0);
122 RCLCPP_INFO(this->node_->get_logger(),
"Sending goal");
124 auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
126 if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
127 rclcpp::FutureReturnCode::SUCCESS)
129 RCLCPP_ERROR(node_->get_logger(),
"send goal call failed :(");
133 rclcpp_action::ClientGoalHandle<Wait>::SharedPtr goal_handle = goal_handle_future.get();
135 RCLCPP_ERROR(node_->get_logger(),
"Goal was rejected by server");
140 auto result_future = client_ptr_->async_get_result(goal_handle);
142 RCLCPP_INFO(node_->get_logger(),
"Waiting for result");
143 if (rclcpp::spin_until_future_complete(node_, result_future) !=
144 rclcpp::FutureReturnCode::SUCCESS)
146 RCLCPP_ERROR(node_->get_logger(),
"get result call failed :(");
150 rclcpp_action::ClientGoalHandle<Wait>::WrappedResult wrapped_result = result_future.get();
152 switch (wrapped_result.code) {
153 case rclcpp_action::ResultCode::SUCCEEDED:
break;
154 case rclcpp_action::ResultCode::ABORTED: RCLCPP_ERROR(
158 case rclcpp_action::ResultCode::CANCELED: RCLCPP_ERROR(
160 "Goal was canceled");
162 default: RCLCPP_ERROR(node_->get_logger(),
"Unknown result code");
166 RCLCPP_INFO(node_->get_logger(),
"result received");
168 if ((node_->now() - start_time).seconds() <
static_cast<double>(wait_time)) {
175 bool WaitBehaviorTester::behaviorTestCancel(
176 const float wait_time)
179 RCLCPP_ERROR(node_->get_logger(),
"Not activated");
184 std::this_thread::sleep_for(5s);
186 auto start_time = node_->now();
187 auto goal_msg = Wait::Goal();
188 goal_msg.time = rclcpp::Duration(wait_time, 0.0);
190 RCLCPP_INFO(this->node_->get_logger(),
"Sending goal");
192 auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
194 if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
195 rclcpp::FutureReturnCode::SUCCESS)
197 RCLCPP_ERROR(node_->get_logger(),
"send goal call failed :(");
201 rclcpp_action::ClientGoalHandle<Wait>::SharedPtr goal_handle = goal_handle_future.get();
203 RCLCPP_ERROR(node_->get_logger(),
"Goal was rejected by server");
208 auto result_future = client_ptr_->async_cancel_all_goals();
210 RCLCPP_INFO(node_->get_logger(),
"Waiting for cancellation");
211 if (rclcpp::spin_until_future_complete(node_, result_future) !=
212 rclcpp::FutureReturnCode::SUCCESS)
214 RCLCPP_ERROR(node_->get_logger(),
"get cancel result call failed :(");
218 auto status = goal_handle_future.get()->get_status();
221 case rclcpp_action::GoalStatus::STATUS_SUCCEEDED: RCLCPP_ERROR(
225 case rclcpp_action::GoalStatus::STATUS_ABORTED: RCLCPP_ERROR(
229 case rclcpp_action::GoalStatus::STATUS_CANCELED: RCLCPP_INFO(
231 "Goal was canceled");
233 case rclcpp_action::GoalStatus::STATUS_CANCELING: RCLCPP_INFO(
235 "Goal is cancelling");
237 case rclcpp_action::GoalStatus::STATUS_EXECUTING: RCLCPP_ERROR(
239 "Goal is executing");
241 case rclcpp_action::GoalStatus::STATUS_ACCEPTED: RCLCPP_ERROR(
243 "Goal is processing");
245 default: RCLCPP_ERROR(node_->get_logger(),
"Unknown result code");
252 void WaitBehaviorTester::sendInitialPose()
254 geometry_msgs::msg::PoseWithCovarianceStamped pose;
255 pose.header.frame_id =
"map";
256 pose.header.stamp = rclcpp::Time();
257 pose.pose.pose.position.x = -2.0;
258 pose.pose.pose.position.y = -0.5;
259 pose.pose.pose.position.z = 0.0;
260 pose.pose.pose.orientation.x = 0.0;
261 pose.pose.pose.orientation.y = 0.0;
262 pose.pose.pose.orientation.z = 0.0;
263 pose.pose.pose.orientation.w = 1.0;
264 for (
int i = 0; i < 35; i++) {
265 pose.pose.covariance[i] = 0.0;
267 pose.pose.covariance[0] = 0.08;
268 pose.pose.covariance[7] = 0.08;
269 pose.pose.covariance[35] = 0.05;
271 publisher_->publish(pose);
272 RCLCPP_INFO(node_->get_logger(),
"Sent initial pose");
275 void WaitBehaviorTester::amclPoseCallback(
276 const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr)
278 initial_pose_received_ =
true;