Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
spin_behavior_tester.hpp
1 // Copyright (c) 2020 Sarthak Mittal
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__SPIN__SPIN_BEHAVIOR_TESTER_HPP_
17 #define BEHAVIORS__SPIN__SPIN_BEHAVIOR_TESTER_HPP_
18 
19 #include <gtest/gtest.h>
20 #include <memory>
21 #include <string>
22 #include <thread>
23 #include <algorithm>
24 
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"
38 
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"
44 
45 namespace nav2_system_tests
46 {
47 
49 {
50 public:
51  using Spin = nav2_msgs::action::Spin;
52  using GoalHandleSpin = rclcpp_action::ClientGoalHandle<Spin>;
53 
56 
57  // Runs a single test with given target yaw
58  bool defaultSpinBehaviorTest(
59  float target_yaw,
60  double tolerance = 0.1);
61 
62  void activate();
63 
64  void deactivate();
65 
66  bool isActive() const
67  {
68  return is_active_;
69  }
70 
71 private:
72  void sendInitialPose();
73 
74  void sendFakeCostmap(float angle);
75  void sendFakeOdom(float angle);
76 
77  void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
78 
79  bool is_active_;
80  bool initial_pose_received_;
81  bool make_fake_costmap_;
82  rclcpp::Time stamp_;
83 
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_;
87 
88  rclcpp::Node::SharedPtr node_;
89 
90  // Publisher to publish initial pose
91  rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
92 
93  // Publisher to publish fake costmap raw
94  rclcpp::Publisher<nav2_msgs::msg::Costmap>::SharedPtr fake_costmap_publisher_;
95 
96  // Publisher to publish fake costmap footprint
97  rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr fake_footprint_publisher_;
98 
99  // Subscriber for amcl pose
100  rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
101 
102  // Action client to call spin action
103  rclcpp_action::Client<Spin>::SharedPtr client_ptr_;
104 };
105 
106 } // namespace nav2_system_tests
107 
108 #endif // BEHAVIORS__SPIN__SPIN_BEHAVIOR_TESTER_HPP_