Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap_topic_collision_checker.hpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Modified by: Shivang Patel (shivaan14@gmail.com)
16 
17 #ifndef NAV2_COSTMAP_2D__COSTMAP_TOPIC_COLLISION_CHECKER_HPP_
18 #define NAV2_COSTMAP_2D__COSTMAP_TOPIC_COLLISION_CHECKER_HPP_
19 
20 #include <string>
21 #include <vector>
22 #include <memory>
23 #include <algorithm>
24 
25 #include "rclcpp/rclcpp.hpp"
26 #include "geometry_msgs/msg/pose_stamped.hpp"
27 #include "geometry_msgs/msg/pose2_d.hpp"
28 #include "nav2_costmap_2d/costmap_2d.hpp"
29 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
30 #include "nav2_costmap_2d/costmap_subscriber.hpp"
31 #include "nav2_costmap_2d/footprint_subscriber.hpp"
32 
33 namespace nav2_costmap_2d
34 {
41 {
42 public:
47  CostmapSubscriber & costmap_sub,
48  FootprintSubscriber & footprint_sub,
49  std::string name = "collision_checker");
50 
55 
63  double scorePose(
64  const geometry_msgs::msg::Pose2D & pose,
65  bool fetch_costmap_and_footprint = true);
66 
74  bool isCollisionFree(
75  const geometry_msgs::msg::Pose2D & pose,
76  bool fetch_costmap_and_footprint = true);
77 
78 protected:
86  Footprint getFootprint(
87  const geometry_msgs::msg::Pose2D & pose,
88  bool fetch_latest_footprint = true);
89 
90  // Name used for logging
91  std::string name_;
92  CostmapSubscriber & costmap_sub_;
93  FootprintSubscriber & footprint_sub_;
95  rclcpp::Clock::SharedPtr clock_;
96  Footprint footprint_;
97 };
98 
99 } // namespace nav2_costmap_2d
100 
101 #endif // NAV2_COSTMAP_2D__COSTMAP_TOPIC_COLLISION_CHECKER_HPP_
Subscribes to the costmap via a ros topic.
Using a costmap via a ros topic, this object is used to find if robot poses are in collision with the...
Footprint getFootprint(const geometry_msgs::msg::Pose2D &pose, bool fetch_latest_footprint=true)
Get a footprint at a set pose.
double scorePose(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns the obstacle footprint score for a particular pose.
CostmapTopicCollisionChecker(CostmapSubscriber &costmap_sub, FootprintSubscriber &footprint_sub, std::string name="collision_checker")
A constructor.
bool isCollisionFree(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns if a pose is collision free.
~CostmapTopicCollisionChecker()=default
A destructor.
Checker for collision with a footprint on a costmap.
Subscriber to the footprint topic to get current robot footprint (if changing) for use in collision a...