6 #include <controller_manager/controller_manager.h>
8 #include <rosgraph_msgs/Clock.h>
10 int main(
int argc,
char **argv)
12 ros::init(argc, argv,
"four_wheel_steering");
20 controller_manager::ControllerManager cm(&robot, nh);
27 std::chrono::system_clock::time_point begin = std::chrono::system_clock::now();
28 std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
32 double elapsed_secs = 0;
36 begin = std::chrono::system_clock::now();
39 cm.update(internal_time, dt);
42 end = std::chrono::system_clock::now();
44 elapsed_secs = std::chrono::duration_cast<std::chrono::duration<double> >((end - begin)).count();
46 if (dt.
toSec() - elapsed_secs < 0.0)
49 0.1,
"Control cycle is taking to much time, elapsed: " << elapsed_secs);
54 std::this_thread::sleep_for(std::chrono::duration<double>(dt.
toSec() - elapsed_secs));
57 rosgraph_msgs::Clock clock;