JointCommandGripper.h
Go to the documentation of this file.
00001 
00006 #ifndef JOINTCOMMANDGRIPPER_H_
00007 #define JOINTCOMMANDGRIPPER_H_
00008 
00009 #include "robodyn_mechanisms/JointCommandInterface.h"
00010 #include "robot_instance/StringUtilities.h"
00011 
00012 class JointCommandGripper : public JointCommandInterface
00013 {
00014 public:
00015     JointCommandGripper(const std::string& mechanism, IoFunctions ioFunctions);
00016     virtual ~JointCommandGripper();
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     std::string jointRoboDynJointName;
00030     std::string jawLeftRoboDynJointName;
00031     std::string jawRightRoboDynJointName;
00032 
00033     std::string jointPositionStatusElement;
00034     std::string jawLeftPositionStatusElement;
00035     std::string jawRightPositionStatusElement;
00036 
00037     std::string jointVelocityStatusElement;
00038     std::string jawLeftVelocityStatusElement;
00039     std::string jawRightVelocityStatusElement;
00040 
00041     std::string jawLeftTorqueStatusElement;
00042     std::string jawRightTorqueStatusElement;
00043 
00044     std::string desiredPositionCommandElement;
00045     std::string desiredPositionVelocityLimitCommandElement;
00046     std::string feedForwardTorqueCommandElement;
00047     std::string proportionalGainCommandElement;
00048     std::string derivativeGainCommandElement;
00049     std::string integralGainCommandElement;
00050     std::string positionLoopTorqueLimitCommandElement;
00051     std::string positionLoopWindupLimitCommandElement;
00052 
00053     std::string jawLeftName;
00054     std::string jawRightName;
00055 
00056     std::string velLimitCommandElement;
00057     std::string curLimitCommandElement;
00058     std::string posKpCommandElement;
00059     std::string pLKiCommandElement;
00060     std::string posKdCommandElement;
00061     std::string pLWindupLimCommandElement;
00062     std::string pLKiMinCommandElement;
00063 
00064     std::vector<double> positionVals;
00065     std::vector<double> velocityVals;
00066     std::vector<double> effortVals;
00067 
00068     unsigned int completeMessageSize;
00069 };
00070 
00071 #endif /* JOINTCOMMANDGRIPPER_H_ */


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