Skip to content

Commit

Permalink
Fix for costmap nodes lifecycle status (#3009)
Browse files Browse the repository at this point in the history
Lifecycle status for global and local cost nodes not correct.
ros2 lifecycle/service commands  shows unconfigured for these two.
This is due to directly calling on_configure/on_activate/on_cleanup
calls in parent node.  This PR to replace on_xxxxxx() to
configure()/activate()/cleanup() calls of lifecycle base.

Signed-off-by: Arshad <arshad.mehmood@intel.com>
  • Loading branch information
arshadlab authored Jun 8, 2022
1 parent b70db7c commit a86e003
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 16 deletions.
16 changes: 8 additions & 8 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,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 @@ -122,7 +122,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
get_parameter("speed_limit_topic", speed_limit_topic);
get_parameter("failure_tolerance", failure_tolerance_);

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 @@ -213,11 +213,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 @@ -237,7 +237,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 @@ -246,7 +246,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 @@ -259,7 +259,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 @@ -271,7 +271,7 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & state)
controllers_.clear();

goal_checkers_.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 @@ -74,11 +74,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 @@ -154,14 +154,14 @@ 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_pose_->activate();
action_server_poses_->activate();
costmap_ros_->on_activate(state);
costmap_ros_->activate();

PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
Expand All @@ -187,14 +187,14 @@ 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_pose_->deactivate();
action_server_poses_->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 @@ -210,15 +210,15 @@ 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_pose_.reset();
action_server_poses_.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

0 comments on commit a86e003

Please sign in to comment.