17 #ifndef BEHAVIOR_TREE__SERVER_HANDLER_HPP_
18 #define BEHAVIOR_TREE__SERVER_HANDLER_HPP_
26 #include "nav2_msgs/srv/clear_entire_costmap.hpp"
27 #include "nav2_msgs/action/compute_path_to_pose.hpp"
28 #include "nav2_msgs/action/follow_path.hpp"
29 #include "nav2_msgs/action/spin.hpp"
30 #include "nav2_msgs/action/back_up.hpp"
31 #include "nav2_msgs/action/wait.hpp"
32 #include "nav2_msgs/action/drive_on_heading.hpp"
33 #include "nav2_msgs/action/compute_path_through_poses.hpp"
34 #include "nav2_msgs/action/compute_route.hpp"
35 #include "nav2_msgs/action/smooth_path.hpp"
37 #include "geometry_msgs/msg/point_stamped.hpp"
39 #include "rclcpp/rclcpp.hpp"
41 #include "dummy_action_server.hpp"
42 #include "dummy_service.hpp"
44 namespace nav2_system_tests
54 geometry_msgs::msg::PoseStamped pose;
55 pose.header.stamp = node->get_clock()->now();
56 pose.header.frame_id =
"map";
57 pose.pose.position.x = 0.0;
58 pose.pose.position.y = 0.0;
59 pose.pose.position.z = 0.0;
60 pose.pose.orientation.x = 0.0;
61 pose.pose.orientation.y = 0.0;
62 pose.pose.orientation.z = 0.0;
63 pose.pose.orientation.w = 1.0;
65 result_->path.header.stamp = node->now();
66 result_->path.header.frame_id = pose.header.frame_id;
67 for (
int i = 0; i < 6; ++i) {
68 result_->path.poses.push_back(pose);
73 void updateResultForFailure(
74 std::shared_ptr<nav2_msgs::action::ComputePathToPose::Result>
77 result->error_code = nav2_msgs::action::ComputePathToPose::Result::TIMEOUT;
78 result->error_msg =
"Timeout";
89 void updateResultForFailure(
90 std::shared_ptr<nav2_msgs::action::FollowPath::Result>
93 result->error_code = nav2_msgs::action::FollowPath::Result::NO_VALID_CONTROL;
94 result->error_msg =
"No valid control";
109 bool isActive()
const
117 std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_local_costmap_server;
118 std::unique_ptr<DummyService<nav2_msgs::srv::ClearEntireCostmap>> clear_global_costmap_server;
119 std::unique_ptr<DummyComputePathToPoseActionServer> compute_path_to_pose_server;
120 std::unique_ptr<DummyFollowPathActionServer> follow_path_server;
121 std::unique_ptr<DummyActionServer<nav2_msgs::action::Spin>> spin_server;
122 std::unique_ptr<DummyActionServer<nav2_msgs::action::Wait>> wait_server;
123 std::unique_ptr<DummyActionServer<nav2_msgs::action::BackUp>> backup_server;
124 std::unique_ptr<DummyActionServer<nav2_msgs::action::ComputeRoute>> compute_route_server;
125 std::unique_ptr<DummyActionServer<nav2_msgs::action::SmoothPath>> smoother_server;
126 std::unique_ptr<DummyActionServer<nav2_msgs::action::DriveOnHeading>> drive_on_heading_server;
127 std::unique_ptr<DummyActionServer<nav2_msgs::action::ComputePathThroughPoses>> ntp_server;
133 rclcpp::Node::SharedPtr node_;
134 std::shared_ptr<std::thread> server_thread_;