Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 31 additions & 2 deletions nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,17 +31,31 @@ namespace nav2_costmap_2d

class Costmap2DROS;

/**
* @class ClearCostmapService
* @brief Exposes services to clear costmap objects in inclusive/exclusive regions or completely
*/
class ClearCostmapService
{
public:
/**
* @brief A constructor
*/
ClearCostmapService(const nav2_util::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap);

/**
* @brief A constructor
*/
ClearCostmapService() = delete;

// Clears the region outside of a user-specified area reverting to the static map
/**
* @brief Clears the region outside of a user-specified area reverting to the static map
*/
void clearRegion(double reset_distance, bool invert);

// Clears all layers
/**
* @brief Clears all layers
*/
void clearEntirely();

private:
Expand All @@ -57,27 +71,42 @@ class ClearCostmapService

// Server for clearing the costmap
rclcpp::Service<nav2_msgs::srv::ClearCostmapExceptRegion>::SharedPtr clear_except_service_;
/**
* @brief Callback to clear costmap except in a given region
*/
void clearExceptRegionCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav2_msgs::srv::ClearCostmapExceptRegion::Request> request,
const std::shared_ptr<nav2_msgs::srv::ClearCostmapExceptRegion::Response> response);

rclcpp::Service<nav2_msgs::srv::ClearCostmapAroundRobot>::SharedPtr clear_around_service_;
/**
* @brief Callback to clear costmap in a given region
*/
void clearAroundRobotCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundRobot::Request> request,
const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundRobot::Response> response);

rclcpp::Service<nav2_msgs::srv::ClearEntireCostmap>::SharedPtr clear_entire_service_;
/**
* @brief Callback to clear costmap
*/
void clearEntireCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav2_msgs::srv::ClearEntireCostmap::Request> request,
const std::shared_ptr<nav2_msgs::srv::ClearEntireCostmap::Response> response);

/**
* @brief Function used to clear a given costmap layer
*/
void clearLayerRegion(
std::shared_ptr<CostmapLayer> & costmap, double pose_x, double pose_y, double reset_distance,
bool invert);

/**
* @brief Get the robot's position in the costmap using the master costmap
*/
bool getPosition(double & x, double & y) const;
};

Expand Down
30 changes: 26 additions & 4 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,11 +258,19 @@ class Costmap2D
*/
double getResolution() const;

/**
* @brief Set the default background value of the costmap
* @param c default value
*/
void setDefaultValue(unsigned char c)
{
default_value_ = c;
}

/**
* @brief Get the default background value of the costmap
* @return default value
*/
unsigned char getDefaultValue()
{
return default_value_;
Expand Down Expand Up @@ -309,12 +317,21 @@ class Costmap2D
*/
bool saveMap(std::string file_name);

/**
* @brief Resize the costmap
*/
void resizeMap(
unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
double origin_y);

/**
* @brief Reset the costmap in bounds
*/
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn);

/**
* @brief Reset the costmap in bounds to a value
*/
void resetMapToValue(
unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value);

