Public Member Functions | Protected Attributes
JointCommandSeriesElastic Class Reference

#include <JointCommandSeriesElastic.h>

Inheritance diagram for JointCommandSeriesElastic:
Inheritance graph
[legend]

List of all members.

Public Member Functions

r2_msgs::JointCapability getCapability ()
r2_msgs::JointCommand getCommandedState ()
sensor_msgs::JointState getCompleteMeasuredState ()
sensor_msgs::JointState getSimpleMeasuredState ()
 JointCommandSeriesElastic (const std::string &mechanism, IoFunctions ioFunctions)
void loadCoeffs ()
void setCommand (r2_msgs::JointCommand msg, r2_msgs::JointControlData)
void setFaultState ()
void updateMeasuredState (r2_msgs::JointControlData msg)
virtual ~JointCommandSeriesElastic ()

Protected Attributes

double backEmfConstant
std::string brakePwmCommandElement
double combinedStiffness
double commandRate
unsigned int completeMessageSize
double deltaEncPos
ros::Duration deltaTime
double deltaTimeSec
std::string derivativeGainCommandElement
std::string desiredPositionCommandElement
std::string desiredPositionVelocityLimitCommandElement
std::vector< double > effortVals
std::string embeddedCommandEffortElement
std::string embeddedCommandName
std::string embeddedCommandPositionElement
 embedded command
std::string embeddedCommandVelocityElement
std::string encoderCalculatedName
std::string encoderName
std::string encoderPositionStatusElement
 encoder status
std::string encoderRawPositionStatusElement
 encoder calculated
std::string encoderTimeElement
std::string encoderTimeoutElement
std::string encoderVelocityStatusElement
double encPosRef
std::string feedForwardTorqueCommandElement
double gearStiffness
int32_t hallEncNow
int32_t hallEncPrev
int32_t hallEncRef
std::string hallPositionStatusElement
 halls calculated
double hallPosRef
std::string hallRawPositionStatusElement
std::string hallsCalculatedName
HallsEncoderStateCalculatorPtr hallsEncoderStateCalculator
std::string hallTimeElement
std::string hallTimeoutElement
int32_t incEncNow
int32_t incEncPrev
int32_t incEncRef
std::string integralGainCommandElement
bool isInitialized
std::string jointCalculatedEffortElement
std::string jointCalculatedName
double jointGearRatio
double jointKinematicDirection
double jointKinematicOffset
std::string jointPositionFilteredStatusElement
 joint calculated
std::string jointPositionStatusElement
 joint status
std::string jointVelocityStatusElement
std::string motComLimitCommandElement
std::string motorCurrentElement
MotorEncoderStateCalculatorPtr motorEncoderStateCalculator
std::string motorName
std::string motorPositionFilteredStatusElement
std::string motorPositionStatusElement
 motor status
std::string motorVelocityStatusElement
std::string positionLoopTorqueLimitCommandElement
std::string positionLoopWindupLimitCommandElement
std::vector< double > positionVals
std::string proportionalGainCommandElement
double springConstant
ros::Time timeNow
ros::Time timePrev
std::string torqueLoopVelocityLimitCommandElement
std::vector< double > velocityVals

Detailed Description

Definition at line 14 of file JointCommandSeriesElastic.h.


Constructor & Destructor Documentation

JointCommandSeriesElastic::JointCommandSeriesElastic ( const std::string &  mechanism,
IoFunctions  ioFunctions 
)

Definition at line 8 of file JointCommandSeriesElastic.cpp.

Definition at line 117 of file JointCommandSeriesElastic.cpp.


Member Function Documentation

r2_msgs::JointCapability JointCommandSeriesElastic::getCapability ( ) [virtual]

Implements JointCommandInterface.

Definition at line 539 of file JointCommandSeriesElastic.cpp.

r2_msgs::JointCommand JointCommandSeriesElastic::getCommandedState ( ) [virtual]

Implements JointCommandInterface.

Definition at line 448 of file JointCommandSeriesElastic.cpp.

sensor_msgs::JointState JointCommandSeriesElastic::getCompleteMeasuredState ( ) [virtual]

Implements JointCommandInterface.

Definition at line 433 of file JointCommandSeriesElastic.cpp.

sensor_msgs::JointState JointCommandSeriesElastic::getSimpleMeasuredState ( ) [virtual]

Implements JointCommandInterface.

Definition at line 422 of file JointCommandSeriesElastic.cpp.

Initialize messages

Parse parameter file

Status Elements joint

motor

encoder

jointCalculated

encoderCalculated

hallsCalculated

embeddedCommand

Command Elements

Capability Elements

Set robot limits

Needed to use the constructor version of make_shared because of the number of arguments in EncoderStateCalculator's constructor.

Implements JointCommandInterface.

Definition at line 120 of file JointCommandSeriesElastic.cpp.

void JointCommandSeriesElastic::setCommand ( r2_msgs::JointCommand  msg,
r2_msgs::JointControlData   
) [virtual]

Implements JointCommandInterface.

Definition at line 464 of file JointCommandSeriesElastic.cpp.

Definition at line 444 of file JointCommandSeriesElastic.cpp.

void JointCommandSeriesElastic::updateMeasuredState ( r2_msgs::JointControlData  msg) [virtual]

encoderCalculated and hallsCalculated initialization

joint

motor

jointGearRatio to get into joint space

