Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
drive_on_heading_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__DRIVE_ON_HEADING__DRIVE_ON_HEADING_BEHAVIOR_TESTER_HPP_
17 #define BEHAVIORS__DRIVE_ON_HEADING__DRIVE_ON_HEADING_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/drive_on_heading.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_util/node_thread.hpp"
31 #include "geometry_msgs/msg/pose_stamped.hpp"
32 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
33 
34 #include "tf2/utils.h"
35 #include "tf2_ros/buffer.h"
36 #include "tf2_ros/transform_listener.h"
37 
38 namespace nav2_system_tests
39 {
40 
42 {
43 public:
44  using DriveOnHeading = nav2_msgs::action::DriveOnHeading;
45  using GoalHandleDriveOnHeading = rclcpp_action::ClientGoalHandle<DriveOnHeading>;
46 
49 
50  // Runs a single test with given target yaw
51  bool defaultDriveOnHeadingBehaviorTest(
52  const DriveOnHeading::Goal goal_msg,
53  double tolerance);
54 
55  void activate();
56 
57  void deactivate();
58 
59  bool isActive() const
60  {
61  return is_active_;
62  }
63 
64 private:
65  void sendInitialPose();
66 
67  void amclPoseCallback(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr);
68 
69  bool is_active_;
70  bool initial_pose_received_;
71  rclcpp::Time stamp_;
72 
73  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
74  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
75 
76  rclcpp::Node::SharedPtr node_;
77 
78  // Publisher to publish initial pose
79  rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
80 
81  // Subscriber for amcl pose
82  rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr subscription_;
83 
84  // Action client to call DriveOnHeading action
85  rclcpp_action::Client<DriveOnHeading>::SharedPtr client_ptr_;
86 };
87 
88 } // namespace nav2_system_tests
89 
90 #endif // BEHAVIORS__DRIVE_ON_HEADING__DRIVE_ON_HEADING_BEHAVIOR_TESTER_HPP_