Public Member Functions | Protected Attributes | List of all members
GenericHWLoop Class Reference

Public Member Functions

 GenericHWLoop (const ros::NodeHandle &nh, boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperHWInterface > hardware_interface)
 
 GenericHWLoop (const ros::NodeHandle &nh, boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperHWInterface > hardware_interface)
 
void update (const ros::TimerEvent &e)
 Timer event Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing. More...
 
void update (const ros::TimerEvent &e)
 Timer event Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing. More...
 

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_freq_
 
ros::Duration elapsed_time_
 
boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperHWInterfacehardware_interface_
 Abstract Hardware Interface for your robot. More...
 
struct timespec last_time_
 
double loop_hz_
 
std::string name_
 
ros::NodeHandle nh_
 
ros::Timer non_realtime_loop_
 

Detailed Description

Definition at line 34 of file robotiq_3f_gripper_can_node.cpp.

Constructor & Destructor Documentation

GenericHWLoop::GenericHWLoop ( const ros::NodeHandle nh,
boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperHWInterface hardware_interface 
)
inline

Create the controller manager

Load rosparams

Get current time for use with first update

Start timer

Definition at line 37 of file robotiq_3f_gripper_can_node.cpp.

GenericHWLoop::GenericHWLoop ( const ros::NodeHandle nh,
boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperHWInterface hardware_interface 
)
inline

Create the controller manager

Load rosparams

Get current time for use with first update

Start timer

Definition at line 38 of file robotiq_3f_gripper_ethercat_node.cpp.

Member Function Documentation

void GenericHWLoop::update ( const ros::TimerEvent e)
inline

Timer event Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing.

Get change in time

Error check cycle time

Input

Control

Output

Definition at line 68 of file robotiq_3f_gripper_can_node.cpp.

void GenericHWLoop::update ( const ros::TimerEvent e)
inline

Timer event Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing.

Get change in time

Error check cycle time

Input

Control

Output

Definition at line 69 of file robotiq_3f_gripper_ethercat_node.cpp.

Member Data Documentation

boost::shared_ptr< controller_manager::ControllerManager > GenericHWLoop::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 120 of file robotiq_3f_gripper_can_node.cpp.

struct timespec GenericHWLoop::current_time_
protected

Definition at line 112 of file robotiq_3f_gripper_can_node.cpp.

double GenericHWLoop::cycle_time_error_threshold_
protected

Definition at line 105 of file robotiq_3f_gripper_can_node.cpp.

ros::Duration GenericHWLoop::desired_update_freq_
protected

Definition at line 104 of file robotiq_3f_gripper_can_node.cpp.

ros::Duration GenericHWLoop::elapsed_time_
protected

Definition at line 109 of file robotiq_3f_gripper_can_node.cpp.

boost::shared_ptr< robotiq_3f_gripper_control::Robotiq3FGripperHWInterface > GenericHWLoop::hardware_interface_
protected

Abstract Hardware Interface for your robot.

Definition at line 123 of file robotiq_3f_gripper_can_node.cpp.

struct timespec GenericHWLoop::last_time_
protected

Definition at line 111 of file robotiq_3f_gripper_can_node.cpp.

double GenericHWLoop::loop_hz_
protected

Definition at line 110 of file robotiq_3f_gripper_can_node.cpp.

std::string GenericHWLoop::name_
protected

Definition at line 101 of file robotiq_3f_gripper_can_node.cpp.

ros::NodeHandle GenericHWLoop::nh_
protected

Definition at line 98 of file robotiq_3f_gripper_can_node.cpp.

ros::Timer GenericHWLoop::non_realtime_loop_
protected

Definition at line 108 of file robotiq_3f_gripper_can_node.cpp.


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


robotiq_3f_gripper_control
Author(s): Nicolas Lauzier (Robotiq inc.), Allison Thackston
autogenerated on Tue Jun 1 2021 02:29:58