Skip to content

Commit

Permalink
Merge branch 'master' into integrate/pal_statistics
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jan 15, 2025
2 parents b72f313 + 751cd85 commit c0df59d
Show file tree
Hide file tree
Showing 18 changed files with 201 additions and 85 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -317,6 +317,13 @@ class ControllerManager : public rclcpp::Node

void initialize_parameters();

/**
* Call shutdown to change the given controller lifecycle node to the finalized state.
*
* \param[in] controller controller to be shutdown.
*/
void shutdown_controller(controller_manager::ControllerSpec & controller) const;

/**
* Clear request lists used when switching controllers. The lists are shared between "callback"
* and "control loop" threads.
Expand Down
64 changes: 38 additions & 26 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,13 @@ static const rmw_qos_profile_t qos_services = {
false};
#endif

inline bool is_controller_unconfigured(
const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_lifecycle_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED;
}

inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_lifecycle_state().id() ==
Expand Down Expand Up @@ -702,39 +709,17 @@ controller_interface::return_type ControllerManager::unload_controller(
return controller_interface::return_type::ERROR;
}

RCLCPP_DEBUG(get_logger(), "Cleanup controller");
RCLCPP_DEBUG(get_logger(), "Shutdown controller");
controller_chain_spec_cleanup(controller_chain_spec_, controller_name);
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
if (is_controller_inactive(*controller.c))
if (is_controller_inactive(*controller.c) || is_controller_unconfigured(*controller.c))
{
RCLCPP_DEBUG(
get_logger(), "Controller '%s' is cleaned-up before unloading!", controller_name.c_str());
get_logger(), "Controller '%s' is shutdown before unloading!", controller_name.c_str());
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
try
{
const auto new_state = controller.c->get_node()->cleanup();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
RCLCPP_WARN(
get_logger(), "Failed to clean-up the controller '%s' before unloading!",
controller_name.c_str());
}
}
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(),
"Caught exception of type : %s while cleaning up the controller '%s' before unloading: %s",
typeid(e).name(), controller_name.c_str(), e.what());
}
catch (...)
{
RCLCPP_ERROR(
get_logger(), "Failed to clean-up the controller '%s' before unloading",
controller_name.c_str());
}
shutdown_controller(controller);
}
executor_->remove_node(controller.c->get_node()->get_node_base_interface());
to.erase(found_it);
Expand All @@ -752,6 +737,33 @@ controller_interface::return_type ControllerManager::unload_controller(
return controller_interface::return_type::OK;
}

void ControllerManager::shutdown_controller(controller_manager::ControllerSpec & controller) const
{
try
{
const auto new_state = controller.c->get_node()->shutdown();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
{
RCLCPP_WARN(
get_logger(), "Failed to shutdown the controller '%s' before unloading!",
controller.info.name.c_str());
}
}
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(),
"Caught exception of type : %s while shutdown the controller '%s' before unloading: %s",
typeid(e).name(), controller.info.name.c_str(), e.what());
}
catch (...)
{
RCLCPP_ERROR(
get_logger(), "Failed to shutdown the controller '%s' before unloading",
controller.info.name.c_str());
}
}

std::vector<ControllerSpec> ControllerManager::get_loaded_controllers() const
{
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
Expand Down
9 changes: 9 additions & 0 deletions controller_manager/test/test_controller/test_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,15 @@ CallbackReturn TestController::on_cleanup(const rclcpp_lifecycle::State & /*prev
return CallbackReturn::SUCCESS;
}

CallbackReturn TestController::on_shutdown(const rclcpp_lifecycle::State &)
{
if (shutdown_calls)
{
(*shutdown_calls)++;
}
return CallbackReturn::SUCCESS;
}

void TestController::set_command_interface_configuration(
const controller_interface::InterfaceConfiguration & cfg)
{
Expand Down
7 changes: 5 additions & 2 deletions controller_manager/test/test_controller/test_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class TestController : public controller_interface::ControllerInterface

CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;

CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;

void set_command_interface_configuration(
const controller_interface::InterfaceConfiguration & cfg);

Expand All @@ -66,9 +68,10 @@ class TestController : public controller_interface::ControllerInterface
rclcpp::Service<example_interfaces::srv::SetBool>::SharedPtr service_;
unsigned int internal_counter = 0;
bool simulate_cleanup_failure = false;
// Variable where we store when cleanup was called, pointer because the controller
// is usually destroyed after cleanup
// Variable where we store when shutdown was called, pointer because the controller
// is usually destroyed after shutdown
size_t * cleanup_calls = nullptr;
size_t * shutdown_calls = nullptr;
controller_interface::InterfaceConfiguration cmd_iface_cfg_;
controller_interface::InterfaceConfiguration state_iface_cfg_;

Expand Down
4 changes: 2 additions & 2 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
EXPECT_EQ(controller_interface::return_type::OK, unload_future.get());

EXPECT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
test_controller->get_lifecycle_state().id());
EXPECT_EQ(1, test_controller.use_count());
}
Expand Down Expand Up @@ -429,7 +429,7 @@ TEST_P(TestControllerManagerWithStrictness, async_controller_lifecycle)
EXPECT_EQ(controller_interface::return_type::OK, unload_future.get());

EXPECT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
test_controller->get_lifecycle_state().id());
EXPECT_EQ(1, test_controller.use_count());
}
Expand Down
18 changes: 9 additions & 9 deletions controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -395,14 +395,14 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv)
ASSERT_GT(test_controller.use_count(), 1)
<< "Controller manager should have have a copy of this shared ptr";

cleanup_calls = 0;
test_controller->cleanup_calls = &cleanup_calls;
size_t shutdown_calls = 0;
test_controller->shutdown_calls = &shutdown_calls;
test_controller.reset(); // destroy our copy of the controller

request->force_kill = false;
result = call_service_and_wait(*client, request, srv_executor, true);
ASSERT_TRUE(result->ok);
ASSERT_EQ(cleanup_calls, 1u);
ASSERT_EQ(shutdown_calls, 1u);
ASSERT_EQ(test_controller.use_count(), 0)
<< "No more references to the controller after reloading.";
test_controller.reset();
Expand All @@ -428,8 +428,8 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv)
<< "Controller manager should still have have a copy of "
"this shared ptr, no unloading was performed";

cleanup_calls = 0;
test_controller->cleanup_calls = &cleanup_calls;
shutdown_calls = 0;
test_controller->shutdown_calls = &shutdown_calls;
test_controller.reset(); // destroy our copy of the controller

// Force stop active controller
Expand All @@ -439,7 +439,7 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv)

ASSERT_EQ(test_controller_weak.use_count(), 0)
<< "No more references to the controller after reloading.";
ASSERT_EQ(cleanup_calls, 1u)
ASSERT_EQ(shutdown_calls, 1u)
<< "Controller should have been stopped and cleaned up with force_kill = true";
}

Expand Down Expand Up @@ -491,7 +491,7 @@ TEST_F(TestControllerManagerSrvs, unload_controller_srv)
result = call_service_and_wait(*client, request, srv_executor, true);
ASSERT_TRUE(result->ok);
EXPECT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
test_controller->get_lifecycle_state().id());
EXPECT_EQ(0u, cm_->get_loaded_controllers().size());
}
Expand Down Expand Up @@ -526,7 +526,7 @@ TEST_F(TestControllerManagerSrvs, robot_description_on_load_and_unload_controlle
unload_request->name = test_controller::TEST_CONTROLLER_NAME;
auto result = call_service_and_wait(*unload_client, unload_request, srv_executor, true);
EXPECT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
test_controller->get_lifecycle_state().id());
EXPECT_EQ(0u, cm_->get_loaded_controllers().size());

Expand Down Expand Up @@ -578,7 +578,7 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv)
unload_request->name = test_controller::TEST_CONTROLLER_NAME;
ASSERT_TRUE(call_service_and_wait(*unload_client, unload_request, srv_executor, true)->ok);
EXPECT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
test_controller->get_lifecycle_state().id());
EXPECT_EQ(0u, cm_->get_loaded_controllers().size());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,12 @@ TestControllerWithInterfaces::on_cleanup(const rclcpp_lifecycle::State & /*previ
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
TestControllerWithInterfaces::on_shutdown(const rclcpp_lifecycle::State & /*previous_state*/)
{
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}

} // namespace test_controller_with_interfaces

