Skip to content

Commit

Permalink
constify the part of the controller interface exported state interfaces
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Oct 7, 2024
1 parent 1bb0eb3 commit 2205989
Show file tree
Hide file tree
Showing 9 changed files with 14 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class ChainableControllerInterface : public ControllerInterfaceBase
bool is_chainable() const final;

CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface::SharedPtr> export_state_interfaces() final;
std::vector<hardware_interface::StateInterface::ConstSharedPtr> export_state_interfaces() final;

CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::CommandInterface::SharedPtr> export_reference_interfaces() final;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase
* \returns empty list.
*/
CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface::SharedPtr> export_state_interfaces() final;
std::vector<hardware_interface::StateInterface::ConstSharedPtr> export_state_interfaces() final;

/**
* Controller has no reference interfaces.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,8 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
* \returns list of state interfaces for preceding controllers.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual std::vector<hardware_interface::StateInterface::SharedPtr> export_state_interfaces() = 0;
virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
export_state_interfaces() = 0;

/**
* Set chained mode of a chainable controller. This method triggers internal processes to switch
Expand Down
7 changes: 4 additions & 3 deletions controller_interface/src/chainable_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,11 @@ return_type ChainableControllerInterface::update(
return ret;
}

std::vector<hardware_interface::StateInterface::SharedPtr>
std::vector<hardware_interface::StateInterface::ConstSharedPtr>
ChainableControllerInterface::export_state_interfaces()
{
auto state_interfaces = on_export_state_interfaces();
std::vector<hardware_interface::StateInterface::SharedPtr> state_interfaces_ptrs_vec;
std::vector<hardware_interface::StateInterface::ConstSharedPtr> state_interfaces_ptrs_vec;
state_interfaces_ptrs_vec.reserve(state_interfaces.size());
ordered_exported_state_interfaces_.reserve(state_interfaces.size());
exported_state_interface_names_.reserve(state_interfaces.size());
Expand Down Expand Up @@ -88,7 +88,8 @@ ChainableControllerInterface::export_state_interfaces()
}
ordered_exported_state_interfaces_.push_back(state_interface);
exported_state_interface_names_.push_back(interface_name);
state_interfaces_ptrs_vec.push_back(state_interface);
state_interfaces_ptrs_vec.push_back(
std::const_pointer_cast<const hardware_interface::StateInterface>(state_interface));
}

return state_interfaces_ptrs_vec;
Expand Down
2 changes: 1 addition & 1 deletion controller_interface/src/controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ ControllerInterface::ControllerInterface() : ControllerInterfaceBase() {}

bool ControllerInterface::is_chainable() const { return false; }

std::vector<hardware_interface::StateInterface::SharedPtr>
std::vector<hardware_interface::StateInterface::ConstSharedPtr>
ControllerInterface::export_state_interfaces()
{
return {};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ TEST_F(ChainableControllerInterfaceTest, interfaces_prefix_is_not_node_name)
std::runtime_error);
ASSERT_THAT(exported_reference_interfaces, IsEmpty());
// expect empty return because interface prefix is not equal to the node name
std::vector<hardware_interface::StateInterface::SharedPtr> exported_state_interfaces;
std::vector<hardware_interface::StateInterface::ConstSharedPtr> exported_state_interfaces;
EXPECT_THROW(
{ exported_state_interfaces = controller.export_state_interfaces(); }, std::runtime_error);
ASSERT_THAT(exported_state_interfaces, IsEmpty());
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -785,7 +785,7 @@ controller_interface::return_type ControllerManager::configure_controller(
get_logger(),
"Controller '%s' is chainable. Interfaces are being exported to resource manager.",
controller_name.c_str());
std::vector<hardware_interface::StateInterface::SharedPtr> state_interfaces;
std::vector<hardware_interface::StateInterface::ConstSharedPtr> state_interfaces;
std::vector<hardware_interface::CommandInterface::SharedPtr> ref_interfaces;
try
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
* \param[in] interfaces list of controller's state interfaces as StateInterfaces.
*/
void import_controller_exported_state_interfaces(
const std::string & controller_name, std::vector<StateInterface::SharedPtr> & interfaces);
const std::string & controller_name, std::vector<StateInterface::ConstSharedPtr> & interfaces);

/// Get list of exported tate interface of a controller.
/**
Expand Down
4 changes: 2 additions & 2 deletions hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -608,7 +608,7 @@ class ResourceStorage
template <class HardwareT>
void import_state_interfaces(HardwareT & hardware)
{
std::vector<StateInterface::ConstSharedPtr> interfaces = hardware.export_state_interfaces();
auto interfaces = hardware.export_state_interfaces();
const auto interface_names = add_state_interfaces(interfaces);

RCLCPP_WARN(
Expand Down Expand Up @@ -1242,7 +1242,7 @@ bool ResourceManager::state_interface_is_available(const std::string & name) con

// CM API: Called in "callback/slow"-thread
void ResourceManager::import_controller_exported_state_interfaces(
const std::string & controller_name, std::vector<StateInterface::SharedPtr> & interfaces)
const std::string & controller_name, std::vector<StateInterface::ConstSharedPtr> & interfaces)
{
std::lock_guard<std::recursive_mutex> guard(resource_interfaces_lock_);
auto interface_names = resource_storage_->add_state_interfaces(interfaces);
Expand Down

0 comments on commit 2205989

Please sign in to comment.