38 #ifndef NAV2_COSTMAP_2D__STATIC_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__STATIC_LAYER_HPP_
45 #include "map_msgs/msg/occupancy_grid_update.hpp"
46 #include "rclcpp/rclcpp.hpp"
47 #include "nav2_costmap_2d/costmap_layer.hpp"
48 #include "nav2_costmap_2d/layered_costmap.hpp"
49 #include "nav_msgs/msg/occupancy_grid.hpp"
50 #include "nav2_costmap_2d/footprint.hpp"
106 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
107 double * min_y,
double * max_x,
double * max_y);
119 int min_i,
int min_j,
int max_i,
int max_j);
135 void processMap(
const nav_msgs::msg::OccupancyGrid & new_map);
143 void incomingMap(
const nav_msgs::msg::OccupancyGrid::SharedPtr new_map);
148 void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update);
163 bool isEqual(
double a,
double b,
double epsilon);
169 rcl_interfaces::msg::SetParametersResult
172 std::vector<geometry_msgs::msg::Point> transformed_footprint_;
173 bool footprint_clearing_enabled_;
174 bool restore_cleared_footprint_;
179 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
185 std::string map_frame_;
191 unsigned int width_{0};
192 unsigned int height_{0};
194 nav2::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr map_sub_;
195 nav2::Subscription<map_msgs::msg::OccupancyGridUpdate>::SharedPtr map_update_sub_;
198 std::string map_topic_;
199 bool map_subscribe_transient_local_;
200 bool subscribe_to_updates_;
201 bool track_unknown_space_;
203 unsigned char lethal_threshold_;
204 unsigned char unknown_cost_value_;
205 bool trinary_costmap_;
206 bool map_received_{
false};
207 bool map_received_in_update_bounds_{
false};
208 tf2::Duration transform_tolerance_;
209 nav_msgs::msg::OccupancyGrid::SharedPtr map_buffer_;
211 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
Takes in a map generated from SLAM to add costs to costmap.
void getParameters()
Get parameters of layer.
virtual ~StaticLayer()
Static Layer destructor.
virtual void deactivate()
Deactivate this layer.
bool has_updated_data_
frame that map is located in
unsigned char interpretValue(unsigned char value)
Interpret the value in the static map given on the topic to convert into costs for the costmap to uti...
StaticLayer()
Static Layer constructor.
virtual void matchSize()
Match the size of the master costmap.
virtual void onInitialize()
Initialization process of layer on startup.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Clear costmap layer info below the robot's footprint.
virtual void activate()
Activate this layer.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
Callback to update the costmap's map from the map_server (or SLAM) with an update in a particular are...
bool isEqual(double a, double b, double epsilon)
Check if two double values are equal within a given epsilon.
void incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
Callback to update the costmap's map from the map_server.
std::string global_frame_
The global frame for the costmap.
void processMap(const nav_msgs::msg::OccupancyGrid &new_map)
Process a new map coming from a topic.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual void reset()
Reset this costmap.