Skip to content

[CostmapTopicCollisionChecker] Alternative constructor with footprint string #4926

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 4 commits into from
Apr 16, 2025
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
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,15 @@ class CostmapTopicCollisionChecker
FootprintSubscriber & footprint_sub,
std::string name = "collision_checker");

/**
* @brief Alternative constructor with a footprint string instead of a subscriber. It needs to be
* defined relative to the robot frame
*/
CostmapTopicCollisionChecker(
CostmapSubscriber & costmap_sub,
std::string footprint_string,
std::string name = "collision_checker");

/**
* @brief A destructor
*/
Expand Down Expand Up @@ -90,10 +99,11 @@ class CostmapTopicCollisionChecker
// Name used for logging
std::string name_;
CostmapSubscriber & costmap_sub_;
FootprintSubscriber & footprint_sub_;
FootprintSubscriber * footprint_sub_ = nullptr;
FootprintCollisionChecker<std::shared_ptr<Costmap2D>> collision_checker_;
rclcpp::Clock::SharedPtr clock_;
Footprint footprint_;
std::string footprint_string_;
};

} // namespace nav2_costmap_2d
Expand Down
20 changes: 18 additions & 2 deletions nav2_costmap_2d/src/costmap_topic_collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,23 @@
std::string name)
: name_(name),
costmap_sub_(costmap_sub),
footprint_sub_(footprint_sub),
footprint_sub_(&footprint_sub),
collision_checker_(nullptr)
{}

CostmapTopicCollisionChecker::CostmapTopicCollisionChecker(

Check warning on line 45 in nav2_costmap_2d/src/costmap_topic_collision_checker.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/src/costmap_topic_collision_checker.cpp#L45

Added line #L45 was not covered by tests
CostmapSubscriber & costmap_sub,
std::string footprint_string,
std::string name)
: name_(name),
costmap_sub_(costmap_sub),
collision_checker_(nullptr)

Check warning on line 51 in nav2_costmap_2d/src/costmap_topic_collision_checker.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/src/costmap_topic_collision_checker.cpp#L48-L51

Added lines #L48 - L51 were not covered by tests
{
if (!makeFootprintFromString(footprint_string, footprint_)) {
throw CollisionCheckerException("Failed to create footprint from string");

Check warning on line 54 in nav2_costmap_2d/src/costmap_topic_collision_checker.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/src/costmap_topic_collision_checker.cpp#L53-L54

Added lines #L53 - L54 were not covered by tests
}
}

bool CostmapTopicCollisionChecker::isCollisionFree(
const geometry_msgs::msg::Pose2D & pose,
bool fetch_costmap_and_footprint)
Expand Down Expand Up @@ -90,7 +103,10 @@
{
if (fetch_latest_footprint) {
std_msgs::msg::Header header;
if (!footprint_sub_.getFootprintInRobotFrame(footprint_, header)) {

// if footprint_sub_ was not initialized (alternative constructor), we are using the
// footprint built from the footprint_string alternative constructor argument.
if (footprint_sub_ && !footprint_sub_->getFootprintInRobotFrame(footprint_, header)) {
throw CollisionCheckerException("Current footprint not available.");
}
}
Expand Down
Loading