#include "pluginlib/class_list_macros.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,9 @@ class TestControllerWithInterfaces : public controller_interface::ControllerInte

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state) override;

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state) override;
};

} // namespace test_controller_with_interfaces
Expand Down
4 changes: 2 additions & 2 deletions joint_limits/include/joint_limits/joint_limiter_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ class JointLimiterInterface
* \returns true if limits are enforced, otherwise false.
*/
virtual bool enforce(
JointLimitsStateDataType & current_joint_states,
const JointLimitsStateDataType & current_joint_states,
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt)
{
joint_limits_ = *(updated_limits_.readFromRT());
Expand Down Expand Up @@ -234,7 +234,7 @@ class JointLimiterInterface
* \returns true if limits are enforced, otherwise false.
*/
virtual bool on_enforce(
JointLimitsStateDataType & current_joint_states,
const JointLimitsStateDataType & current_joint_states,
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0;

/** \brief Checks if the logging interface is set.
Expand Down
2 changes: 1 addition & 1 deletion joint_limits/include/joint_limits/joint_limits_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ bool is_limited(double value, double min, double max);
*/
PositionLimits compute_position_limits(
const joint_limits::JointLimits & limits, const std::optional<double> & act_vel,
const std::optional<double> & prev_command_pos, double dt);
const std::optional<double> & act_pos, const std::optional<double> & prev_command_pos, double dt);

/**
* @brief Computes the velocity limits based on the position and acceleration limits.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class JointSaturationLimiter : public JointLimiterInterface<JointLimitsStateData
* \returns true if limits are enforced, otherwise false.
*/
bool on_enforce(
JointLimitsStateDataType & current_joint_states,
const JointLimitsStateDataType & current_joint_states,
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) override;

protected:
Expand Down
2 changes: 1 addition & 1 deletion joint_limits/include/joint_limits/joint_soft_limiter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class JointSoftLimiter : public JointSaturationLimiter<JointControlInterfacesDat
}

