Skip to content

Commit ce48595

Browse files
committed
Integrate pal_statistics for introspecting the ros2_control_demos
1 parent 7b7f70c commit ce48595

File tree

3 files changed

+30
-0
lines changed

3 files changed

+30
-0
lines changed

example_12/controllers/src/passthrough_controller.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,11 @@ controller_interface::CallbackReturn PassthroughController::on_configure(
8585
reference_interfaces_.resize(
8686
reference_interface_names_.size(), std::numeric_limits<double>::quiet_NaN());
8787

88+
for (size_t i = 0; i < reference_interface_names_.size(); i++)
89+
{
90+
REGISTER_DEFAULT_INTROSPECTION(reference_interface_names_[i], &reference_interfaces_[i]);
91+
}
92+
8893
return controller_interface::CallbackReturn::SUCCESS;
8994
}
9095

example_12/hardware/rrbot.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,15 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
8383
}
8484
}
8585

86+
REGISTER_DEFAULT_INTROSPECTION("hw_start_sec", &hw_start_sec_);
87+
REGISTER_DEFAULT_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
88+
REGISTER_DEFAULT_INTROSPECTION("hw_slowdown", &hw_slowdown_);
89+
for (size_t i = 0; i < info_.joints.size(); ++i)
90+
{
91+
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_states_[i]);
92+
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_commands_[i]);
93+
}
94+
8695
return hardware_interface::CallbackReturn::SUCCESS;
8796
}
8897

example_4/hardware/rrbot_system_with_sensor.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,22 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init(
9090
}
9191
}
9292

93+
REGISTER_DEFAULT_INTROSPECTION("hw_start_sec", &hw_start_sec_);
94+
REGISTER_DEFAULT_INTROSPECTION("hw_stop_sec", &hw_stop_sec_);
95+
REGISTER_DEFAULT_INTROSPECTION("hw_slowdown", &hw_slowdown_);
96+
REGISTER_DEFAULT_INTROSPECTION("hw_sensor_change", &hw_sensor_change_);
97+
for (size_t i = 0; i < info_.joints.size(); ++i)
98+
{
99+
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_state", &hw_joint_states_[i]);
100+
REGISTER_DEFAULT_INTROSPECTION(info_.joints[i].name + ".hw_command", &hw_joint_commands_[i]);
101+
}
102+
for (size_t i = 0; i < info_.sensors[0].state_interfaces.size(); ++i)
103+
{
104+
REGISTER_DEFAULT_INTROSPECTION(
105+
info_.sensors[0].name + "." + info_.sensors[0].state_interfaces[i].name,
106+
&hw_sensor_states_[i]);
107+
}
108+
93109
return hardware_interface::CallbackReturn::SUCCESS;
94110
}
95111

0 commit comments

Comments
 (0)