Skip to content

Commit

Permalink
Constify the exported state interfaces to ConstSharedPtr
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Oct 7, 2024
1 parent 1c7a5d1 commit 1bb0eb3
Show file tree
Hide file tree
Showing 12 changed files with 40 additions and 38 deletions.
2 changes: 1 addition & 1 deletion hardware_interface/include/hardware_interface/actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class Actuator final
const rclcpp_lifecycle::State & error();

HARDWARE_INTERFACE_PUBLIC
std::vector<StateInterface::SharedPtr> export_state_interfaces();
std::vector<StateInterface::ConstSharedPtr> export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<CommandInterface::SharedPtr> export_command_interfaces();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
* \return vector of state interfaces
*/
[[deprecated(
"Replaced by vector<StateInterface::SharedPtr> on_export_state_interfaces() method. "
"Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
"Exporting is "
"handled "
"by the Framework.")]] virtual std::vector<StateInterface>
Expand Down Expand Up @@ -201,13 +201,13 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
*
* \return vector of shared pointers to the created and stored StateInterfaces
*/
virtual std::vector<StateInterface::SharedPtr> on_export_state_interfaces()
virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
{
// import the unlisted interfaces
std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
export_unlisted_state_interface_descriptions();

std::vector<StateInterface::SharedPtr> state_interfaces;
std::vector<StateInterface::ConstSharedPtr> state_interfaces;
state_interfaces.reserve(
unlisted_interface_descriptions.size() + joint_state_interfaces_.size());

Expand All @@ -220,15 +220,15 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
auto state_interface = std::make_shared<StateInterface>(description);
actuator_states_.insert(std::make_pair(name, state_interface));
unlisted_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}

for (const auto & [name, descr] : joint_state_interfaces_)
{
auto state_interface = std::make_shared<StateInterface>(descr);
actuator_states_.insert(std::make_pair(name, state_interface));
joint_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}
return state_interfaces;
}
Expand Down
1 change: 1 addition & 0 deletions hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,7 @@ class StateInterface : public Handle
using Handle::Handle;

using SharedPtr = std::shared_ptr<StateInterface>;
using ConstSharedPtr = std::shared_ptr<const StateInterface>;
};

class CommandInterface : public Handle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,23 +29,23 @@ class LoanedStateInterface
using Deleter = std::function<void(void)>;

[[deprecated("Replaced by the new version using shared_ptr")]] explicit LoanedStateInterface(
StateInterface & state_interface)
const StateInterface & state_interface)
: LoanedStateInterface(state_interface, nullptr)
{
}

[[deprecated("Replaced by the new version using shared_ptr")]] LoanedStateInterface(
StateInterface & state_interface, Deleter && deleter)
const StateInterface & state_interface, Deleter && deleter)
: state_interface_(state_interface), deleter_(std::forward<Deleter>(deleter))
{
}

explicit LoanedStateInterface(StateInterface::SharedPtr state_interface)
explicit LoanedStateInterface(StateInterface::ConstSharedPtr state_interface)
: LoanedStateInterface(state_interface, nullptr)
{
}

LoanedStateInterface(StateInterface::SharedPtr state_interface, Deleter && deleter)
LoanedStateInterface(StateInterface::ConstSharedPtr state_interface, Deleter && deleter)
: state_interface_(*state_interface), deleter_(std::forward<Deleter>(deleter))
{
}
Expand Down Expand Up @@ -78,7 +78,7 @@ class LoanedStateInterface
double get_value() const { return state_interface_.get_value(); }

protected:
StateInterface & state_interface_;
const StateInterface & state_interface_;
Deleter deleter_;
};

Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/include/hardware_interface/sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class Sensor final
const rclcpp_lifecycle::State & error();

