46#include <controller_manager/controller_manager.h>
50using namespace std::chrono;
51using clock = high_resolution_clock;
62 RmRobotHWLoop(ros::NodeHandle& nh, std::shared_ptr<RmRobotHW> hardware_interface);
82 double cycle_time_error_threshold_{};
85 std::thread loop_thread_;
86 std::atomic_bool loop_running_;
88 ros::Duration elapsed_time_;
89 clock::time_point last_time_;
97 std::shared_ptr<controller_manager::ControllerManager> controller_manager_;
100 std::shared_ptr<RmRobotHW> hardware_interface_;
Definition control_loop.h:54
~RmRobotHWLoop()
Definition control_loop.cpp:118
RmRobotHWLoop(ros::NodeHandle &nh, std::shared_ptr< RmRobotHW > hardware_interface)
Create controller manager. Load loop frequency. Start control loop which call rm_hw::RmRobotHWLoop::u...
Definition control_loop.cpp:41
void update()
Timed method that reads current hardware's state, runs the controller code once and sends the new com...
Definition control_loop.cpp:84
Definition control_loop.h:49
high_resolution_clock clock
Definition control_loop.h:51