Skip to content

Commit d982069

Browse files
committed
adjust to usage of get_/set_state or command functions
1 parent 1cd3a91 commit d982069

File tree

1 file changed

+7
-8
lines changed

1 file changed

+7
-8
lines changed

example_1/hardware/rrbot.cpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -103,11 +103,11 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_configure
103103
// reset values always when configuring hardware
104104
for (const auto & [name, descr] : joint_state_interfaces_)
105105
{
106-
joint_state_set_value(descr, 0.0);
106+
set_state(name, 0.0);
107107
}
108108
for (const auto & [name, descr] : joint_command_interfaces_)
109109
{
110-
joint_command_set_value(descr, 0.0);
110+
set_command(name, 0.0);
111111
}
112112
RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Successfully configured!");
113113

@@ -133,7 +133,7 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_activate(
133133
// command and state should be equal when starting
134134
for (const auto & [name, descr] : joint_state_interfaces_)
135135
{
136-
joint_command_set_value(descr, joint_state_get_value(descr));
136+
set_command(name, get_state(name));
137137
}
138138

139139
RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Successfully activated!");
@@ -170,13 +170,12 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::read(
170170

171171
for (const auto & [name, descr] : joint_state_interfaces_)
172172
{
173-
auto new_value = joint_state_get_value(descr) +
174-
(joint_command_get_value(descr) - joint_state_get_value(descr)) / hw_slowdown_;
175-
joint_state_set_value(descr, new_value);
173+
auto new_value = get_state(name) + (get_command(name) - get_state(name)) / hw_slowdown_;
174+
set_state(name, new_value);
176175
// Simulate RRBot's movement
177176
RCLCPP_INFO_STREAM(
178177
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
179-
"Got state " << joint_state_get_value(descr) << " for joint: " << descr.get_name() << "!");
178+
"Got state " << get_state(name) << " for joint: " << name << "!");
180179
}
181180
RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Joints successfully read!");
182181
// END: This part here is for exemplary purposes - Please do not copy to your production code
@@ -195,7 +194,7 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::write(
195194
// Simulate sending commands to the hardware
196195
RCLCPP_INFO_STREAM(
197196
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
198-
"Got command" << joint_command_get_value(descr) << " for joint: " << descr.get_name() << "!");
197+
"Got command" << get_command(name) << " for joint: " << name << "!");
199198
}
200199
RCLCPP_INFO(
201200
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Joints successfully written!");

0 commit comments

Comments
 (0)