Nav2 Navigation Stack - humble  humble
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 "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"
37 
38 #include "tf2/utils.h"
39 #include "tf2_ros/buffer.h"
40 #include "tf2_ros/transform_listener.h"
41 
42 namespace nav2_system_tests
43 {
44 
46 {
47 public:
48  using AssistedTeleop = nav2_msgs::action::AssistedTeleop;
49 
52 
53  // Runs a single test with given target yaw
54  bool defaultAssistedTeleopTest(
55  const float lin_vel,
56  const float ang_vel);
57 
58  void activate();
59 
60  void deactivate();
61 
62  bool isActive() const
63  {
64  return is_active_;
65  }
66 
67 private:
68  void sendInitialPose();
69 
70  void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
71 
72  void filteredVelCallback(geometry_msgs::msg::Twist::SharedPtr msg);
73 
74  unsigned int counter_;
75  bool is_active_;
76  bool initial_pose_received_;
77  rclcpp::Time stamp_;
78 
79  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
80  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
81 
82  rclcpp::Node::SharedPtr node_;
83 
84  // Publishers
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_;
88 
89  // Subscribers
90  rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
91  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr filtered_vel_sub_;
92 
93  // Action client to call AssistedTeleop action
94  rclcpp_action::Client<AssistedTeleop>::SharedPtr client_ptr_;
95 
96  // collision checking
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_;
100 };
101 
102 } // namespace nav2_system_tests
103 
104 #endif // BEHAVIORS__ASSISTED_TELEOP__ASSISTED_TELEOP_BEHAVIOR_TESTER_HPP_