Classes | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
JointCommandInterface Class Reference

#include <JointCommandInterface.h>

Inheritance diagram for JointCommandInterface:
Inheritance graph
[legend]

List of all members.

Classes

class  IoFunctions

Public Member Functions

virtual r2_msgs::JointCapability getCapability ()=0
virtual r2_msgs::JointCommand getCommandedState ()=0
virtual sensor_msgs::JointState getCompleteMeasuredState ()=0
virtual sensor_msgs::JointState getSimpleMeasuredState ()=0
virtual void loadCoeffs ()=0
virtual void setCommand (r2_msgs::JointCommand msg, r2_msgs::JointControlData control)=0
virtual void updateMeasuredState (r2_msgs::JointControlData msg)=0

Public Attributes

std::string mechanism
std::vector< std::string > roboDynActuators
std::vector< std::string > roboDynAllJoints
std::vector< std::string > roboDynJoints

Protected Member Functions

 JointCommandInterface (const std::string &mechanism, IoFunctions io)
virtual ~JointCommandInterface ()

Protected Attributes

r2_msgs::JointCommand commandedStateMsg
sensor_msgs::JointState completeMeasuredStateMsg
IoFunctions io
r2_msgs::JointCapability jointCapabilityMsg
sensor_msgs::JointState simpleMeasuredStateMsg

Detailed Description

Definition at line 21 of file JointCommandInterface.h.


Constructor & Destructor Documentation

JointCommandInterface::JointCommandInterface ( const std::string &  mechanism,
IoFunctions  io 
) [inline, protected]

Definition at line 72 of file JointCommandInterface.h.

virtual JointCommandInterface::~JointCommandInterface ( ) [inline, protected, virtual]

Definition at line 75 of file JointCommandInterface.h.


Member Function Documentation

virtual r2_msgs::JointCapability JointCommandInterface::getCapability ( ) [pure virtual]
virtual r2_msgs::JointCommand JointCommandInterface::getCommandedState ( ) [pure virtual]
virtual sensor_msgs::JointState JointCommandInterface::getCompleteMeasuredState ( ) [pure virtual]
virtual sensor_msgs::JointState JointCommandInterface::getSimpleMeasuredState ( ) [pure virtual]
virtual void JointCommandInterface::loadCoeffs ( ) [pure virtual]
virtual void JointCommandInterface::setCommand ( r2_msgs::JointCommand  msg,
r2_msgs::JointControlData  control 
) [pure virtual]
virtual void JointCommandInterface::updateMeasuredState ( r2_msgs::JointControlData  msg) [pure virtual]

Member Data Documentation

r2_msgs::JointCommand JointCommandInterface::commandedStateMsg [protected]

Definition at line 81 of file JointCommandInterface.h.

sensor_msgs::JointState JointCommandInterface::completeMeasuredStateMsg [protected]

Definition at line 80 of file JointCommandInterface.h.

Definition at line 75 of file JointCommandInterface.h.

r2_msgs::JointCapability JointCommandInterface::jointCapabilityMsg [protected]

Definition at line 82 of file JointCommandInterface.h.

Definition at line 67 of file JointCommandInterface.h.

std::vector<std::string> JointCommandInterface::roboDynActuators

Definition at line 69 of file JointCommandInterface.h.

std::vector<std::string> JointCommandInterface::roboDynAllJoints

Definition at line 68 of file JointCommandInterface.h.

std::vector<std::string> JointCommandInterface::roboDynJoints

Definition at line 68 of file JointCommandInterface.h.

sensor_msgs::JointState JointCommandInterface::simpleMeasuredStateMsg [protected]

Definition at line 79 of file JointCommandInterface.h.


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


robodyn_mechanisms
Author(s):
autogenerated on Thu Jun 6 2019 21:22:49