Public Member Functions | List of all members
RosReflexxesInterface Class Referenceabstract

#include <RosReflexxesInterface.h>

Inheritance diagram for RosReflexxesInterface:
Inheritance graph
[legend]

Public Member Functions

virtual std::vector< double > get_current_acceleration ()=0
 
virtual std::vector< double > get_current_position ()=0
 
virtual std::vector< double > get_current_velocity ()=0
 
virtual std::vector< double > get_target_command ()=0
 
virtual bool init (ros::NodeHandle nh)=0
 
virtual void set_target_command (const std::vector< double > &command)=0
 
virtual void set_target_position (const std::vector< double > &t_pos)=0
 
virtual void set_target_velocity (const std::vector< double > &t_vel)=0
 
virtual void starting (const std::vector< double > &initial_command)=0
 
virtual std::vector< double > update ()=0
 
std::vector< double > update (const std::vector< double > &command)
 
virtual ~RosReflexxesInterface ()
 

Detailed Description

Definition at line 12 of file RosReflexxesInterface.h.

Constructor & Destructor Documentation

virtual RosReflexxesInterface::~RosReflexxesInterface ( )
inlinevirtual

Definition at line 16 of file RosReflexxesInterface.h.

Member Function Documentation

virtual std::vector<double> RosReflexxesInterface::get_current_acceleration ( )
pure virtual
virtual std::vector<double> RosReflexxesInterface::get_current_position ( )
pure virtual
virtual std::vector<double> RosReflexxesInterface::get_current_velocity ( )
pure virtual
virtual std::vector<double> RosReflexxesInterface::get_target_command ( )
pure virtual

make ros interface generic

Implemented in RosReflexxesPositionInterface, and RosReflexxesVelocityInterface.

virtual bool RosReflexxesInterface::init ( ros::NodeHandle  nh)
pure virtual
virtual void RosReflexxesInterface::set_target_command ( const std::vector< double > &  command)
pure virtual
virtual void RosReflexxesInterface::set_target_position ( const std::vector< double > &  t_pos)
pure virtual
virtual void RosReflexxesInterface::set_target_velocity ( const std::vector< double > &  t_vel)
pure virtual
virtual void RosReflexxesInterface::starting ( const std::vector< double > &  initial_command)
pure virtual
virtual std::vector<double> RosReflexxesInterface::update ( )
pure virtual
std::vector<double> RosReflexxesInterface::update ( const std::vector< double > &  command)
inline

Definition at line 24 of file RosReflexxesInterface.h.


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


ros_reflexxes
Author(s):
autogenerated on Sat Nov 21 2020 03:17:43