HARDWARE_INTERFACE_PUBLIC
std::vector<StateInterface::SharedPtr> export_state_interfaces();
std::vector<StateInterface::ConstSharedPtr> export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::string get_name() const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
* \return vector of state interfaces
*/
[[deprecated(
"Replaced by vector<StateInterface::SharedPtr> on_export_state_interfaces() method. "
"Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
"Exporting is handled "
"by the Framework.")]] virtual std::vector<StateInterface>
export_state_interfaces()
Expand Down Expand Up @@ -185,13 +185,13 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
*
* \return vector of shared pointers to the created and stored StateInterfaces
*/
virtual std::vector<StateInterface::SharedPtr> on_export_state_interfaces()
virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
{
// import the unlisted interfaces
std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
export_unlisted_state_interface_descriptions();

std::vector<StateInterface::SharedPtr> state_interfaces;
std::vector<StateInterface::ConstSharedPtr> state_interfaces;
state_interfaces.reserve(
unlisted_interface_descriptions.size() + sensor_state_interfaces_.size());

Expand All @@ -203,7 +203,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
auto state_interface = std::make_shared<StateInterface>(description);
sensor_states_map_.insert(std::make_pair(name, state_interface));
unlisted_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}

for (const auto & [name, descr] : sensor_state_interfaces_)
Expand All @@ -212,7 +212,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
auto state_interface = std::make_shared<StateInterface>(descr);
sensor_states_map_.insert(std::make_pair(name, state_interface));
sensor_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}

return state_interfaces;
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/include/hardware_interface/system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class System final
const rclcpp_lifecycle::State & error();

HARDWARE_INTERFACE_PUBLIC
std::vector<StateInterface::SharedPtr> export_state_interfaces();
std::vector<StateInterface::ConstSharedPtr> export_state_interfaces();

HARDWARE_INTERFACE_PUBLIC
std::vector<CommandInterface::SharedPtr> export_command_interfaces();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
* \return vector of state interfaces
*/
[[deprecated(
"Replaced by vector<StateInterface::SharedPtr> on_export_state_interfaces() method. "
"Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
"Exporting is handled "
"by the Framework.")]] virtual std::vector<StateInterface>
export_state_interfaces()
Expand Down Expand Up @@ -221,13 +221,13 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
*
* \return vector of shared pointers to the created and stored StateInterfaces
*/
std::vector<StateInterface::SharedPtr> on_export_state_interfaces()
std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
{
// import the unlisted interfaces
std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
export_unlisted_state_interface_descriptions();

std::vector<StateInterface::SharedPtr> state_interfaces;
std::vector<StateInterface::ConstSharedPtr> state_interfaces;
state_interfaces.reserve(
unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
Expand All @@ -241,29 +241,29 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
auto state_interface = std::make_shared<StateInterface>(description);
system_states_.insert(std::make_pair(name, state_interface));
unlisted_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}

for (const auto & [name, descr] : joint_state_interfaces_)
{
auto state_interface = std::make_shared<StateInterface>(descr);
system_states_.insert(std::make_pair(name, state_interface));
joint_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}
for (const auto & [name, descr] : sensor_state_interfaces_)
{
auto state_interface = std::make_shared<StateInterface>(descr);
system_states_.insert(std::make_pair(name, state_interface));
sensor_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}
for (const auto & [name, descr] : gpio_state_interfaces_)
{
auto state_interface = std::make_shared<StateInterface>(descr);
system_states_.insert(std::make_pair(name, state_interface));
gpio_states_.push_back(state_interface);
state_interfaces.push_back(state_interface);
state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
}
return state_interfaces;
}
Expand Down
6 changes: 3 additions & 3 deletions hardware_interface/src/actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ const rclcpp_lifecycle::State & Actuator::error()
return impl_->get_lifecycle_state();
}

std::vector<StateInterface::SharedPtr> Actuator::export_state_interfaces()
std::vector<StateInterface::ConstSharedPtr> Actuator::export_state_interfaces()
{
// BEGIN (Handle export change): for backward compatibility, can be removed if
// export_command_interfaces() method is removed
Expand All @@ -222,11 +222,11 @@ std::vector<StateInterface::SharedPtr> Actuator::export_state_interfaces()

// BEGIN (Handle export change): for backward compatibility, can be removed if
// export_command_interfaces() method is removed
std::vector<StateInterface::SharedPtr> interface_ptrs;
std::vector<StateInterface::ConstSharedPtr> interface_ptrs;
interface_ptrs.reserve(interfaces.size());
for (auto const & interface : interfaces)
{
interface_ptrs.emplace_back(std::make_shared<StateInterface>(interface));
interface_ptrs.emplace_back(std::make_shared<const StateInterface>(interface));
}
return interface_ptrs;
// END: for backward compatibility
Expand Down
9 changes: 5 additions & 4 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::SharedPtr> interfaces = hardware.export_state_interfaces();
std::vector<StateInterface::ConstSharedPtr> interfaces = hardware.export_state_interfaces();
const auto interface_names = add_state_interfaces(interfaces);

RCLCPP_WARN(
Expand Down Expand Up @@ -678,7 +678,7 @@ class ResourceStorage
}
}