encoder

jointGearRatio to get into joint space

jointCalculated

APS1 - APS2

encoderCalculated --effort val - replace encoderPositoinStatusElement with positionval (filtered) ???

jointGearRatio to get into joint space

enc - APS2

hallsCalculated

jointGearRatio to get into joint space

embeddedCommand

Implements JointCommandInterface.

Definition at line 358 of file JointCommandSeriesElastic.cpp.


Member Data Documentation

Definition at line 84 of file JointCommandSeriesElastic.h.

Definition at line 75 of file JointCommandSeriesElastic.h.

Definition at line 80 of file JointCommandSeriesElastic.h.

Definition at line 98 of file JointCommandSeriesElastic.h.

Definition at line 112 of file JointCommandSeriesElastic.h.

Definition at line 97 of file JointCommandSeriesElastic.h.

Definition at line 95 of file JointCommandSeriesElastic.h.

Definition at line 96 of file JointCommandSeriesElastic.h.

Definition at line 70 of file JointCommandSeriesElastic.h.

Definition at line 66 of file JointCommandSeriesElastic.h.

Definition at line 67 of file JointCommandSeriesElastic.h.

std::vector<double> JointCommandSeriesElastic::effortVals [protected]

Definition at line 109 of file JointCommandSeriesElastic.h.

Definition at line 64 of file JointCommandSeriesElastic.h.

Definition at line 105 of file JointCommandSeriesElastic.h.

embedded command

Definition at line 62 of file JointCommandSeriesElastic.h.

Definition at line 63 of file JointCommandSeriesElastic.h.

Definition at line 103 of file JointCommandSeriesElastic.h.

std::string JointCommandSeriesElastic::encoderName [protected]

Definition at line 101 of file JointCommandSeriesElastic.h.

encoder status

Definition at line 43 of file JointCommandSeriesElastic.h.

encoder calculated

Definition at line 51 of file JointCommandSeriesElastic.h.

Definition at line 52 of file JointCommandSeriesElastic.h.

Definition at line 53 of file JointCommandSeriesElastic.h.

Definition at line 44 of file JointCommandSeriesElastic.h.

Definition at line 88 of file JointCommandSeriesElastic.h.

Definition at line 68 of file JointCommandSeriesElastic.h.

Definition at line 79 of file JointCommandSeriesElastic.h.

Definition at line 89 of file JointCommandSeriesElastic.h.

Definition at line 90 of file JointCommandSeriesElastic.h.

Definition at line 91 of file JointCommandSeriesElastic.h.

halls calculated

Definition at line 56 of file JointCommandSeriesElastic.h.

Definition at line 92 of file JointCommandSeriesElastic.h.

Definition at line 57 of file JointCommandSeriesElastic.h.

Definition at line 104 of file JointCommandSeriesElastic.h.

HallsEncoderStateCalculatorPtr JointCommandSeriesElastic::hallsEncoderStateCalculator [protected]

Definition at line 115 of file JointCommandSeriesElastic.h.

Definition at line 58 of file JointCommandSeriesElastic.h.

Definition at line 59 of file JointCommandSeriesElastic.h.

Definition at line 85 of file JointCommandSeriesElastic.h.

Definition at line 86 of file JointCommandSeriesElastic.h.

Definition at line 87 of file JointCommandSeriesElastic.h.

Definition at line 71 of file JointCommandSeriesElastic.h.

Definition at line 111 of file JointCommandSeriesElastic.h.

Definition at line 35 of file JointCommandSeriesElastic.h.

Definition at line 102 of file JointCommandSeriesElastic.h.

Definition at line 83 of file JointCommandSeriesElastic.h.

Definition at line 82 of file JointCommandSeriesElastic.h.

Definition at line 81 of file JointCommandSeriesElastic.h.

joint calculated

Definition at line 47 of file JointCommandSeriesElastic.h.

joint status

Definition at line 33 of file JointCommandSeriesElastic.h.

Definition at line 34 of file JointCommandSeriesElastic.h.

Definition at line 76 of file JointCommandSeriesElastic.h.

Definition at line 40 of file JointCommandSeriesElastic.h.

MotorEncoderStateCalculatorPtr JointCommandSeriesElastic::motorEncoderStateCalculator [protected]

Definition at line 114 of file JointCommandSeriesElastic.h.

std::string JointCommandSeriesElastic::motorName [protected]

Definition at line 100 of file JointCommandSeriesElastic.h.

Definition at line 48 of file JointCommandSeriesElastic.h.

motor status

Definition at line 38 of file JointCommandSeriesElastic.h.

Definition at line 39 of file JointCommandSeriesElastic.h.

Definition at line 72 of file JointCommandSeriesElastic.h.

Definition at line 73 of file JointCommandSeriesElastic.h.

std::vector<double> JointCommandSeriesElastic::positionVals [protected]

Definition at line 107 of file JointCommandSeriesElastic.h.

Definition at line 69 of file JointCommandSeriesElastic.h.

Definition at line 78 of file JointCommandSeriesElastic.h.

Definition at line 93 of file JointCommandSeriesElastic.h.

Definition at line 94 of file JointCommandSeriesElastic.h.

Definition at line 74 of file JointCommandSeriesElastic.h.

std::vector<double> JointCommandSeriesElastic::velocityVals [protected]

Definition at line 108 of file JointCommandSeriesElastic.h.


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


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