Skip to content

Commit

Permalink
rename the macro to REGISTER_ROS2_CONTROL_INTROSPECTION
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Dec 5, 2024
1 parent ce48595 commit 3646e22
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 13 deletions.
2 changes: 1 addition & 1 deletion example_12/controllers/src/passthrough_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ controller_interface::CallbackReturn PassthroughController::on_configure(

for (size_t i = 0; i < reference_interface_names_.size(); i++)
{
REGISTER_DEFAULT_INTROSPECTION(reference_interface_names_[i], &reference_interfaces_[i]);
REGISTER_ROS2_CONTROL_INTROSPECTION(reference_interface_names_[i], &reference_interfaces_[i]);
}

return controller_interface::CallbackReturn::SUCCESS;
Expand Down
10 changes: 5 additions & 5 deletions example_12/hardware/rrbot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,13 +83,13 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
}
}

REGISTER_DEFAULT_INTROSPECTION("hw_start_sec", &hw_start_sec_);
REGISTER_DEFAULT_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
REGISTER_DEFAULT_INTROSPECTION("hw_slowdown", &hw_slowdown_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_start_sec", &hw_start_sec_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_slowdown", &hw_slowdown_);
for (size_t i = 0; i < info_.joints.size(); ++i)
{
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_states_[i]);
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_commands_[i]);
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_states_[i]);
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_commands_[i]);
}

return hardware_interface::CallbackReturn::SUCCESS;
Expand Down
14 changes: 7 additions & 7 deletions example_4/hardware/rrbot_system_with_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,18 +90,18 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init(
}
}

REGISTER_DEFAULT_INTROSPECTION("hw_start_sec", &hw_start_sec_);
REGISTER_DEFAULT_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
REGISTER_DEFAULT_INTROSPECTION("hw_slowdown", &hw_slowdown_);
REGISTER_DEFAULT_INTROSPECTION("hw_sensor_change", &hw_sensor_change_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_start_sec", &hw_start_sec_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_slowdown", &hw_slowdown_);
REGISTER_ROS2_CONTROL_INTROSPECTION("hw_sensor_change", &hw_sensor_change_);
for (size_t i = 0; i < info_.joints.size(); ++i)
{
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_joint_states_[i]);
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_joint_commands_[i]);
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_joint_states_[i]);
REGISTER_ROS2_CONTROL_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_joint_commands_[i]);
}
for (size_t i = 0; i < info_.sensors[0].state_interfaces.size(); ++i)
{
REGISTER_DEFAULT_INTROSPECTION(
REGISTER_ROS2_CONTROL_INTROSPECTION(
info_.sensors[0].name + "." + info_.sensors[0].state_interfaces[i].name,
&hw_sensor_states_[i]);
}
Expand Down

0 comments on commit 3646e22

Please sign in to comment.