Skip to content

Commit

Permalink
enable ReflowComments to also use ColumnLimit on comments (#1037)
Browse files Browse the repository at this point in the history
* enable ReflowComments to also use ColumnLimit on comments

* apply the formatting changes of clang format : ReflowComments

---------

Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com>
  • Loading branch information
saikishor and bmagyar committed May 30, 2023
1 parent bdf7e44 commit 0637782
Show file tree
Hide file tree
Showing 19 changed files with 289 additions and 255 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,6 @@ ConstructorInitializerIndentWidth: 0
ContinuationIndentWidth: 2
DerivePointerAlignment: false
PointerAlignment: Middle
ReflowComments: false
ReflowComments: true
IncludeBlocks: Preserve
...
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@ class ChainableControllerInterface : public ControllerInterfaceBase
virtual ~ChainableControllerInterface() = default;

/**
* Control step update. Command interfaces are updated based on on reference inputs and current states.
* Control step update. Command interfaces are updated based on on reference inputs and current
* states.
* **The method called in the (real-time) control loop.**
*
* \param[in] time The time at the start of this control loop iteration
Expand Down Expand Up @@ -83,7 +84,9 @@ class ChainableControllerInterface : public ControllerInterfaceBase
*
* \param[in] flag marking a switch to or from chained mode.
*
* \returns true if controller successfully switched between "chained" and "external" mode. \default returns true so the method don't have to be overridden if controller can always switch chained mode.
* \returns true if controller successfully switched between "chained" and "external" mode.
* \default returns true so the method don't have to be overridden if controller can always switch
* chained mode.
*/
virtual bool on_set_chained_mode(bool chained_mode);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,15 +74,13 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy

/// Get configuration for controller's required command interfaces.
/**
* Method used by the controller_manager to get the set of command interfaces used by the controller.
* Each controller can use individual method to determine interface names that in simples case
* have the following format: `<joint>/<interface>`.
* The method is called only in `inactive` or `active` state, i.e., `on_configure` has to be
* called first.
* The configuration is used to check if controller can be activated and to claim interfaces from
* hardware.
* The claimed interfaces are populated in the
* \ref ControllerInterfaceBase::command_interfaces_ "command_interfaces_" member.
* Method used by the controller_manager to get the set of command interfaces used by the
* controller. Each controller can use individual method to determine interface names that in
* simples case have the following format: `<joint>/<interface>`. The method is called only in
* `inactive` or `active` state, i.e., `on_configure` has to be called first. The configuration is
* used to check if controller can be activated and to claim interfaces from hardware. The claimed
* interfaces are populated in the \ref ControllerInterfaceBase::command_interfaces_
* "command_interfaces_" member.
*
* \returns configuration of command interfaces.
*/
Expand Down Expand Up @@ -131,7 +129,8 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
virtual CallbackReturn on_init() = 0;

/**
* Control step update. Command interfaces are updated based on on reference inputs and current states.
* Control step update. Command interfaces are updated based on on reference inputs and current
* states.
* **The method called in the (real-time) control loop.**
*
* \param[in] time The time at the start of this control loop iteration
Expand Down
26 changes: 13 additions & 13 deletions controller_interface/include/controller_interface/helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,19 +23,19 @@ namespace controller_interface
{
/// Reorder interfaces with references according to joint names or full interface names.
/**
* Method to reorder and check if all expected interfaces are provided for the joint.
* Fill `ordered_interfaces` with references from `unordered_interfaces` in the same order as in
* `ordered_names`.
*
* \param[in] unordered_interfaces vector with loaned unordered state or command interfaces.
* \param[in] ordered_names vector with ordered names to order \p unordered_interfaces.
* The valued inputs are list of joint names or interface full names.
* If joint names are used for ordering, \p interface_type specifies valid interface.
* If full interface names are used for ordering, \p interface_type should be empty string ("").
* \param[in] interface_type used for ordering interfaces with respect to joint names.
* \param[out] ordered_interfaces vector with ordered interfaces.
* \return true if all interfaces or joints in \p ordered_names are found, otherwise false.
*/
* Method to reorder and check if all expected interfaces are provided for the joint.
* Fill `ordered_interfaces` with references from `unordered_interfaces` in the same order as in
* `ordered_names`.
*
* \param[in] unordered_interfaces vector with loaned unordered state or command interfaces.
* \param[in] ordered_names vector with ordered names to order \p unordered_interfaces.
* The valued inputs are list of joint names or interface full names.
* If joint names are used for ordering, \p interface_type specifies valid interface.
* If full interface names are used for ordering, \p interface_type should be empty string ("").
* \param[in] interface_type used for ordering interfaces with respect to joint names.
* \param[out] ordered_interfaces vector with ordered interfaces.
* \return true if all interfaces or joints in \p ordered_names are found, otherwise false.
*/
template <typename T>
bool get_ordered_interfaces(
std::vector<T> & unordered_interfaces, const std::vector<std::string> & ordered_names,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -318,8 +318,8 @@ class ControllerManager : public rclcpp::Node
const std::string & command_interface);

/**
* Clear request lists used when switching controllers. The lists are shared between "callback" and
* "control loop" threads.
* Clear request lists used when switching controllers. The lists are shared between "callback"
* and "control loop" threads.
*/
void clear_requests();

Expand Down Expand Up @@ -428,23 +428,26 @@ class ControllerManager : public rclcpp::Node
* lists match and returns a reference to it
* This referenced list can be modified safely until switch_updated_controller_list()
* is called, at this point the RT thread may start using it at any time
* \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by rt list
* \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by
* rt list
*/
std::vector<ControllerSpec> & get_unused_list(
const std::lock_guard<std::recursive_mutex> & guard);

/// get_updated_list Returns a const reference to the most updated list.
/**
* \warning May or may not being used by the realtime thread, read-only reference for safety
* \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by rt list
* \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by
* rt list
*/
const std::vector<ControllerSpec> & get_updated_list(
const std::lock_guard<std::recursive_mutex> & guard) const;

/**
* switch_updated_list Switches the "updated" and "outdated" lists, and waits
* until the RT thread is using the new "updated" list.
* \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by rt list
* \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by
* rt list
*/
void switch_updated_list(const std::lock_guard<std::recursive_mutex> & guard);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,9 @@ namespace hardware_interface
/**
* The typical examples are conveyors or motors.
*
* Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
* with the following meaning:
* Methods return values have type
* rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following
* meaning:
*
* \returns CallbackReturn::SUCCESS method execution was successful.
* \returns CallbackReturn::FAILURE method execution has failed and and can be called again.
Expand All @@ -46,7 +47,8 @@ namespace hardware_interface
* The hardware ends after each method in a state with the following meaning:
*
* UNCONFIGURED (on_init, on_cleanup):
* Hardware is initialized but communication is not started and therefore no interface is available.
* Hardware is initialized but communication is not started and therefore no interface is
* available.
*
* INACTIVE (on_configure, on_deactivate):
* Communication with the hardware is started and it is configured.
Expand Down Expand Up @@ -126,12 +128,12 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
*
* \note This is a non-realtime evaluation of whether a set of command interface claims are
* possible, and call to start preparing data structures for the upcoming switch that will occur.
* \note All starting and stopping interface keys are passed to all components, so the function should
* return return_type::OK by default when given interface keys not relevant for this component.
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
* \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping.
* \return return_type::OK if the new command interface combination can be prepared,
* or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
* \note All starting and stopping interface keys are passed to all components, so the function
* should return return_type::OK by default when given interface keys not relevant for this
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs
* stopping. \return return_type::OK if the new command interface combination can be prepared, or
* if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
*/
virtual return_type prepare_command_mode_switch(
const std::vector<std::string> & /*start_interfaces*/,
Expand All @@ -145,11 +147,11 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
* Perform the mode-switching for the new command interface combination.
*
* \note This is part of the realtime update loop, and should be fast.
* \note All starting and stopping interface keys are passed to all components, so the function should
* return return_type::OK by default when given interface keys not relevant for this component.
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
* \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping.
* \return return_type::OK if the new command interface combination can be switched to,
* \note All starting and stopping interface keys are passed to all components, so the function
* should return return_type::OK by default when given interface keys not relevant for this
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs
* stopping. \return return_type::OK if the new command interface combination can be switched to,
* or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
*/
virtual return_type perform_command_mode_switch(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ namespace hardware_interface
{
/// Search XML snippet from URDF for information about a control component.
/**
* \param[in] urdf string with robot's URDF
* \return vector filled with information about robot's control resources
* \throws std::runtime_error if a robot attribute or tag is not found
*/
* \param[in] urdf string with robot's URDF
* \return vector filled with information about robot's control resources
* \throws std::runtime_error if a robot attribute or tag is not found
*/
HARDWARE_INTERFACE_PUBLIC
std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string & urdf);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -188,8 +188,9 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
/**
* Return list of cached controller names that use the hardware with name \p hardware_name.
*
* \param[in] hardware_name the name of the hardware for which cached controllers should be returned.
* \returns list of cached controller names that depend on hardware with name \p hardware_name.
* \param[in] hardware_name the name of the hardware for which cached controllers should be
* returned. \returns list of cached controller names that depend on hardware with name \p
* hardware_name.
*/
std::vector<std::string> get_cached_controllers_to_hardware(const std::string & hardware_name);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,9 @@ namespace hardware_interface
/**
* The typical examples are Force-Torque Sensor (FTS), Interial Measurement Unit (IMU).
*
* Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
* with the following meaning:
* Methods return values have type
* rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following
* meaning:
*
* \returns CallbackReturn::SUCCESS method execution was successful.
* \returns CallbackReturn::FAILURE method execution has failed and and can be called again.
Expand All @@ -46,7 +47,8 @@ namespace hardware_interface
* The hardware ends after each method in a state with the following meaning:
*
* UNCONFIGURED (on_init, on_cleanup):
* Hardware is initialized but communication is not started and therefore no interface is available.
* Hardware is initialized but communication is not started and therefore no interface is
* available.
*
* INACTIVE (on_configure, on_deactivate):
* Communication with the hardware is started and it is configured.
Expand Down
30 changes: 16 additions & 14 deletions hardware_interface/include/hardware_interface/system_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,9 @@ namespace hardware_interface
* The common examples for these types of hardware are multi-joint systems with or without sensors
* such as industrial or humanoid robots.
*
* Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
* with the following meaning:
* Methods return values have type
* rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following
* meaning:
*
* \returns CallbackReturn::SUCCESS method execution was successful.
* \returns CallbackReturn::FAILURE method execution has failed and and can be called again.
Expand All @@ -47,7 +48,8 @@ namespace hardware_interface
* The hardware ends after each method in a state with the following meaning:
*
* UNCONFIGURED (on_init, on_cleanup):
* Hardware is initialized but communication is not started and therefore no interface is available.
* Hardware is initialized but communication is not started and therefore no interface is
* available.
*
* INACTIVE (on_configure, on_deactivate):
* Communication with the hardware is started and it is configured.
Expand Down Expand Up @@ -127,12 +129,12 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
*
* \note This is a non-realtime evaluation of whether a set of command interface claims are
* possible, and call to start preparing data structures for the upcoming switch that will occur.
* \note All starting and stopping interface keys are passed to all components, so the function should
* return return_type::OK by default when given interface keys not relevant for this component.
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
* \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping.
* \return return_type::OK if the new command interface combination can be prepared,
* or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
* \note All starting and stopping interface keys are passed to all components, so the function
* should return return_type::OK by default when given interface keys not relevant for this
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs
* stopping. \return return_type::OK if the new command interface combination can be prepared, or
* if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
*/
virtual return_type prepare_command_mode_switch(
const std::vector<std::string> & /*start_interfaces*/,
Expand All @@ -146,11 +148,11 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
* Perform the mode-switching for the new command interface combination.
*
* \note This is part of the realtime update loop, and should be fast.
* \note All starting and stopping interface keys are passed to all components, so the function should
* return return_type::OK by default when given interface keys not relevant for this component.
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
* \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping.
* \return return_type::OK if the new command interface combination can be switched to,
* \note All starting and stopping interface keys are passed to all components, so the function
* should return return_type::OK by default when given interface keys not relevant for this
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs
* stopping. \return return_type::OK if the new command interface combination can be switched to,
* or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
*/
virtual return_type perform_command_mode_switch(
Expand Down
18 changes: 9 additions & 9 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,11 +304,11 @@ hardware_interface::InterfaceInfo parse_interfaces_from_xml(

/// Search XML snippet from URDF for information about a control component.
/**
* \param[in] component_it pointer to the iterator where component
* info should be found
* \return ComponentInfo filled with information about component
* \throws std::runtime_error if a component attribute or tag is not found
*/
* \param[in] component_it pointer to the iterator where component
* info should be found
* \return ComponentInfo filled with information about component
* \throws std::runtime_error if a component attribute or tag is not found
*/
ComponentInfo parse_component_from_xml(const tinyxml2::XMLElement * component_it)
{
ComponentInfo component;
Expand Down Expand Up @@ -417,10 +417,10 @@ ActuatorInfo parse_transmission_actuator_from_xml(const tinyxml2::XMLElement * e

/// Search XML snippet from URDF for information about a transmission.
/**
* \param[in] transmission_it pointer to the iterator where transmission info should be found
* \return TransmissionInfo filled with information about transmission
* \throws std::runtime_error if an attribute or tag is not found
*/
* \param[in] transmission_it pointer to the iterator where transmission info should be found
* \return TransmissionInfo filled with information about transmission
* \throws std::runtime_error if an attribute or tag is not found
*/
TransmissionInfo parse_transmission_from_xml(const tinyxml2::XMLElement * transmission_it)
{
TransmissionInfo transmission;
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class TestActuator : public ActuatorInterface
* if (info_.joints[0].command_interfaces.size() != 1) {return CallbackReturn::ERROR;}
* // can only give feedback state for position and velocity
* if (info_.joints[0].state_interfaces.size() != 2) {return CallbackReturn::ERROR;}
*/
*/

return CallbackReturn::SUCCESS;
}
Expand Down
Loading

0 comments on commit 0637782

Please sign in to comment.