Public Member Functions | Private Attributes | List of all members
dynamixel::DynamixelLoop Class Reference

#include <dynamixel_loop.hpp>

Public Member Functions

 DynamixelLoop (ros::NodeHandle &nh, boost::shared_ptr< dynamixel::DynamixelHardwareInterface > hardware_interface)
 
void jsCallback (const sensor_msgs::JointState::ConstPtr &js)
 
void update (const ros::TimerEvent &e)
 

Private Attributes

boost::shared_ptr< controller_manager::ControllerManager_controller_manager
 
struct timespec _current_time
 
double _cycle_time_error_threshold
 
ros::Duration _desired_update_freq
 
ros::Duration _elapsed_time
 
boost::shared_ptr< dynamixel::DynamixelHardwareInterface_hardware_interface
 Abstract Hardware Interface for your robot. More...
 
struct timespec _last_time
 
double _loop_hz
 
ros::NodeHandle _nh
 
ros::Timer _non_realtime_loop
 
sensor_msgs::JointState joint_state
 
ros::Subscriber js_sub
 
ros::Publisher torque_pub
 

Detailed Description

Definition at line 59 of file dynamixel_loop.hpp.

Constructor & Destructor Documentation

dynamixel::DynamixelLoop::DynamixelLoop ( ros::NodeHandle nh,
boost::shared_ptr< dynamixel::DynamixelHardwareInterface hardware_interface 
)

Definition at line 47 of file dynamixel_loop.cpp.

Member Function Documentation

void dynamixel::DynamixelLoop::jsCallback ( const sensor_msgs::JointState::ConstPtr &  js)

Definition at line 79 of file dynamixel_loop.cpp.

void dynamixel::DynamixelLoop::update ( const ros::TimerEvent e)

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 83 of file dynamixel_loop.cpp.

Member Data Documentation

boost::shared_ptr<controller_manager::ControllerManager> dynamixel::DynamixelLoop::_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 98 of file dynamixel_loop.hpp.

struct timespec dynamixel::DynamixelLoop::_current_time
private

Definition at line 90 of file dynamixel_loop.hpp.

double dynamixel::DynamixelLoop::_cycle_time_error_threshold
private

Definition at line 81 of file dynamixel_loop.hpp.

ros::Duration dynamixel::DynamixelLoop::_desired_update_freq
private

Definition at line 80 of file dynamixel_loop.hpp.

ros::Duration dynamixel::DynamixelLoop::_elapsed_time
private

Definition at line 87 of file dynamixel_loop.hpp.

boost::shared_ptr<dynamixel::DynamixelHardwareInterface> dynamixel::DynamixelLoop::_hardware_interface
private

Abstract Hardware Interface for your robot.

Definition at line 101 of file dynamixel_loop.hpp.

struct timespec dynamixel::DynamixelLoop::_last_time
private

Definition at line 89 of file dynamixel_loop.hpp.

double dynamixel::DynamixelLoop::_loop_hz
private

Definition at line 88 of file dynamixel_loop.hpp.

ros::NodeHandle dynamixel::DynamixelLoop::_nh
private

Definition at line 75 of file dynamixel_loop.hpp.

ros::Timer dynamixel::DynamixelLoop::_non_realtime_loop
private

Definition at line 86 of file dynamixel_loop.hpp.

sensor_msgs::JointState dynamixel::DynamixelLoop::joint_state
private

Definition at line 77 of file dynamixel_loop.hpp.

ros::Subscriber dynamixel::DynamixelLoop::js_sub
private

Definition at line 78 of file dynamixel_loop.hpp.

ros::Publisher dynamixel::DynamixelLoop::torque_pub
private

Definition at line 83 of file dynamixel_loop.hpp.


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


svenzva_drivers
Author(s): Max Svetlik
autogenerated on Wed Oct 28 2020 03:31:27