16 #ifndef BEHAVIORS__BACKUP__BACKUP_BEHAVIOR_TESTER_HPP_
17 #define BEHAVIORS__BACKUP__BACKUP_BEHAVIOR_TESTER_HPP_
19 #include <gtest/gtest.h>
25 #include "rclcpp/rclcpp.hpp"
26 #include "rclcpp_action/rclcpp_action.hpp"
27 #include "angles/angles.h"
28 #include "nav2_msgs/action/back_up.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_util/node_thread.hpp"
31 #include "geometry_msgs/msg/pose_stamped.hpp"
32 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
34 #include "tf2/utils.h"
35 #include "tf2_ros/buffer.h"
36 #include "tf2_ros/transform_listener.h"
38 namespace nav2_system_tests
44 using BackUp = nav2_msgs::action::BackUp;
45 using GoalHandleBackup = rclcpp_action::ClientGoalHandle<BackUp>;
51 bool defaultBackupBehaviorTest(
52 const BackUp::Goal goal_msg,
53 const double tolerance);
65 void sendInitialPose();
67 void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
70 bool initial_pose_received_;
73 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
74 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
76 rclcpp::Node::SharedPtr node_;
79 rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
82 rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
85 rclcpp_action::Client<BackUp>::SharedPtr client_ptr_;