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

#include <dynamixel_hardware_interface.hpp>

Inheritance diagram for dynamixel::DynamixelHardwareInterface:
Inheritance graph
[legend]

Public Member Functions

 DynamixelHardwareInterface ()
 
void init (ros::NodeHandle nh)
 
void read_joints (sensor_msgs::JointState js)
 
std::vector< double > write_joints ()
 
 ~DynamixelHardwareInterface ()
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
 RobotHW ()
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual ~RobotHW ()
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Private Member Functions

 DynamixelHardwareInterface (DynamixelHardwareInterface const &)
 
DynamixelHardwareInterfaceoperator= (DynamixelHardwareInterface const &)
 

Private Attributes

hardware_interface::EffortJointInterface _jnt_effort_interface
 
hardware_interface::JointStateInterface _jnt_state_interface
 
std::vector< double > _joint_angles
 
std::vector< double > _joint_commands
 
std::vector< double > _joint_efforts
 
std::vector< std::string > _joint_names
 
std::vector< double > _joint_velocities
 
std::vector< double > _prev_commands
 
ros::Publisher torque_pub
 

Additional Inherited Members

- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 16 of file dynamixel_hardware_interface.hpp.

Constructor & Destructor Documentation

dynamixel::DynamixelHardwareInterface::DynamixelHardwareInterface ( )

Definition at line 12 of file dynamixel_hardware_interface.cpp.

dynamixel::DynamixelHardwareInterface::~DynamixelHardwareInterface ( )

Definition at line 15 of file dynamixel_hardware_interface.cpp.

dynamixel::DynamixelHardwareInterface::DynamixelHardwareInterface ( DynamixelHardwareInterface const &  )
private

Member Function Documentation

void dynamixel::DynamixelHardwareInterface::init ( ros::NodeHandle  nh)

Definition at line 19 of file dynamixel_hardware_interface.cpp.

DynamixelHardwareInterface& dynamixel::DynamixelHardwareInterface::operator= ( DynamixelHardwareInterface const &  )
private
void dynamixel::DynamixelHardwareInterface::read_joints ( sensor_msgs::JointState  js)

Copy joint's information to memory

firstly queries the information from the dynamixels, then put it in private attributes, for use by a controller.

Warning: do not get any information on torque

Definition at line 73 of file dynamixel_hardware_interface.cpp.

std::vector< double > dynamixel::DynamixelHardwareInterface::write_joints ( )

Send new joint's target position to dynamixels

takes the target position from memory (given by a controller) and sends them to the dynamixels.

Definition at line 88 of file dynamixel_hardware_interface.cpp.

Member Data Documentation

hardware_interface::EffortJointInterface dynamixel::DynamixelHardwareInterface::_jnt_effort_interface
private

Definition at line 35 of file dynamixel_hardware_interface.hpp.

hardware_interface::JointStateInterface dynamixel::DynamixelHardwareInterface::_jnt_state_interface
private

Definition at line 34 of file dynamixel_hardware_interface.hpp.

std::vector<double> dynamixel::DynamixelHardwareInterface::_joint_angles
private

Definition at line 42 of file dynamixel_hardware_interface.hpp.

std::vector<double> dynamixel::DynamixelHardwareInterface::_joint_commands
private

Definition at line 41 of file dynamixel_hardware_interface.hpp.

std::vector<double> dynamixel::DynamixelHardwareInterface::_joint_efforts
private

Definition at line 44 of file dynamixel_hardware_interface.hpp.

std::vector<std::string> dynamixel::DynamixelHardwareInterface::_joint_names
private

Definition at line 39 of file dynamixel_hardware_interface.hpp.

std::vector<double> dynamixel::DynamixelHardwareInterface::_joint_velocities
private

Definition at line 43 of file dynamixel_hardware_interface.hpp.

std::vector<double> dynamixel::DynamixelHardwareInterface::_prev_commands
private

Definition at line 40 of file dynamixel_hardware_interface.hpp.

ros::Publisher dynamixel::DynamixelHardwareInterface::torque_pub
private

Definition at line 45 of file dynamixel_hardware_interface.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