JointCommandRigid.h
Go to the documentation of this file.
00001 
00006 #ifndef JOINTCOMMANDRIGID_H_
00007 #define JOINTCOMMANDRIGID_H_
00008 
00009 #include "robodyn_mechanisms/JointCommandInterface.h"
00010 #include "robot_instance/StringUtilities.h"
00011 
00012 class JointCommandRigid : public JointCommandInterface
00013 {
00014 public:
00015     JointCommandRigid(const std::string& mechanism, IoFunctions ioFunctions);
00016     virtual ~JointCommandRigid();
00017 
00018     sensor_msgs::JointState           getSimpleMeasuredState();
00019     sensor_msgs::JointState           getCompleteMeasuredState();
00020     r2_msgs::JointCommand getCommandedState();
00021     void setCommand(r2_msgs::JointCommand msg, r2_msgs::JointControlData);
00022     void updateMeasuredState(r2_msgs::JointControlData msg);
00023     void setFaultState();
00024 
00025     r2_msgs::JointCapability getCapability();
00026     void loadCoeffs();
00027 
00028 protected:
00029 
00030     std::string jointRoboDynJointName;
00031     std::string encoderRoboDynJointName;
00032 
00033     std::string jointPositionStatusElement;
00034     std::string encoderPositionStatusElement;
00035 
00036     std::string jointVelocityStatusElement;
00037     std::string encoderVelocityStatusElement;
00038 
00039     std::string desiredPositionCommandElement;
00040     std::string desiredPositionVelocityLimitCommandElement;
00041     std::string brakePwmCommandElement;
00042     std::string motComLimitCommandElement;
00043 
00044     double jointKinematicOffset;
00045     double        jointGearRatio;
00046 
00047     std::string encoderName;
00048 
00049     std::vector<double> positionVals;
00050     std::vector<double> velocityVals;
00051     std::vector<double> effortVals;
00052 
00053     unsigned int completeMessageSize;
00054 };
00055 
00056 #endif /* JOINTCOMMANDSERIESELASTIC_H_ */


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