Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
assisted_teleop_behavior_tester.hpp
1 // Copyright (c) 2020 Samsung Research
2 // Copyright (c) 2018 Intel Corporation
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License. Reserved.
15 
16 #ifndef BEHAVIORS__ASSISTED_TELEOP__ASSISTED_TELEOP_BEHAVIOR_TESTER_HPP_
17 #define BEHAVIORS__ASSISTED_TELEOP__ASSISTED_TELEOP_BEHAVIOR_TESTER_HPP_
18 
19 #include <gtest/gtest.h>
20 #include <memory>
21 #include <string>
22 #include <thread>
23 #include <algorithm>
24 
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
27 #include "geometry_msgs/msg/twist_stamped.hpp"
28 #include "geometry_msgs/msg/pose.hpp"
29 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
30 #include "nav2_msgs/action/assisted_teleop.hpp"
31 #include "nav2_ros_common/node_thread.hpp"
32 #include "nav2_util/robot_utils.hpp"
33 #include "rclcpp_action/rclcpp_action.hpp"
34 #include "rclcpp/rclcpp.hpp"
35 #include "std_msgs/msg/empty.hpp"
36 
37 #include "tf2/utils.hpp"
38 #include "tf2_ros/buffer.hpp"
39 #include "tf2_ros/transform_listener.hpp"
40 
41 namespace nav2_system_tests
42 {
43 
45 {
46 public:
47  using AssistedTeleop = nav2_msgs::action::AssistedTeleop;
48 
51 
52  // Runs a single test with given target yaw
53  bool defaultAssistedTeleopTest(
54  const float lin_vel,
55  const float ang_vel);
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  void filteredVelCallback(geometry_msgs::msg::TwistStamped::SharedPtr msg);
72 
73  unsigned int counter_;
74  bool is_active_;
75  bool initial_pose_received_;
76  rclcpp::Time stamp_;
77 
78  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
79  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
80 
81  rclcpp::Node::SharedPtr node_;
82 
83  // Publishers
84  rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr initial_pose_pub_;
85  rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr preempt_pub_;
86  rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr cmd_vel_pub_;
87 
88  // Subscribers
89  nav2::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
90  nav2::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr filtered_vel_sub_;
91 
92  // Action client to call AssistedTeleop action
93  nav2::ActionClient<AssistedTeleop>::SharedPtr client_ptr_;
94 
95  // collision checking
96  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
97  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
98  std::unique_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
99 };
100 
101 } // namespace nav2_system_tests
102 
103 #endif // BEHAVIORS__ASSISTED_TELEOP__ASSISTED_TELEOP_BEHAVIOR_TESTER_HPP_