2626namespace ros2_control_demo_hardware
2727{
2828
29- return_type DiffBotSystemHardware::configure (
29+ hardware_interface:: return_type DiffBotSystemHardware::configure (
3030 const hardware_interface::HardwareInfo & info)
3131{
32- if (configure_default (info) != return_type::OK) {
33- return return_type::ERROR;
32+ if (configure_default (info) != hardware_interface:: return_type::OK) {
33+ return hardware_interface:: return_type::ERROR;
3434 }
3535
3636 hw_start_sec_ = stod (info_.hardware_parameters [" example_param_hw_start_duration_sec" ]);
@@ -46,7 +46,7 @@ return_type DiffBotSystemHardware::configure(
4646 rclcpp::get_logger (" DiffBotSystemHardware" ),
4747 " Joint '%s' has %d command interfaces found. 1 expected." ,
4848 joint.name .c_str (), joint.command_interfaces .size ());
49- return return_type::ERROR;
49+ return hardware_interface:: return_type::ERROR;
5050 }
5151
5252 if (joint.command_interfaces [0 ].name != hardware_interface::HW_IF_VELOCITY) {
@@ -55,15 +55,15 @@ return_type DiffBotSystemHardware::configure(
5555 " Joint '%s' have %s command interfaces found. '%s' expected." ,
5656 joint.name .c_str (), joint.command_interfaces [0 ].name .c_str (),
5757 hardware_interface::HW_IF_VELOCITY);
58- return return_type::ERROR;
58+ return hardware_interface:: return_type::ERROR;
5959 }
6060
6161 if (joint.state_interfaces .size () != 2 ) {
6262 RCLCPP_FATAL (
6363 rclcpp::get_logger (" DiffBotSystemHardware" ),
6464 " Joint '%s' has %d state interface. 2 expected." ,
6565 joint.name .c_str (), joint.state_interfaces .size ());
66- return return_type::ERROR;
66+ return hardware_interface:: return_type::ERROR;
6767 }
6868
6969 if (joint.state_interfaces [0 ].name != hardware_interface::HW_IF_POSITION) {
@@ -72,7 +72,7 @@ return_type DiffBotSystemHardware::configure(
7272 " Joint '%s' have '%s' as first state interface. '%s' and '%s' expected." ,
7373 joint.name .c_str (), joint.state_interfaces [0 ].name .c_str (),
7474 hardware_interface::HW_IF_POSITION);
75- return return_type::ERROR;
75+ return hardware_interface:: return_type::ERROR;
7676 }
7777
7878 if (joint.state_interfaces [1 ].name != hardware_interface::HW_IF_VELOCITY) {
@@ -81,12 +81,12 @@ return_type DiffBotSystemHardware::configure(
8181 " Joint '%s' have '%s' as second state interface. '%s' expected." ,
8282 joint.name .c_str (), joint.state_interfaces [1 ].name .c_str (),
8383 hardware_interface::HW_IF_VELOCITY);
84- return return_type::ERROR;
84+ return hardware_interface:: return_type::ERROR;
8585 }
8686 }
8787
8888 status_ = hardware_interface::status::CONFIGURED;
89- return return_type::OK;
89+ return hardware_interface:: return_type::OK;
9090}
9191
9292std::vector<hardware_interface::StateInterface>
@@ -118,7 +118,7 @@ DiffBotSystemHardware::export_command_interfaces()
118118 return command_interfaces;
119119}
120120
121- return_type DiffBotSystemHardware::start ()
121+ hardware_interface:: return_type DiffBotSystemHardware::start ()
122122{
123123 RCLCPP_INFO (
124124 rclcpp::get_logger (" DiffBotSystemHardware" ),
@@ -145,10 +145,10 @@ return_type DiffBotSystemHardware::start()
145145 rclcpp::get_logger (" DiffBotSystemHardware" ),
146146 " System Sucessfully started!" );
147147
148- return return_type::OK;
148+ return hardware_interface:: return_type::OK;
149149}
150150
151- return_type DiffBotSystemHardware::stop ()
151+ hardware_interface:: return_type DiffBotSystemHardware::stop ()
152152{
153153 RCLCPP_INFO (
154154 rclcpp::get_logger (" DiffBotSystemHardware" ),
@@ -167,7 +167,7 @@ return_type DiffBotSystemHardware::stop()
167167 rclcpp::get_logger (" DiffBotSystemHardware" ),
168168 " System sucessfully stopped!" );
169169
170- return return_type::OK;
170+ return hardware_interface:: return_type::OK;
171171}
172172
173173hardware_interface::return_type DiffBotSystemHardware::read ()
@@ -189,7 +189,7 @@ hardware_interface::return_type DiffBotSystemHardware::read()
189189 rclcpp::get_logger (" DiffBotSystemHardware" ),
190190 " Joints sucessfully read!" );
191191
192- return return_type::OK;
192+ return hardware_interface:: return_type::OK;
193193}
194194
195195hardware_interface::return_type ros2_control_demo_hardware::DiffBotSystemHardware::write ()
@@ -208,7 +208,7 @@ hardware_interface::return_type ros2_control_demo_hardware::DiffBotSystemHardwar
208208 rclcpp::get_logger (" DiffBotSystemHardware" ),
209209 " Joints sucessfully written!" );
210210
211- return return_type::OK;
211+ return hardware_interface:: return_type::OK;
212212}
213213
214214} // namespace ros2_control_demo_hardware
0 commit comments