16 #ifndef BEHAVIORS__SPIN__SPIN_BEHAVIOR_TESTER_HPP_
17 #define BEHAVIORS__SPIN__SPIN_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/spin.hpp"
29 #include "nav2_msgs/msg/costmap.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 #include "nav2_util/node_thread.hpp"
32 #include "geometry_msgs/msg/point32.hpp"
33 #include "geometry_msgs/msg/polygon_stamped.hpp"
34 #include "geometry_msgs/msg/pose_stamped.hpp"
35 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
36 #include "geometry_msgs/msg/transform_stamped.hpp"
37 #include "geometry_msgs/msg/quaternion.hpp"
39 #include "tf2/utils.h"
40 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
41 #include "tf2_ros/buffer.h"
42 #include "tf2_ros/transform_broadcaster.h"
43 #include "tf2_ros/transform_listener.h"
45 namespace nav2_system_tests
51 using Spin = nav2_msgs::action::Spin;
52 using GoalHandleSpin = rclcpp_action::ClientGoalHandle<Spin>;
58 bool defaultSpinBehaviorTest(
60 double tolerance = 0.1);
72 void sendInitialPose();
74 void sendFakeCostmap(
float angle);
75 void sendFakeOdom(
float angle);
77 void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
80 bool initial_pose_received_;
81 bool make_fake_costmap_;
84 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
85 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
86 std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
88 rclcpp::Node::SharedPtr node_;
91 rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
94 rclcpp::Publisher<nav2_msgs::msg::Costmap>::SharedPtr fake_costmap_publisher_;
97 rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr fake_footprint_publisher_;
100 rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
103 rclcpp_action::Client<Spin>::SharedPtr client_ptr_;