Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
speed_filter.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2020 Samsung Research Russia
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the <ORGANIZATION> nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Alexey Merzlyakov
36  *********************************************************************/
37 
38 #ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
40 
41 #include <memory>
42 #include <string>
43 
44 #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
45 
46 #include "nav2_msgs/msg/costmap_filter_info.hpp"
47 #include "nav2_msgs/msg/speed_limit.hpp"
48 
49 namespace nav2_costmap_2d
50 {
57 class SpeedFilter : public CostmapFilter
58 {
59 public:
63  SpeedFilter();
64 
68  void initializeFilter(
69  const std::string & filter_info_topic);
70 
74  void process(
75  nav2_costmap_2d::Costmap2D & master_grid,
76  int min_i, int min_j, int max_i, int max_j,
77  const geometry_msgs::msg::Pose2D & pose);
78 
82  void resetFilter();
83 
87  bool isActive();
88 
89 private:
93  void filterInfoCallback(const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg);
97  void maskCallback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
98 
99  rclcpp::Subscription<nav2_msgs::msg::CostmapFilterInfo>::SharedPtr filter_info_sub_;
100  rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr mask_sub_;
101 
102  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_pub_;
103 
104  nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_;
105 
106  std::string global_frame_; // Frame of current layer (master_grid)
107 
108  double base_, multiplier_;
109  bool percentage_;
110  double speed_limit_, speed_limit_prev_;
111 };
112 
113 } // namespace nav2_costmap_2d
114 
115 #endif // NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
: CostmapFilter basic class. It is inherited from Layer in order to avoid hidden problems when the sh...
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
void resetFilter()
Reset the costmap filter / topic / info.
void process(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose2D &pose)
Process the keepout layer at the current pose / bounds / grid.
bool isActive()
If this filter is active.