#include <control_loop.h>
Definition at line 84 of file control_loop.h.
◆ RmRobotHWLoop()
◆ ~RmRobotHWLoop()
rm_hw::RmRobotHWLoop::~RmRobotHWLoop |
( |
| ) |
|
◆ update()
void rm_hw::RmRobotHWLoop::update |
( |
| ) |
|
Timed method that reads current hardware's state, runs the controller code once and sends the new commands to the hardware.
Timed method that reads current hardware's state, runs the controller code once and sends the new commands to the hardware.
Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing.
Definition at line 115 of file control_loop.cpp.
◆ controller_manager_
ROS Controller Manager and Runner
This class advertises a ROS interface for loading, unloading, starting, and stopping ros_control-based controllers. It also serializes execution of all running controllers in update.
Definition at line 128 of file control_loop.h.
◆ cycle_time_error_threshold_
double rm_hw::RmRobotHWLoop::cycle_time_error_threshold_ {} |
|
private |
◆ elapsed_time_
◆ hardware_interface_
std::shared_ptr<RmRobotHW> rm_hw::RmRobotHWLoop::hardware_interface_ |
|
private |
◆ last_time_
clock::time_point rm_hw::RmRobotHWLoop::last_time_ |
|
private |
◆ loop_hz_
double rm_hw::RmRobotHWLoop::loop_hz_ {} |
|
private |
◆ loop_running_
std::atomic_bool rm_hw::RmRobotHWLoop::loop_running_ |
|
private |
◆ loop_thread_
std::thread rm_hw::RmRobotHWLoop::loop_thread_ |
|
private |
◆ nh_
The documentation for this class was generated from the following files: