33 #include <controller_manager/controller_manager.h>
35 #include <rosgraph_msgs/Clock.h>
37 int main(
int argc,
char **argv)
47 controller_manager::ControllerManager cm(&robot, nh);
54 std::chrono::system_clock::time_point begin = std::chrono::system_clock::now();
55 std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
59 double elapsed_secs = 0;
63 begin = std::chrono::system_clock::now();
66 cm.update(internal_time, dt);
70 end = std::chrono::system_clock::now();
72 elapsed_secs = std::chrono::duration_cast<std::chrono::duration<double> >((end - begin)).count();
74 if (dt.
toSec() - elapsed_secs < 0.0)
77 0.1,
"Control cycle is taking to much time, elapsed: " << elapsed_secs);
82 std::this_thread::sleep_for(std::chrono::duration<double>(dt.
toSec() - elapsed_secs));
85 rosgraph_msgs::Clock clock;