Skip to content

Commit 34f2da8

Browse files
committed
adjust everywhere return_type
1 parent 83e666d commit 34f2da8

File tree

4 files changed

+39
-43
lines changed

4 files changed

+39
-43
lines changed

ros2_control_demo_hardware/include/ros2_control_demo_hardware/diffbot_system.hpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -29,8 +29,6 @@
2929
#include "rclcpp/macros.hpp"
3030
#include "ros2_control_demo_hardware/visibility_control.h"
3131

32-
using hardware_interface::return_type;
33-
3432
namespace ros2_control_demo_hardware
3533
{
3634
class DiffBotSystemHardware : public
@@ -40,7 +38,7 @@ class DiffBotSystemHardware : public
4038
RCLCPP_SHARED_PTR_DEFINITIONS(DiffBotSystemHardware);
4139

4240
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
43-
return_type configure(const hardware_interface::HardwareInfo & info) override;
41+
hardware_interface::return_type configure(const hardware_interface::HardwareInfo & info) override;
4442

4543
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
4644
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
@@ -49,16 +47,16 @@ class DiffBotSystemHardware : public
4947
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
5048

5149
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
52-
return_type start() override;
50+
hardware_interface::return_type start() override;
5351

5452
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
55-
return_type stop() override;
53+
hardware_interface::return_type stop() override;
5654

5755
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
58-
return_type read() override;
56+
hardware_interface::return_type read() override;
5957

6058
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
61-
return_type write() override;
59+
hardware_interface::return_type write() override;
6260

6361
private:
6462
// Parameters for the DiffBot simulation

ros2_control_demo_hardware/include/ros2_control_demo_hardware/rrbot_system_position_only.hpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,6 @@
3030
#include "hardware_interface/types/hardware_interface_status_values.hpp"
3131
#include "ros2_control_demo_hardware/visibility_control.h"
3232

33-
using hardware_interface::return_type;
34-
3533
namespace ros2_control_demo_hardware
3634
{
3735
class RRBotSystemPositionOnlyHardware : public
@@ -41,7 +39,7 @@ class RRBotSystemPositionOnlyHardware : public
4139
RCLCPP_SHARED_PTR_DEFINITIONS(RRBotSystemPositionOnlyHardware);
4240

4341
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
44-
return_type configure(const hardware_interface::HardwareInfo & info) override;
42+
hardware_interface::return_type configure(const hardware_interface::HardwareInfo & info) override;
4543

4644
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
4745
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
@@ -50,16 +48,16 @@ class RRBotSystemPositionOnlyHardware : public
5048
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
5149

5250
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
53-
return_type start() override;
51+
hardware_interface::return_type start() override;
5452

5553
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
56-
return_type stop() override;
54+
hardware_interface::return_type stop() override;
5755

5856
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
59-
return_type read() override;
57+
hardware_interface::return_type read() override;
6058

6159
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
62-
return_type write() override;
60+
hardware_interface::return_type write() override;
6361

6462
private:
6563
// Parameters for the RRBot simulation

ros2_control_demo_hardware/src/diffbot_system.cpp

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -26,11 +26,11 @@
2626
namespace 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

9292
std::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

173173
hardware_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

195195
hardware_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

ros2_control_demo_hardware/src/rrbot_system_position_only.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -26,11 +26,11 @@
2626
namespace ros2_control_demo_hardware
2727
{
2828

29-
return_type RRBotSystemPositionOnlyHardware::configure(
29+
hardware_interface::return_type RRBotSystemPositionOnlyHardware::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 RRBotSystemPositionOnlyHardware::configure(
4646
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
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_POSITION) {
@@ -55,15 +55,15 @@ return_type RRBotSystemPositionOnlyHardware::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_POSITION);
58-
return return_type::ERROR;
58+
return hardware_interface::return_type::ERROR;
5959
}
6060

6161
if (joint.state_interfaces.size() != 1) {
6262
RCLCPP_FATAL(
6363
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
6464
"Joint '%s' has %d state interface. 1 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,12 +72,12 @@ return_type RRBotSystemPositionOnlyHardware::configure(
7272
"Joint '%s' have %s state interface. '%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

7979
status_ = hardware_interface::status::CONFIGURED;
80-
return return_type::OK;
80+
return hardware_interface::return_type::OK;
8181
}
8282

8383
std::vector<hardware_interface::StateInterface>
@@ -107,7 +107,7 @@ RRBotSystemPositionOnlyHardware::export_command_interfaces()
107107
}
108108

109109

110-
return_type RRBotSystemPositionOnlyHardware::start()
110+
hardware_interface::return_type RRBotSystemPositionOnlyHardware::start()
111111
{
112112
RCLCPP_INFO(
113113
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
@@ -134,10 +134,10 @@ return_type RRBotSystemPositionOnlyHardware::start()
134134
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
135135
"System Sucessfully started!");
136136

137-
return return_type::OK;
137+
return hardware_interface::return_type::OK;
138138
}
139139

140-
return_type RRBotSystemPositionOnlyHardware::stop()
140+
hardware_interface::return_type RRBotSystemPositionOnlyHardware::stop()
141141
{
142142
RCLCPP_INFO(
143143
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
@@ -156,7 +156,7 @@ return_type RRBotSystemPositionOnlyHardware::stop()
156156
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
157157
"System sucessfully stopped!");
158158

159-
return return_type::OK;
159+
return hardware_interface::return_type::OK;
160160
}
161161

162162
hardware_interface::return_type RRBotSystemPositionOnlyHardware::read()
@@ -176,7 +176,7 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::read()
176176
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
177177
"Joints sucessfully read!");
178178

179-
return return_type::OK;
179+
return hardware_interface::return_type::OK;
180180
}
181181

182182
hardware_interface::return_type ros2_control_demo_hardware::RRBotSystemPositionOnlyHardware::write()
@@ -195,7 +195,7 @@ hardware_interface::return_type ros2_control_demo_hardware::RRBotSystemPositionO
195195
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
196196
"Joints sucessfully written!");
197197

198-
return return_type::OK;
198+
return hardware_interface::return_type::OK;
199199
}
200200

201201
} // namespace ros2_control_demo_hardware

0 commit comments

Comments
 (0)