17 #ifndef BEHAVIORS__WAIT__WAIT_BEHAVIOR_TESTER_HPP_
18 #define BEHAVIORS__WAIT__WAIT_BEHAVIOR_TESTER_HPP_
20 #include <gtest/gtest.h>
26 #include "rclcpp/rclcpp.hpp"
27 #include "rclcpp_action/rclcpp_action.hpp"
28 #include "angles/angles.h"
29 #include "nav2_msgs/action/wait.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 #include "nav2_util/node_thread.hpp"
32 #include "geometry_msgs/msg/pose_stamped.hpp"
33 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
35 #include "tf2/utils.h"
36 #include "tf2_ros/buffer.h"
37 #include "tf2_ros/transform_listener.h"
39 namespace nav2_system_tests
45 using Wait = nav2_msgs::action::Wait;
46 using GoalHandleWait = rclcpp_action::ClientGoalHandle<Wait>;
55 bool behaviorTestCancel(
float time);
67 void sendInitialPose();
69 void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
72 bool initial_pose_received_;
74 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
75 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
77 rclcpp::Node::SharedPtr node_;
80 rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
83 rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
86 rclcpp_action::Client<Wait>::SharedPtr client_ptr_;