#include <control_loop.hpp>
Public Member Functions | |
DynamixelLoop (ros::NodeHandle &nh, std::shared_ptr< hw_int > hardware_interface) | |
void | update (const ros::TimerEvent &) |
Private Types | |
using | hw_int = typename dynamixel::DynamixelHardwareInterface< Protocol > |
Private Attributes | |
std::shared_ptr< controller_manager::ControllerManager > | _controller_manager |
steady_clock::time_point | _current_time |
double | _cycle_time_error_threshold |
ros::Duration | _desired_update_freq |
ros::Duration | _elapsed_time |
std::shared_ptr< hw_int > | _hardware_interface |
Abstract Hardware Interface for your robot. More... | |
steady_clock::time_point | _last_time |
double | _loop_hz |
ros::NodeHandle | _nh |
ros::Timer | _non_realtime_loop |
Definition at line 61 of file control_loop.hpp.
|
private |
Definition at line 62 of file control_loop.hpp.
|
inline |
Definition at line 65 of file control_loop.hpp.
|
inline |
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 100 of file control_loop.hpp.
|
private |
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 152 of file control_loop.hpp.
|
private |
Definition at line 144 of file control_loop.hpp.
|
private |
Definition at line 137 of file control_loop.hpp.
|
private |
Definition at line 136 of file control_loop.hpp.
|
private |
Definition at line 141 of file control_loop.hpp.
|
private |
Abstract Hardware Interface for your robot.
Definition at line 155 of file control_loop.hpp.
|
private |
Definition at line 143 of file control_loop.hpp.
|
private |
Definition at line 142 of file control_loop.hpp.
|
private |
Definition at line 133 of file control_loop.hpp.
|
private |
Definition at line 140 of file control_loop.hpp.