Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ros_control_boilerplate::GenericHWControlLoop Class Reference

The control loop - repeatidly calls read() and write() to the hardware interface at a specified frequency We use MONOTONIC time to ensure robustness in the event of system time updates/change. See http://stackoverflow.com/questions/3523442/difference-between-clock-realtime-and-clock-monotonic. More...

#include <generic_hw_control_loop.h>

Public Member Functions

 GenericHWControlLoop (ros::NodeHandle &nh, boost::shared_ptr< hardware_interface::RobotHW > hardware_interface)
 Constructor. More...
 
void run ()
 

Protected Member Functions

void update ()
 

Protected Attributes

boost::shared_ptr< controller_manager::ControllerManagercontroller_manager_
 ROS Controller Manager and Runner. More...
 
struct timespec current_time_
 
double cycle_time_error_threshold_
 
ros::Duration desired_update_period_
 
ros::Duration elapsed_time_
 
boost::shared_ptr< hardware_interface::RobotHWhardware_interface_
 Abstract Hardware Interface for your robot. More...
 
struct timespec last_time_
 
double loop_hz_
 
std::string name_ = "generic_hw_control_loop"
 
ros::NodeHandle nh_
 

Detailed Description

The control loop - repeatidly calls read() and write() to the hardware interface at a specified frequency We use MONOTONIC time to ensure robustness in the event of system time updates/change. See http://stackoverflow.com/questions/3523442/difference-between-clock-realtime-and-clock-monotonic.

Definition at line 56 of file generic_hw_control_loop.h.

Constructor & Destructor Documentation

ros_control_boilerplate::GenericHWControlLoop::GenericHWControlLoop ( ros::NodeHandle nh,
boost::shared_ptr< hardware_interface::RobotHW hardware_interface 
)

Constructor.

Parameters
NodeHandle
hardware_interface- the robot-specific hardware interface to be use with your robot

Definition at line 47 of file generic_hw_control_loop.cpp.

Member Function Documentation

void ros_control_boilerplate::GenericHWControlLoop::run ( )

Definition at line 67 of file generic_hw_control_loop.cpp.

void ros_control_boilerplate::GenericHWControlLoop::update ( )
protected

Definition at line 76 of file generic_hw_control_loop.cpp.

Member Data Documentation

boost::shared_ptr<controller_manager::ControllerManager> ros_control_boilerplate::GenericHWControlLoop::controller_manager_
protected

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 98 of file generic_hw_control_loop.h.

struct timespec ros_control_boilerplate::GenericHWControlLoop::current_time_
protected

Definition at line 90 of file generic_hw_control_loop.h.

double ros_control_boilerplate::GenericHWControlLoop::cycle_time_error_threshold_
protected

Definition at line 84 of file generic_hw_control_loop.h.

ros::Duration ros_control_boilerplate::GenericHWControlLoop::desired_update_period_
protected

Definition at line 83 of file generic_hw_control_loop.h.

ros::Duration ros_control_boilerplate::GenericHWControlLoop::elapsed_time_
protected

Definition at line 87 of file generic_hw_control_loop.h.

boost::shared_ptr<hardware_interface::RobotHW> ros_control_boilerplate::GenericHWControlLoop::hardware_interface_
protected

Abstract Hardware Interface for your robot.

Definition at line 101 of file generic_hw_control_loop.h.

struct timespec ros_control_boilerplate::GenericHWControlLoop::last_time_
protected

Definition at line 89 of file generic_hw_control_loop.h.

double ros_control_boilerplate::GenericHWControlLoop::loop_hz_
protected

Definition at line 88 of file generic_hw_control_loop.h.

std::string ros_control_boilerplate::GenericHWControlLoop::name_ = "generic_hw_control_loop"
protected

Definition at line 80 of file generic_hw_control_loop.h.

ros::NodeHandle ros_control_boilerplate::GenericHWControlLoop::nh_
protected

Definition at line 77 of file generic_hw_control_loop.h.


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


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Thu Feb 25 2021 03:58:54