rm_control
|
#include <control_loop.h>
Public Member Functions | |
RmRobotHWLoop (ros::NodeHandle &nh, std::shared_ptr< RmRobotHW > hardware_interface) | |
Create controller manager. Load loop frequency. Start control loop which call rm_hw::RmRobotHWLoop::update() in a frequency. | |
~RmRobotHWLoop () | |
void | update () |
Timed method that reads current hardware's state, runs the controller code once and sends the new commands to the hardware. | |
rm_hw::RmRobotHWLoop::RmRobotHWLoop | ( | ros::NodeHandle & | nh, |
std::shared_ptr< RmRobotHW > | hardware_interface ) |
Create controller manager. Load loop frequency. Start control loop which call rm_hw::RmRobotHWLoop::update() in a frequency.
nh | Node-handle of a ROS node. |
hardware_interface | A pointer which point to hardware_interface. |
rm_hw::RmRobotHWLoop::~RmRobotHWLoop | ( | ) |
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.