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
1 change: 0 additions & 1 deletion nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ class AmclNode : public nav2_util::LifecycleNode
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

// Since the sensor data from gazebo or the robot is not lifecycle enabled, we won't
// respond until we're in the active state
Expand Down
7 changes: 0 additions & 7 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -389,13 +389,6 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
AmclNode::on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
AmclNode::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
Expand Down
5 changes: 0 additions & 5 deletions nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,11 +82,6 @@ class BtNavigator : public nav2_util::LifecycleNode
* @return SUCCESS or FAILURE
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when in error state
* @param state Reference to LifeCycle node state
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

using Action = nav2_msgs::action::NavigateToPose;

Expand Down
7 changes: 0 additions & 7 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,13 +222,6 @@ BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
BtNavigator::on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
BtNavigator::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
Expand Down
6 changes: 0 additions & 6 deletions nav2_controller/include/nav2_controller/nav2_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,12 +102,6 @@ class ControllerServer : public nav2_util::LifecycleNode
* @return Success or Failure
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when in Error state
* @param state LifeCycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

using Action = nav2_msgs::action::FollowPath;
using ActionServer = nav2_util::SimpleActionServer<Action>;
Expand Down
7 changes: 0 additions & 7 deletions nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,13 +228,6 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & state)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
ControllerServer::on_error(const rclcpp_lifecycle::State &)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
ControllerServer::on_shutdown(const rclcpp_lifecycle::State &)
{
Expand Down
1 change: 0 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 @@ -97,7 +97,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

/**
* @brief Subscribes to sensor topics if necessary and starts costmap
Expand Down
7 changes: 0 additions & 7 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,13 +274,6 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
Costmap2DROS::on_error(const rclcpp_lifecycle::State &)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
Costmap2DROS::on_shutdown(const rclcpp_lifecycle::State &)
{
Expand Down
6 changes: 0 additions & 6 deletions nav2_map_server/include/nav2_map_server/map_saver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,12 +86,6 @@ class MapSaver : public nav2_util::LifecycleNode
* @return Success or Failure
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when Error is raised
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

/**
* @brief Map saving service callback
Expand Down
6 changes: 0 additions & 6 deletions nav2_map_server/include/nav2_map_server/map_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,12 +77,6 @@ class MapServer : public nav2_util::LifecycleNode
* @return Success or Failure
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when Error is raised
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

/**
* @brief Load the map YAML, image from map file name and
Expand Down
7 changes: 0 additions & 7 deletions nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,13 +95,6 @@ MapSaver::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
MapSaver::on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
MapSaver::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
Expand Down
7 changes: 0 additions & 7 deletions nav2_map_server/src/map_server/map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,13 +160,6 @@ MapServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
MapServer::on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
MapServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
Expand Down
6 changes: 0 additions & 6 deletions nav2_planner/include/nav2_planner/planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,12 +89,6 @@ class PlannerServer : public nav2_util::LifecycleNode
* @return SUCCESS or FAILURE
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when in error state
* @param state Reference to LifeCycle node state
* @return SUCCESS or FAILURE
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

using ActionServer = nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathToPose>;

Expand Down
7 changes: 0 additions & 7 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,13 +197,6 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & state)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
PlannerServer::on_error(const rclcpp_lifecycle::State &)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
PlannerServer::on_shutdown(const rclcpp_lifecycle::State &)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ class RecoveryServer : public nav2_util::LifecycleNode
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

std::shared_ptr<tf2_ros::Buffer> tf_;
std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
Expand Down
7 changes: 0 additions & 7 deletions nav2_recoveries/src/recovery_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,13 +169,6 @@ RecoveryServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
RecoveryServer::on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
RecoveryServer::on_shutdown(const rclcpp_lifecycle::State &)
{
Expand Down
8 changes: 8 additions & 0 deletions nav2_util/include/nav2_util/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,14 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
rclcpp_lifecycle::LifecycleNode::shared_from_this());
}

nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(
get_logger(),
"Lifecycle node %s does not have error state implemented", get_name());
return nav2_util::CallbackReturn::SUCCESS;
}

// bond connection to lifecycle manager
void createBond();
void destroyBond();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,11 +92,6 @@ class WaypointFollower : public nav2_util::LifecycleNode
* @return SUCCESS or FAILURE
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when in error state
* @param state Reference to LifeCycle node state
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

/**
* @brief Action server callbacks
Expand Down
7 changes: 0 additions & 7 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,13 +101,6 @@ WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
WaypointFollower::on_error(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
return nav2_util::CallbackReturn::SUCCESS;
}

nav2_util::CallbackReturn
WaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
Expand Down