We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 8a79614 commit 037a117Copy full SHA for 037a117
kuka_drivers_core/src/control_node.cpp
@@ -117,15 +117,15 @@ int main(int argc, char ** argv)
117
controller_manager->get_clock()->sleep_for(period);
118
119
// for calculating the measured period of the loop
120
- rclcpp::Time previous_time = controller_manager->get_trigger_clock()->now();
+ rclcpp::Time previous_time = controller_manager->get_clock()->now();
121
std::this_thread::sleep_for(period);
122
123
try
124
{
125
while (rclcpp::ok())
126
127
// calculate measured period
128
- auto const current_time = controller_manager->get_trigger_clock()->now();
+ auto const current_time = controller_manager->get_clock()->now();
129
auto const dt = current_time - previous_time;
130
previous_time = current_time;
131
0 commit comments