Public Member Functions | Private Attributes | List of all members
rm_hw::RmRobotHWLoop Class Reference

#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. More...
 
void update ()
 Timed method that reads current hardware's state, runs the controller code once and sends the new commands to the hardware. More...
 
 ~RmRobotHWLoop ()
 

Private Attributes

std::shared_ptr< controller_manager::ControllerManagercontroller_manager_
 
double cycle_time_error_threshold_ {}
 
ros::Duration elapsed_time_
 
std::shared_ptr< RmRobotHWhardware_interface_
 
clock::time_point last_time_
 
double loop_hz_ {}
 
std::atomic_bool loop_running_
 
std::thread loop_thread_
 
ros::NodeHandle nh_
 

Detailed Description

Definition at line 84 of file control_loop.h.

Constructor & Destructor Documentation

◆ RmRobotHWLoop()

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.

Parameters
nhNode-handle of a ROS node.
hardware_interfaceA pointer which point to hardware_interface.

Definition at line 72 of file control_loop.cpp.

◆ ~RmRobotHWLoop()

rm_hw::RmRobotHWLoop::~RmRobotHWLoop ( )

Definition at line 149 of file control_loop.cpp.

Member Function Documentation

◆ 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.

Member Data Documentation

◆ controller_manager_

std::shared_ptr<controller_manager::ControllerManager> rm_hw::RmRobotHWLoop::controller_manager_
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 128 of file control_loop.h.

◆ cycle_time_error_threshold_

double rm_hw::RmRobotHWLoop::cycle_time_error_threshold_ {}
private

Definition at line 113 of file control_loop.h.

◆ elapsed_time_

ros::Duration rm_hw::RmRobotHWLoop::elapsed_time_
private

Definition at line 119 of file control_loop.h.

◆ hardware_interface_

std::shared_ptr<RmRobotHW> rm_hw::RmRobotHWLoop::hardware_interface_
private

Definition at line 131 of file control_loop.h.

◆ last_time_

clock::time_point rm_hw::RmRobotHWLoop::last_time_
private

Definition at line 120 of file control_loop.h.

◆ loop_hz_

double rm_hw::RmRobotHWLoop::loop_hz_ {}
private

Definition at line 118 of file control_loop.h.

◆ loop_running_

std::atomic_bool rm_hw::RmRobotHWLoop::loop_running_
private

Definition at line 117 of file control_loop.h.

◆ loop_thread_

std::thread rm_hw::RmRobotHWLoop::loop_thread_
private

Definition at line 116 of file control_loop.h.

◆ nh_

ros::NodeHandle rm_hw::RmRobotHWLoop::nh_
private

Definition at line 110 of file control_loop.h.


The documentation for this class was generated from the following files:


rm_hw
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:44