16 #ifndef BEHAVIORS__ASSISTED_TELEOP__ASSISTED_TELEOP_BEHAVIOR_TESTER_HPP_
17 #define BEHAVIORS__ASSISTED_TELEOP__ASSISTED_TELEOP_BEHAVIOR_TESTER_HPP_
19 #include <gtest/gtest.h>
25 #include "angles/angles.h"
26 #include "geometry_msgs/msg/pose_stamped.hpp"
27 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
28 #include "geometry_msgs/msg/twist.hpp"
29 #include "geometry_msgs/msg/pose2_d.hpp"
30 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
31 #include "nav2_msgs/action/assisted_teleop.hpp"
32 #include "nav2_util/node_thread.hpp"
33 #include "nav2_util/robot_utils.hpp"
34 #include "rclcpp_action/rclcpp_action.hpp"
35 #include "rclcpp/rclcpp.hpp"
36 #include "std_msgs/msg/empty.hpp"
38 #include "tf2/utils.h"
39 #include "tf2_ros/buffer.h"
40 #include "tf2_ros/transform_listener.h"
42 namespace nav2_system_tests
48 using AssistedTeleop = nav2_msgs::action::AssistedTeleop;
54 bool defaultAssistedTeleopTest(
68 void sendInitialPose();
70 void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
72 void filteredVelCallback(geometry_msgs::msg::Twist::SharedPtr msg);
74 unsigned int counter_;
76 bool initial_pose_received_;
79 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
80 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
82 rclcpp::Node::SharedPtr node_;
85 rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr initial_pose_pub_;
86 rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr preempt_pub_;
87 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_pub_;
90 rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
91 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr filtered_vel_sub_;
94 rclcpp_action::Client<AssistedTeleop>::SharedPtr client_ptr_;
97 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
98 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
99 std::unique_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;