Public Member Functions | Private Types | Private Attributes | List of all members
dynamixel::DynamixelLoop< Protocol > Class Template Reference

#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
 

Detailed Description

template<class Protocol>
class dynamixel::DynamixelLoop< Protocol >

Definition at line 61 of file control_loop.hpp.

Member Typedef Documentation

template<class Protocol>
using dynamixel::DynamixelLoop< Protocol >::hw_int = typename dynamixel::DynamixelHardwareInterface<Protocol>
private

Definition at line 62 of file control_loop.hpp.

Constructor & Destructor Documentation

template<class Protocol>
dynamixel::DynamixelLoop< Protocol >::DynamixelLoop ( ros::NodeHandle nh,
std::shared_ptr< hw_int hardware_interface 
)
inline

Definition at line 65 of file control_loop.hpp.

Member Function Documentation

template<class Protocol>
void dynamixel::DynamixelLoop< Protocol >::update ( const ros::TimerEvent )
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.

Member Data Documentation

template<class Protocol>
std::shared_ptr<controller_manager::ControllerManager> dynamixel::DynamixelLoop< Protocol >::_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 152 of file control_loop.hpp.

template<class Protocol>
steady_clock::time_point dynamixel::DynamixelLoop< Protocol >::_current_time
private

Definition at line 144 of file control_loop.hpp.

template<class Protocol>
double dynamixel::DynamixelLoop< Protocol >::_cycle_time_error_threshold
private

Definition at line 137 of file control_loop.hpp.

template<class Protocol>
ros::Duration dynamixel::DynamixelLoop< Protocol >::_desired_update_freq
private

Definition at line 136 of file control_loop.hpp.

template<class Protocol>
ros::Duration dynamixel::DynamixelLoop< Protocol >::_elapsed_time
private

Definition at line 141 of file control_loop.hpp.

template<class Protocol>
std::shared_ptr<hw_int> dynamixel::DynamixelLoop< Protocol >::_hardware_interface
private

Abstract Hardware Interface for your robot.

Definition at line 155 of file control_loop.hpp.

template<class Protocol>
steady_clock::time_point dynamixel::DynamixelLoop< Protocol >::_last_time
private

Definition at line 143 of file control_loop.hpp.

template<class Protocol>
double dynamixel::DynamixelLoop< Protocol >::_loop_hz
private

Definition at line 142 of file control_loop.hpp.

template<class Protocol>
ros::NodeHandle dynamixel::DynamixelLoop< Protocol >::_nh
private

Definition at line 133 of file control_loop.hpp.

template<class Protocol>
ros::Timer dynamixel::DynamixelLoop< Protocol >::_non_realtime_loop
private

Definition at line 140 of file control_loop.hpp.


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


dynamixel_control_hw
Author(s):
autogenerated on Mon Jun 10 2019 13:04:02