Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
wait_behavior_tester.hpp
1 // Copyright (c) 2020 Samsung Research
2 // Copyright (c) 2020 Sarthak Mittal
3 // Copyright (c) 2018 Intel Corporation
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License. Reserved.
16 
17 #ifndef BEHAVIORS__WAIT__WAIT_BEHAVIOR_TESTER_HPP_
18 #define BEHAVIORS__WAIT__WAIT_BEHAVIOR_TESTER_HPP_
19 
20 #include <gtest/gtest.h>
21 #include <memory>
22 #include <string>
23 #include <thread>
24 #include <algorithm>
25 
26 #include "rclcpp/rclcpp.hpp"
27 #include "rclcpp_action/rclcpp_action.hpp"
28 #include "nav2_msgs/action/wait.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_ros_common/node_thread.hpp"
31 #include "nav2_ros_common/lifecycle_node.hpp"
32 #include "geometry_msgs/msg/pose_stamped.hpp"
33 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
34 
35 #include "tf2/utils.hpp"
36 #include "tf2_ros/buffer.hpp"
37 #include "tf2_ros/transform_listener.hpp"
38 
39 namespace nav2_system_tests
40 {
41 
43 {
44 public:
45  using Wait = nav2_msgs::action::Wait;
46  using GoalHandleWait = rclcpp_action::ClientGoalHandle<Wait>;
47 
50 
51  // Runs a single test with given target yaw
52  bool behaviorTest(
53  float time);
54 
55  bool behaviorTestCancel(float time);
56 
57  void activate();
58 
59  void deactivate();
60 
61  bool isActive() const
62  {
63  return is_active_;
64  }
65 
66 private:
67  void sendInitialPose();
68 
69  void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
70 
71  bool is_active_;
72  bool initial_pose_received_;
73 
74  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
75  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
76 
77  rclcpp::Node::SharedPtr node_;
78 
79  // Publisher to publish initial pose
80  rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
81 
82  // Subscriber for amcl pose
83  nav2::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
84 
85  // Action client to call wait action
86  nav2::ActionClient<Wait>::SharedPtr client_ptr_;
87 };
88 
89 } // namespace nav2_system_tests
90 
91 #endif // BEHAVIORS__WAIT__WAIT_BEHAVIOR_TESTER_HPP_