Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Takes in a map generated from SLAM to add costs to costmap. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp>
Public Member Functions | |
StaticLayer () | |
Static Layer constructor. | |
virtual | ~StaticLayer () |
Static Layer destructor. | |
virtual void | onInitialize () |
Initialization process of layer on startup. | |
virtual void | activate () |
Activate this layer. | |
virtual void | deactivate () |
Deactivate this layer. | |
virtual void | reset () |
Reset this costmap. | |
virtual bool | isClearable () |
If clearing operations should be processed on this layer or not. | |
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. More... | |
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. More... | |
virtual void | matchSize () |
Match the size of the master costmap. | |
![]() | |
CostmapLayer () | |
CostmapLayer constructor. | |
bool | isDiscretized () |
If layer is discrete. | |
virtual void | clearArea (int start_x, int start_y, int end_x, int end_y, bool invert) |
Clear an are in the costmap with the given dimension if invert, then clear everything except these dimensions. | |
void | addExtraBounds (double mx0, double my0, double mx1, double my1) |
![]() | |
Layer () | |
A constructor. | |
virtual | ~Layer () |
A destructor. | |
void | initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2_util::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group) |
Initialization process of layer on startup. | |
virtual void | onFootprintChanged () |
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. | |
std::string | getName () const |
Get the name of the costmap layer. | |
bool | isCurrent () const |
Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More... | |
bool | isEnabled () const |
Gets whether the layer is enabled. | |
const std::vector< geometry_msgs::msg::Point > & | getFootprint () const |
Convenience function for layered_costmap_->getFootprint(). | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterValue &value) |
Convenience functions for declaring ROS parameters. | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterType ¶m_type) |
Convenience functions for declaring ROS parameters. | |
bool | hasParameter (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
std::string | getFullName (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
![]() | |
Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0) | |
Constructor for a costmap. More... | |
Costmap2D (const Costmap2D &map) | |
Copy constructor for a costmap, creates a copy efficiently. More... | |
Costmap2D (const nav_msgs::msg::OccupancyGrid &map) | |
Constructor for a costmap from an OccupancyGrid map. More... | |
Costmap2D & | operator= (const Costmap2D &map) |
Overloaded assignment operator. More... | |
bool | copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y) |
Turn this costmap into a copy of a window of a costmap passed in. More... | |
bool | copyWindow (const Costmap2D &source, unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn, unsigned int dx0, unsigned int dy0) |
Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap. More... | |
Costmap2D () | |
Default constructor. | |
virtual | ~Costmap2D () |
Destructor. | |
unsigned char | getCost (unsigned int mx, unsigned int my) const |
Get the cost of a cell in the costmap. More... | |
unsigned char | getCost (unsigned int index) const |
Get the cost of a cell in the costmap. More... | |
void | setCost (unsigned int mx, unsigned int my, unsigned char cost) |
Set the cost of a cell in the costmap. More... | |
void | mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const |
Convert from map coordinates to world coordinates. More... | |
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const |
Convert from world coordinates to map coordinates. More... | |
bool | worldToMapContinuous (double wx, double wy, float &mx, float &my) const |
Convert from world coordinates to map coordinates. More... | |
void | worldToMapNoBounds (double wx, double wy, int &mx, int &my) const |
Convert from world coordinates to map coordinates without checking for legal bounds. More... | |
void | worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const |
Convert from world coordinates to map coordinates, constraining results to legal bounds. More... | |
unsigned int | getIndex (unsigned int mx, unsigned int my) const |
Given two map coordinates... compute the associated index. More... | |
void | indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const |
Given an index... compute the associated map coordinates. More... | |
unsigned char * | getCharMap () const |
Will return a pointer to the underlying unsigned char array used as the costmap. More... | |
unsigned int | getSizeInCellsX () const |
Accessor for the x size of the costmap in cells. More... | |
unsigned int | getSizeInCellsY () const |
Accessor for the y size of the costmap in cells. More... | |
double | getSizeInMetersX () const |
Accessor for the x size of the costmap in meters. More... | |
double | getSizeInMetersY () const |
Accessor for the y size of the costmap in meters. More... | |
double | getOriginX () const |
Accessor for the x origin of the costmap. More... | |
double | getOriginY () const |
Accessor for the y origin of the costmap. More... | |
double | getResolution () const |
Accessor for the resolution of the costmap. More... | |
void | setDefaultValue (unsigned char c) |
Set the default background value of the costmap. More... | |
unsigned char | getDefaultValue () |
Get the default background value of the costmap. More... | |
bool | setConvexPolygonCost (const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value) |
Sets the cost of a convex polygon to a desired value. More... | |
void | polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
Get the map cells that make up the outline of a polygon. More... | |
void | convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
Get the map cells that fill a convex polygon. More... | |
virtual void | updateOrigin (double new_origin_x, double new_origin_y) |
Move the origin of the costmap to a new location.... keeping data when it can. More... | |
bool | saveMap (std::string file_name) |
Save the costmap out to a pgm file. More... | |
void | resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y) |
Resize the costmap. | |
void | resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn) |
Reset the costmap in bounds. | |
void | resetMapToValue (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value) |
Reset the costmap in bounds to a value. | |
unsigned int | cellDistance (double world_dist) |
Given distance in the world... convert it to cells. More... | |
mutex_t * | getMutex () |
Protected Member Functions | |
void | getParameters () |
Get parameters of layer. | |
void | processMap (const nav_msgs::msg::OccupancyGrid &new_map) |
Process a new map coming from a topic. | |
void | incomingMap (const nav_msgs::msg::OccupancyGrid::SharedPtr new_map) |
Callback to update the costmap's map from the map_server. More... | |
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 area of the map. | |
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 utilize. | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
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. | |
![]() | |
void | updateWithTrueOverwrite (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithOverwrite (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithMax (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithMaxWithoutUnknownOverwrite (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | updateWithAddition (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
void | touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y) |
void | useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y) |
CombinationMethod | combination_method_from_int (const int value) |
Converts an integer to a CombinationMethod enum and logs on failure. More... | |
![]() | |
template<typename data_type > | |
void | copyMapRegion (data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y) |
Copy a region of a source map into a destination map. More... | |
virtual void | deleteMaps () |
Deletes the costmap, static_map, and markers data structures. | |
virtual void | resetMaps () |
Resets the costmap and static_map to be unknown space. | |
virtual void | initMaps (unsigned int size_x, unsigned int size_y) |
Initializes the costmap, static_map, and markers data structures. More... | |
template<class ActionType > | |
void | raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX, unsigned int min_length=0) |
Raytrace a line and apply some action at each step. More... | |
Protected Attributes | |
std::vector< geometry_msgs::msg::Point > | transformed_footprint_ |
bool | footprint_clearing_enabled_ |
std::string | global_frame_ |
The global frame for the costmap. | |
std::string | map_frame_ |
bool | has_updated_data_ {false} |
frame that map is located in | |
unsigned int | x_ {0} |
unsigned int | y_ {0} |
unsigned int | width_ {0} |
unsigned int | height_ {0} |
rclcpp::Subscription< nav_msgs::msg::OccupancyGrid >::SharedPtr | map_sub_ |
rclcpp::Subscription< map_msgs::msg::OccupancyGridUpdate >::SharedPtr | map_update_sub_ |
std::string | map_topic_ |
bool | map_subscribe_transient_local_ |
bool | subscribe_to_updates_ |
bool | track_unknown_space_ |
bool | use_maximum_ |
unsigned char | lethal_threshold_ |
unsigned char | unknown_cost_value_ |
bool | trinary_costmap_ |
bool | map_received_ {false} |
bool | map_received_in_update_bounds_ {false} |
tf2::Duration | transform_tolerance_ |
nav_msgs::msg::OccupancyGrid::SharedPtr | map_buffer_ |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
![]() | |
bool | has_extra_bounds_ |
![]() | |
LayeredCostmap * | layered_costmap_ |
std::string | name_ |
tf2_ros::Buffer * | tf_ |
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
rclcpp::Clock::SharedPtr | clock_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("nav2_costmap_2d")} |
bool | current_ |
bool | enabled_ |
std::unordered_set< std::string > | local_params_ |
![]() | |
unsigned int | size_x_ |
unsigned int | size_y_ |
double | resolution_ |
double | origin_x_ |
double | origin_y_ |
unsigned char * | costmap_ |
unsigned char | default_value_ |
Additional Inherited Members | |
![]() | |
typedef std::recursive_mutex | mutex_t |
Takes in a map generated from SLAM to add costs to costmap.
Definition at line 60 of file static_layer.hpp.
|
protected |
Callback executed when a parameter change is detected.
event | ParameterEvent message |
Definition at line 475 of file static_layer.cpp.
References has_updated_data_.
Referenced by getParameters().
|
protected |
Callback to update the costmap's map from the map_server.
new_map | The map to put into the costmap. The origin of the new map along with its size will determine what parts of the costmap's static map are overwritten. |
Definition at line 285 of file static_layer.cpp.
References processMap().
Referenced by onInitialize().
|
virtual |
Update the bounds of the master costmap by this layer's update dimensions.
robot_x | X pose of robot |
robot_y | Y pose of robot |
robot_yaw | Robot orientation |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y max map coord of the window to update |
Implements nav2_costmap_2d::Layer.
Definition at line 342 of file static_layer.cpp.
References has_updated_data_, nav2_costmap_2d::LayeredCostmap::isRolling(), nav2_costmap_2d::Costmap2D::mapToWorld(), processMap(), and updateFootprint().
|
virtual |
Update the costs in the master costmap in the window.
master_grid | The master costmap grid to update |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y max map coord of the window to update |
Implements nav2_costmap_2d::Layer.
Definition at line 402 of file static_layer.cpp.
References nav2_costmap_2d::Costmap2D::getCost(), nav2_costmap_2d::LayeredCostmap::getCostmap(), global_frame_, nav2_costmap_2d::LayeredCostmap::isRolling(), nav2_costmap_2d::Costmap2D::mapToWorld(), nav2_costmap_2d::Costmap2D::setConvexPolygonCost(), nav2_costmap_2d::Costmap2D::setCost(), and nav2_costmap_2d::Costmap2D::worldToMap().