bool on_enforce(
JointControlInterfacesData & actual, JointControlInterfacesData & desired,
const JointControlInterfacesData & actual, JointControlInterfacesData & desired,
const rclcpp::Duration & dt) override;

bool has_soft_position_limits(const joint_limits::SoftJointLimits & soft_joint_limits)
Expand Down
8 changes: 5 additions & 3 deletions joint_limits/src/joint_limits_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ bool is_limited(double value, double min, double max) { return value < min || va

PositionLimits compute_position_limits(
const joint_limits::JointLimits & limits, const std::optional<double> & act_vel,
const std::optional<double> & prev_command_pos, double dt)
const std::optional<double> & act_pos, const std::optional<double> & prev_command_pos, double dt)
{
PositionLimits pos_limits(limits.min_position, limits.max_position);
if (limits.has_velocity_limits)
Expand All @@ -50,8 +50,10 @@ PositionLimits compute_position_limits(
: limits.max_velocity;
const double max_vel = std::min(limits.max_velocity, delta_vel);
const double delta_pos = max_vel * dt;
pos_limits.lower_limit = std::max(prev_command_pos.value() - delta_pos, pos_limits.lower_limit);
pos_limits.upper_limit = std::min(prev_command_pos.value() + delta_pos, pos_limits.upper_limit);
const double position_reference =
act_pos.has_value() ? act_pos.value() : prev_command_pos.value();
pos_limits.lower_limit = std::max(position_reference - delta_pos, pos_limits.lower_limit);
pos_limits.upper_limit = std::min(position_reference + delta_pos, pos_limits.upper_limit);
}
internal::check_and_swap_limits(pos_limits.lower_limit, pos_limits.upper_limit);
return pos_limits;
Expand Down
6 changes: 3 additions & 3 deletions joint_limits/src/joint_range_limiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ bool JointSaturationLimiter<JointControlInterfacesData>::on_init()

template <>
bool JointSaturationLimiter<JointControlInterfacesData>::on_enforce(
JointControlInterfacesData & actual, JointControlInterfacesData & desired,
const JointControlInterfacesData & actual, JointControlInterfacesData & desired,
const rclcpp::Duration & dt)
{
bool limits_enforced = false;
Expand Down Expand Up @@ -112,8 +112,8 @@ bool JointSaturationLimiter<JointControlInterfacesData>::on_enforce(

if (desired.has_position())
{
const auto limits =
compute_position_limits(joint_limits, actual.velocity, prev_command_.position, dt_seconds);
const auto limits = compute_position_limits(
joint_limits, actual.velocity, actual.position, prev_command_.position, dt_seconds);
limits_enforced = is_limited(desired.position.value(), limits.lower_limit, limits.upper_limit);
desired.position = std::clamp(desired.position.value(), limits.lower_limit, limits.upper_limit);
}
Expand Down
Loading

0 comments on commit c0df59d

Please sign in to comment.