@@ -53,30 +53,26 @@ class State;
5353namespace ur_controllers
5454{
5555const auto kUninitializedValue = std::numeric_limits<double >::quiet_NaN();
56+ using hardware_interface::HW_IF_EFFORT;
5657using hardware_interface::HW_IF_POSITION;
5758using hardware_interface::HW_IF_VELOCITY;
58- using hardware_interface::HW_IF_EFFORT;
59-
6059
6160SpeedScalingStateController::SpeedScalingStateController ()
62- {}
61+ {
62+ }
6363
64- controller_interface::InterfaceConfiguration SpeedScalingStateController::command_interface_configuration ()
65- const
64+ controller_interface::InterfaceConfiguration SpeedScalingStateController::command_interface_configuration () const
6665{
67- return controller_interface::InterfaceConfiguration{controller_interface::
68- interface_configuration_type::NONE};
66+ return controller_interface::InterfaceConfiguration{ controller_interface::interface_configuration_type::NONE };
6967}
7068
71- controller_interface::InterfaceConfiguration SpeedScalingStateController::state_interface_configuration ()
72- const
69+ controller_interface::InterfaceConfiguration SpeedScalingStateController::state_interface_configuration () const
7370{
74- return controller_interface::InterfaceConfiguration{controller_interface::
75- interface_configuration_type::ALL};
71+ return controller_interface::InterfaceConfiguration{ controller_interface::interface_configuration_type::ALL };
7672}
7773
7874rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
79- SpeedScalingStateController::on_configure (const rclcpp_lifecycle::State & /* previous_state*/ )
75+ SpeedScalingStateController::on_configure (const rclcpp_lifecycle::State& /* previous_state*/ )
8076{
8177 try
8278 {
@@ -93,30 +89,31 @@ SpeedScalingStateController::on_configure(const rclcpp_lifecycle::State & /*prev
9389}
9490
9591rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
96- SpeedScalingStateController::on_activate (const rclcpp_lifecycle::State & /* previous_state*/ )
92+ SpeedScalingStateController::on_activate (const rclcpp_lifecycle::State& /* previous_state*/ )
9793{
98- if (!init_joint_data ()) {
94+ if (!init_joint_data ())
95+ {
9996 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
10097 }
10198
10299 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
103100}
104101
105102rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
106- SpeedScalingStateController::on_deactivate (const rclcpp_lifecycle::State & /* previous_state*/ )
103+ SpeedScalingStateController::on_deactivate (const rclcpp_lifecycle::State& /* previous_state*/ )
107104{
108105 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
109106}
110107
111- template <typename T>
112- bool has_any_key (
113- const std::unordered_map<std::string, T> & map,
114- const std::vector<std::string> & keys)
108+ template <typename T>
109+ bool has_any_key (const std::unordered_map<std::string, T>& map, const std::vector<std::string>& keys)
115110{
116111 bool found_key = false ;
117- for (const auto & key_item : map) {
118- const auto & key = key_item.first ;
119- if (std::find (keys.cbegin (), keys.cend (), key) != keys.cend ()) {
112+ for (const auto & key_item : map)
113+ {
114+ const auto & key = key_item.first ;
115+ if (std::find (keys.cbegin (), keys.cend (), key) != keys.cend ())
116+ {
120117 found_key = true ;
121118 break ;
122119 }
@@ -127,21 +124,24 @@ bool has_any_key(
127124bool SpeedScalingStateController::init_joint_data ()
128125{
129126 // loop in reverse order, this maintains the order of values at retrieval time
130- for (auto si = state_interfaces_.crbegin (); si != state_interfaces_.crend (); si++) {
127+ for (auto si = state_interfaces_.crbegin (); si != state_interfaces_.crend (); si++)
128+ {
131129 // initialize map if name is new
132- if (name_if_value_mapping_.count (si->get_name ()) == 0 ) {
130+ if (name_if_value_mapping_.count (si->get_name ()) == 0 )
131+ {
133132 name_if_value_mapping_[si->get_name ()] = {};
134133 }
135134 // add interface name
136- name_if_value_mapping_[si->get_name ()][si->get_interface_name ()] =
137- kUninitializedValue ;
135+ name_if_value_mapping_[si->get_name ()][si->get_interface_name ()] = kUninitializedValue ;
138136 }
139137
140138 // filter state interfaces that have a speed scaling factor
141139 // the rest will be ignored for this message
142- for (const auto & name_ifv : name_if_value_mapping_) {
143- const auto & interfaces_and_values = name_ifv.second ;
144- if (has_any_key (interfaces_and_values, {" speed_scaling_factor" })) {
140+ for (const auto & name_ifv : name_if_value_mapping_)
141+ {
142+ const auto & interfaces_and_values = name_ifv.second ;
143+ if (has_any_key (interfaces_and_values, { " speed_scaling_factor" }))
144+ {
145145 joint_names_.push_back (name_ifv.first );
146146 }
147147 }
@@ -152,23 +152,22 @@ bool SpeedScalingStateController::init_joint_data()
152152double get_value (const std::unordered_map<std::string, std::unordered_map<std::string, double >>& map,
153153 const std::string& name, const std::string& interface_name)
154154{
155- double get_value (
156- const std::unordered_map<std::string, std::unordered_map<std::string, double >> & map,
157- const std::string & name, const std::string & interface_name)
158- {
159- const auto & interfaces_and_values = map.at (name);
155+ const auto & interfaces_and_values = map.at (name);
160156 const auto interface_and_value = interfaces_and_values.find (interface_name);
161- if (interface_and_value != interfaces_and_values.cend ()) {
157+ if (interface_and_value != interfaces_and_values.cend ())
158+ {
162159 return interface_and_value->second ;
163- } else {
160+ }
161+ else
162+ {
164163 return kUninitializedValue ;
165164 }
166165}
167166
168- controller_interface::return_type
169- SpeedScalingStateController::update ()
167+ controller_interface::return_type SpeedScalingStateController::update ()
170168{
171- for (const auto & state_interface : state_interfaces_) {
169+ for (const auto & state_interface : state_interfaces_)
170+ {
172171 name_if_value_mapping_[state_interface.get_name ()][state_interface.get_interface_name ()] =
173172 state_interface.get_value ();
174173 RCLCPP_DEBUG (get_node ()->get_logger (), " %s/%s: %f\n " , state_interface.get_name ().c_str (),
@@ -186,9 +185,8 @@ SpeedScalingStateController::update()
186185 return controller_interface::return_type::SUCCESS;
187186}
188187
189- } // namespace joint_state_controller
188+ } // namespace ur_controllers
190189
191190#include " pluginlib/class_list_macros.hpp"
192191
193- PLUGINLIB_EXPORT_CLASS (
194- ur_controllers::SpeedScalingStateController, controller_interface::ControllerInterface)
192+ PLUGINLIB_EXPORT_CLASS (ur_controllers::SpeedScalingStateController, controller_interface::ControllerInterface)
0 commit comments