std::string add_state_interface(StateInterface::SharedPtr interface)
std::string add_state_interface(StateInterface::ConstSharedPtr interface)
{
auto interface_name = interface->get_name();
const auto [it, success] = state_interface_map_.emplace(interface_name, interface);
Expand All @@ -702,7 +702,8 @@ class ResourceStorage
* \returns list of interface names that are added into internal storage. The output is used to
* avoid additional iterations to cache interface names, e.g., for initializing info structures.
*/
std::vector<std::string> add_state_interfaces(std::vector<StateInterface::SharedPtr> & interfaces)
std::vector<std::string> add_state_interfaces(
std::vector<StateInterface::ConstSharedPtr> & interfaces)
{
std::vector<std::string> interface_names;
interface_names.reserve(interfaces.size());
Expand Down Expand Up @@ -1068,7 +1069,7 @@ class ResourceStorage
std::unordered_map<std::string, std::vector<std::string>> controllers_reference_interfaces_map_;

/// Storage of all available state interfaces
std::map<std::string, StateInterface::SharedPtr> state_interface_map_;
std::map<std::string, StateInterface::ConstSharedPtr> state_interface_map_;
/// Storage of all available command interfaces
std::map<std::string, CommandInterface::SharedPtr> command_interface_map_;

Expand Down
6 changes: 3 additions & 3 deletions hardware_interface/src/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ const rclcpp_lifecycle::State & Sensor::error()
return impl_->get_lifecycle_state();
}

std::vector<StateInterface::SharedPtr> Sensor::export_state_interfaces()
std::vector<StateInterface::ConstSharedPtr> Sensor::export_state_interfaces()
{
// BEGIN (Handle export change): for backward compatibility, can be removed if
// export_command_interfaces() method is removed
Expand All @@ -221,11 +221,11 @@ std::vector<StateInterface::SharedPtr> Sensor::export_state_interfaces()

// BEGIN (Handle export change): for backward compatibility, can be removed if
// export_command_interfaces() method is removed
std::vector<StateInterface::SharedPtr> interface_ptrs;
std::vector<StateInterface::ConstSharedPtr> interface_ptrs;
interface_ptrs.reserve(interfaces.size());
for (auto const & interface : interfaces)
{
interface_ptrs.emplace_back(std::make_shared<StateInterface>(interface));
interface_ptrs.emplace_back(std::make_shared<const StateInterface>(interface));
}
return interface_ptrs;
// END: for backward compatibility
Expand Down
6 changes: 3 additions & 3 deletions hardware_interface/src/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ const rclcpp_lifecycle::State & System::error()
return impl_->get_lifecycle_state();
}

std::vector<StateInterface::SharedPtr> System::export_state_interfaces()
std::vector<StateInterface::ConstSharedPtr> System::export_state_interfaces()
{
// BEGIN (Handle export change): for backward compatibility, can be removed if
// export_command_interfaces() method is removed
Expand All @@ -220,11 +220,11 @@ std::vector<StateInterface::SharedPtr> System::export_state_interfaces()

// BEGIN (Handle export change): for backward compatibility, can be removed if
// export_command_interfaces() method is removed
std::vector<StateInterface::SharedPtr> interface_ptrs;
std::vector<StateInterface::ConstSharedPtr> interface_ptrs;
interface_ptrs.reserve(interfaces.size());
for (auto const & interface : interfaces)
{
interface_ptrs.emplace_back(std::make_shared<StateInterface>(interface));
interface_ptrs.emplace_back(std::make_shared<const StateInterface>(interface));
}
return interface_ptrs;
// END: for backward compatibility
Expand Down

0 comments on commit 1bb0eb3

Please sign in to comment.