Skip to content
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

Fix for costmap nodes lifecycle status #3005

Merged
merged 1 commit into from
Jun 8, 2022
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
16 changes: 8 additions & 8 deletions nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ ControllerServer::~ControllerServer()
}

nav2_util::CallbackReturn
ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
{
auto node = shared_from_this();

Expand Down Expand Up @@ -102,7 +102,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
get_parameter("min_theta_velocity_threshold", min_theta_velocity_threshold_);
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);

costmap_ros_->on_configure(state);
costmap_ros_->configure();

try {
progress_checker_type_ = nav2_util::get_plugin_type_param(node, progress_checker_id_);
Expand Down Expand Up @@ -171,11 +171,11 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
}

nav2_util::CallbackReturn
ControllerServer::on_activate(const rclcpp_lifecycle::State & state)
ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");

costmap_ros_->on_activate(state);
costmap_ros_->activate();
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->activate();
Expand All @@ -187,7 +187,7 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & state)
}

nav2_util::CallbackReturn
ControllerServer::on_deactivate(const rclcpp_lifecycle::State & state)
ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Deactivating");

Expand All @@ -196,7 +196,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & state)
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->deactivate();
}
costmap_ros_->on_deactivate(state);
costmap_ros_->deactivate();

publishZeroVelocity();
vel_publisher_->on_deactivate();
Expand All @@ -205,7 +205,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & state)
}

nav2_util::CallbackReturn
ControllerServer::on_cleanup(const rclcpp_lifecycle::State & state)
ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");

Expand All @@ -215,7 +215,7 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & state)
it->second->cleanup();
}
controllers_.clear();
costmap_ros_->on_cleanup(state);
costmap_ros_->cleanup();

// Release any allocated resources
action_server_.reset();
Expand Down
16 changes: 8 additions & 8 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,11 +64,11 @@ PlannerServer::~PlannerServer()
}

nav2_util::CallbackReturn
PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Configuring");

costmap_ros_->on_configure(state);
costmap_ros_->configure();
costmap_ = costmap_ros_->getCostmap();

RCLCPP_DEBUG(
Expand Down Expand Up @@ -139,13 +139,13 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
}

nav2_util::CallbackReturn
PlannerServer::on_activate(const rclcpp_lifecycle::State & state)
PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");

plan_publisher_->on_activate();
action_server_->activate();
costmap_ros_->on_activate(state);
costmap_ros_->activate();

PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
Expand All @@ -156,13 +156,13 @@ PlannerServer::on_activate(const rclcpp_lifecycle::State & state)
}

nav2_util::CallbackReturn
PlannerServer::on_deactivate(const rclcpp_lifecycle::State & state)
PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Deactivating");

action_server_->deactivate();
plan_publisher_->on_deactivate();
costmap_ros_->on_deactivate(state);
costmap_ros_->deactivate();

PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
Expand All @@ -173,14 +173,14 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & state)
}

nav2_util::CallbackReturn
PlannerServer::on_cleanup(const rclcpp_lifecycle::State & state)
PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");

action_server_.reset();
plan_publisher_.reset();
tf_.reset();
costmap_ros_->on_cleanup(state);
costmap_ros_->cleanup();

PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
Expand Down