Expand Down Expand Up @@ -390,7 +407,8 @@ class Costmap2D
* @param y0 The starting y coordinate
* @param x1 The ending x coordinate
* @param y1 The ending y coordinate
* @param max_length The maximum desired length of the segment... allows you to not go all the way to the endpoint
* @param max_length The maximum desired length of the segment...
* allows you to not go all the way to the endpoint
* @param min_length The minimum desired length of the segment
*/
template<class ActionType>
Expand Down Expand Up @@ -426,7 +444,7 @@ class Costmap2D
if (abs_dx >= abs_dy) {
int error_y = abs_dx / 2;

// Subtract min_length from total length since initial point (x0, y0) has been adjusted by min Z
// Subtract minlength from length since initial point (x0, y0)has been adjusted by min Z
length = (unsigned int)(scale * abs_dx) - min_length;

bresenham2D(
Expand All @@ -437,15 +455,16 @@ class Costmap2D
// otherwise y is dominant
int error_x = abs_dy / 2;

// Subtract min_length from total length since initial point (x0, y0) has been adjusted by min Z
// Subtract minlength from total length since initial point (x0, y0) has been adjusted by min Z
length = (unsigned int)(scale * abs_dy) - min_length;
bresenham2D(
at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, length);
}

private:
/**
* @brief A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step
* @brief A 2D implementation of Bresenham's raytracing algorithm...
* applies an action at each step
*/
template<class ActionType>
inline void bresenham2D(
Expand All @@ -467,6 +486,9 @@ class Costmap2D
at(offset);
}

/**
* @brief get the sign of an int
*/
inline int sign(int x)
{
return x > 0 ? 1.0 : -1.0;
Expand Down
15 changes: 15 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,19 +78,34 @@ class Costmap2DPublisher
*/
~Costmap2DPublisher();

/**
* @brief Configure node
*/
void on_configure() {}

/**
* @brief Activate node
*/
void on_activate()
{
costmap_pub_->on_activate();
costmap_update_pub_->on_activate();
costmap_raw_pub_->on_activate();
}

/**
* @brief deactivate node
*/
void on_deactivate()
{
costmap_pub_->on_deactivate();
costmap_update_pub_->on_deactivate();
costmap_raw_pub_->on_deactivate();
}

/**
* @brief Cleanup node
*/
void on_cleanup() {}

/** @brief Include the given bounds in the changed-rectangle. */
Expand Down
36 changes: 35 additions & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,12 +90,34 @@ class Costmap2DROS : public nav2_util::LifecycleNode
const std::string & parent_namespace,
const std::string & local_namespace);

/**
* @brief A destructor
*/
~Costmap2DROS();

/**
* @brief Configure node
*/
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;

/**
* @brief Activate node
*/
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;

/**
* @brief Deactivate node
*/
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;

/**
* @brief Cleanup node
*/
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;

/**
* @brief shutdown node
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;

/**
Expand All @@ -120,6 +142,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode
*/
void resume();

/**
* @brief Update the map with the layered costmap / plugins
*/
void updateMap();

/**
Expand Down Expand Up @@ -190,6 +215,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode
return robot_base_frame_;
}

/**
* @brief Get the layered costmap object used in the node
*/
LayeredCostmap * getLayeredCostmap()
{
return layered_costmap_.get();
Expand Down Expand Up @@ -284,6 +312,10 @@ class Costmap2DROS : public nav2_util::LifecycleNode
std::unique_ptr<LayeredCostmap> layered_costmap_{nullptr};
std::string name_;
std::string parent_namespace_;

/**
* @brief Function on timer for costmap update
*/
void mapUpdateLoop(double frequency);
bool map_update_thread_shutdown_{false};
bool stop_updates_{false};
Expand All @@ -294,7 +326,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode
rclcpp::Duration publish_cycle_{1, 0};
pluginlib::ClassLoader<Layer> plugin_loader_{"nav2_costmap_2d", "nav2_costmap_2d::Layer"};

// Parameters
/**
* @brief Get parameters for node
*/
void getParameters();
bool always_send_full_costmap_{false};
std::string footprint_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,13 @@ namespace nav2_costmap_2d
class CostmapFilter : public Layer
{
public:
/**
* @brief A constructor
*/
CostmapFilter();
/**
* @brief A destructor
*/
~CostmapFilter();

/**
Expand All @@ -69,18 +75,53 @@ class CostmapFilter : public Layer
return access_;
}

/** Layer API **/
/**
* @brief Initialization process of layer on startup
*/
virtual void onInitialize() final;

/**
* @brief Update the bounds of the master costmap by this layer's update dimensions
* @param robot_x X pose of robot
* @param robot_y Y pose of robot
* @param robot_yaw Robot orientation
* @param min_x X min map coord of the window to update
* @param min_y Y min map coord of the window to update
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
virtual void updateBounds(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y, double * max_x, double * max_y) final;

/**
* @brief Update the costs in the master costmap in the window
* @param master_grid The master costmap grid to update
* @param min_x X min map coord of the window to update
* @param min_y Y min map coord of the window to update
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
virtual void updateCosts(
nav2_costmap_2d::Costmap2D & master_grid,
int min_i, int min_j, int max_i, int max_j) final;

/**
* @brief Activate the layer
*/
virtual void activate() final;
/**
* @brief Deactivate the layer
*/
virtual void deactivate() final;
/**
* @brief Reset the layer
*/
virtual void reset() final;

/**
* @brief If clearing operations should be processed on this layer or not
*/
virtual bool isClearable() {return false;}

/** CostmapFilter API **/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,25 +50,51 @@
namespace nav2_costmap_2d
{

/**
* @class KeepoutFilter
* @brief Reads in a keepout mask and marks keepout regions in the map
* to prevent planning or control in restricted areas
*/
class KeepoutFilter : public CostmapFilter
{
public:
/**
* @brief A constructor
*/
KeepoutFilter();

/**
* @brief Initialize the filter and subscribe to the info topic
*/
void initializeFilter(
const std::string & filter_info_topic);

/**
* @brief Process the keepout layer at the current pose / bounds / grid
*/
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);

/**
* @brief Reset the costmap filter / topic / info
*/
void resetFilter();

/**
* @brief If this filter is active
*/
bool isActive();

private:
/**
* @brief Callback for the filter information
*/
void filterInfoCallback(const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg);
/**
* @brief Callback for the filter mask
*/
void maskCallback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg);

rclcpp::Subscription<nav2_msgs::msg::CostmapFilterInfo>::SharedPtr filter_info_sub_;
Expand Down
Loading