15 #ifndef PLANNING__PLANNER_TESTER_HPP_
16 #define PLANNING__PLANNER_TESTER_HPP_
18 #include <gtest/gtest.h>
24 #include "rclcpp/rclcpp.hpp"
25 #include "rclcpp_action/rclcpp_action.hpp"
26 #include "nav2_msgs/action/compute_path_to_pose.hpp"
27 #include "nav_msgs/msg/occupancy_grid.hpp"
28 #include "nav2_msgs/msg/costmap.hpp"
29 #include "nav2_msgs/srv/get_costmap.hpp"
30 #include "nav2_msgs/srv/is_path_valid.hpp"
31 #include "visualization_msgs/msg/marker.hpp"
32 #include "nav2_util/costmap.hpp"
33 #include "nav2_util/node_thread.hpp"
34 #include "geometry_msgs/msg/pose_stamped.hpp"
35 #include "geometry_msgs/msg/transform_stamped.hpp"
36 #include "tf2_msgs/msg/tf_message.hpp"
37 #include "nav2_planner/planner_server.hpp"
38 #include "tf2_ros/transform_broadcaster.h"
40 namespace nav2_system_tests
56 std::cout <<
"" << std::endl;
58 std::cout << costmap_ros_->getCostmap()->getCharMap()[i] <<
" ";
60 std::cout <<
"" << std::endl;
65 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(
66 *(costmap_ros_->getCostmap()->getMutex()));
68 nav2_msgs::msg::CostmapMetaData prop;
69 nav2_msgs::msg::Costmap cm = costmap->
get_costmap(prop);
71 costmap_ros_->getCostmap()->resizeMap(
72 prop.size_x, prop.size_y,
73 prop.resolution, prop.origin.position.x, prop.origin.position.x);
75 volatile unsigned char * costmap_ptr = costmap_ros_->getCostmap()->getCharMap();
77 costmap_ptr =
new unsigned char[prop.size_x * prop.size_y];
78 std::copy(cm.data.begin(), cm.data.end(), costmap_ptr);
82 const geometry_msgs::msg::PoseStamped & goal,
83 nav_msgs::msg::Path & path)
85 geometry_msgs::msg::PoseStamped start;
86 if (!nav2_util::getCurrentPose(start, *tf_,
"map",
"base_link", 0.1)) {
90 auto dummy_cancel_checker = []() {
return false;};
91 path = planners_[
"GridBased"]->createPlan(start, goal, dummy_cancel_checker);
95 if (!path.poses.size()) {
104 void onCleanup(
const rclcpp_lifecycle::State & state)
109 void onActivate(
const rclcpp_lifecycle::State & state)
114 void onDeactivate(
const rclcpp_lifecycle::State & state)
119 void onConfigure(
const rclcpp_lifecycle::State & state)
125 enum class TaskStatus : int8_t
135 using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped;
136 using ComputePathToPoseResult = nav_msgs::msg::Path;
146 void loadDefaultMap();
149 void loadSimpleCostmap(
const nav2_util::TestCostmap & testCostmapType);
154 bool defaultPlannerTest(
155 ComputePathToPoseResult & path,
156 const double deviation_tolerance = 1.0);
160 bool defaultPlannerRandomTests(
161 const unsigned int number_tests,
162 const float acceptable_fail_ratio);
164 bool isPathValid(nav_msgs::msg::Path & path);
169 TaskStatus createPlan(
170 const ComputePathToPoseCommand & goal,
171 ComputePathToPoseResult & path
177 bool using_fake_costmap_;
180 bool trinary_costmap_;
181 bool track_unknown_space_;
182 int lethal_threshold_;
183 int unknown_cost_value_;
184 nav2_util::TestCostmap testCostmapType_;
187 std::shared_ptr<nav_msgs::msg::OccupancyGrid> map_;
190 std::unique_ptr<nav2_util::Costmap> costmap_;
193 std::shared_ptr<NavFnPlannerTester> planner_tester_;
196 rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr path_valid_client_;
199 std::unique_ptr<nav2_util::NodeThread> spin_thread_;
202 std::unique_ptr<geometry_msgs::msg::TransformStamped> base_transform_;
203 std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
204 rclcpp::TimerBase::SharedPtr transform_timer_;
205 void publishRobotTransform();
206 void startRobotTransform();
207 void updateRobotPosition(
const geometry_msgs::msg::Point & position);
210 rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr map_pub_;
211 rclcpp::TimerBase::SharedPtr map_timer_;
212 rclcpp::WallRate map_publish_rate_;
219 const geometry_msgs::msg::Point & robot_position,
220 const ComputePathToPoseCommand & goal,
221 ComputePathToPoseResult & path);
223 bool isCollisionFree(
const ComputePathToPoseResult & path);
225 bool isWithinTolerance(
226 const geometry_msgs::msg::Point & robot_position,
227 const ComputePathToPoseCommand & goal,
228 const ComputePathToPoseResult & path)
const;
230 bool isWithinTolerance(
231 const geometry_msgs::msg::Point & robot_position,
232 const ComputePathToPoseCommand & goal,
233 const ComputePathToPoseResult & path,
234 const double deviationTolerance,
235 const ComputePathToPoseResult & reference_path)
const;
237 void printPath(
const ComputePathToPoseResult & path)
const;
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins...
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
PlannerServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_planner::PlannerServer.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
Class for a single layered costmap initialized from an occupancy grid representing the map.
nav2_msgs::msg::Costmap get_costmap(const nav2_msgs::msg::CostmapMetaData &specifications)
Get a costmap message from this object.