Skip to content

Commit 8726ccc

Browse files
committed
rename the macro to REGISTER_ROS2_CONTROL_INTROSPECTION
1 parent e8cd5d4 commit 8726ccc

File tree

3 files changed

+13
-13
lines changed

3 files changed

+13
-13
lines changed

example_12/controllers/src/passthrough_controller.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ controller_interface::CallbackReturn PassthroughController::on_configure(
8787

8888
for (size_t i = 0; i < reference_interface_names_.size(); i++)
8989
{
90-
REGISTER_DEFAULT_INTROSPECTION(reference_interface_names_[i], &reference_interfaces_[i]);
90+
REGISTER_ROS2_CONTROL_INTROSPECTION(reference_interface_names_[i], &reference_interfaces_[i]);
9191
}
9292

9393
return controller_interface::CallbackReturn::SUCCESS;

example_12/hardware/rrbot.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -81,13 +81,13 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
8181
}
8282
}
8383

84-
REGISTER_DEFAULT_INTROSPECTION("hw_start_sec", &hw_start_sec_);
85-
REGISTER_DEFAULT_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
86-
REGISTER_DEFAULT_INTROSPECTION("hw_slowdown", &hw_slowdown_);
84+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_start_sec", &hw_start_sec_);
85+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
86+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_slowdown", &hw_slowdown_);
8787
for (size_t i = 0; i < info_.joints.size(); ++i)
8888
{
89-
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_states_[i]);
90-
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_commands_[i]);
89+
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_states_[i]);
90+
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_commands_[i]);
9191
}
9292

9393
return hardware_interface::CallbackReturn::SUCCESS;

example_4/hardware/rrbot_system_with_sensor.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -85,18 +85,18 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init(
8585
}
8686
}
8787

88-
REGISTER_DEFAULT_INTROSPECTION("hw_start_sec", &hw_start_sec_);
89-
REGISTER_DEFAULT_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
90-
REGISTER_DEFAULT_INTROSPECTION("hw_slowdown", &hw_slowdown_);
91-
REGISTER_DEFAULT_INTROSPECTION("hw_sensor_change", &hw_sensor_change_);
88+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_start_sec", &hw_start_sec_);
89+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
90+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_slowdown", &hw_slowdown_);
91+
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_sensor_change", &hw_sensor_change_);
9292
for (size_t i = 0; i < info_.joints.size(); ++i)
9393
{
94-
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_joint_states_[i]);
95-
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_joint_commands_[i]);
94+
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_joint_states_[i]);
95+
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_joint_commands_[i]);
9696
}
9797
for (size_t i = 0; i < info_.sensors[0].state_interfaces.size(); ++i)
9898
{
99-
REGISTER_DEFAULT_INTROSPECTION(
99+
REGISTER_ROS2_CONTROL_INTROSPECTION(
100100
info_.sensors[0].name + "." + info_.sensors[0].state_interfaces[i].name,
101101
&hw_sensor_states_[i]);
102102
}

0 commit comments

Comments
 (0)