Go to the documentation of this file.00001 #include "riq_hand_ethercat_hardware/riq_hand_state.h"
00002
00003 namespace riq_hand_ethercat_hardware
00004 {
00005
00006
00007 const char* RIQGripperStatus::modeString(unsigned mode)
00008 {
00009 switch(mode)
00010 {
00011 case CYLINDRICAL_MODE:
00012 return "Cylindrical";
00013 case PINCH_MODE:
00014 return "Pinch";
00015 case SPHERIOD_MODE:
00016 return "Spheriod";
00017 case SCISSORS_MODE:
00018 return "Scissors";
00019 default:
00020 return "Unknown";
00021 };
00022 }
00023
00024 const char* RIQGripperStatus::gripString(unsigned grip)
00025 {
00026 switch(grip)
00027 {
00028 case GRIP_STOPPED:
00029 return "Stop";
00030 case GRIP_OPENED:
00031 return "Open";
00032 case GRIP_CLOSED:
00033 return "Close";
00034 case GRIP_INITIALIZING_OR_CHANGING:
00035 return "Mode Change, Initialization";
00036 default:
00037 return "Unknown";
00038 };
00039 }
00040
00041 const char* RIQGripperStatus::statusString(unsigned status)
00042 {
00043 switch (status)
00044 {
00045 case ACTION_FAULTED:
00046 return "Requested action has faulted";
00047 case ACTION_IN_PROGRESS:
00048 return "Requested action is in progress";
00049 case ACTION_ILLEGAL_UNDEFINED:
00050 return "Illegal/Undefined";
00051 case ACTION_SUCCESSFUL:
00052 return "Requested action was successfully completed";
00053 default:
00054 return "Unknown";
00055 }
00056 }
00057
00058
00059 const char* RIQObjectStatus::detectedString(unsigned detected, bool in_scissors_mode)
00060 {
00061 if (in_scissors_mode)
00062 {
00063 switch (detected)
00064 {
00065 case OBJECT_NOT_DETECTED:
00066 return "No object detected";
00067 case OBJECT_DETECTED_1_FINGER:
00068 case OBJECT_DETECTED_2_FINGERS:
00069 return "Invalid in scissors mode";
00070 case OBJECT_DETECTED_ALL_FINGERS:
00071 return "Scissors detected an object";
00072 default:
00073 return "Unknown";
00074 }
00075 }
00076 else
00077 {
00078 switch (detected)
00079 {
00080 case OBJECT_NOT_DETECTED:
00081 return "No object detected";
00082 case OBJECT_DETECTED_1_FINGER:
00083 return "One finger detected an object";
00084 case OBJECT_DETECTED_2_FINGERS:
00085 return "Two fingers detected an object";
00086 case OBJECT_DETECTED_ALL_FINGERS:
00087 return "All fingers detected an object";
00088 default:
00089 return "Unknown";
00090 }
00091 }
00092 }
00093
00094 const char* RIQObjectStatus::wasDetectedString(bool was_detected)
00095 {
00096 return (was_detected) ? "An object was detected by the " : "No object was detected by the ";
00097 }
00098
00099
00100
00101 const char* RIQHandStateEcat::faultString(unsigned fault)
00102 {
00103 switch (fault)
00104 {
00105 case FAULT_NEED_INITIALIZATION_TO_COMPLETE:
00106 return "Action delayed, initialization must be completed prior to action";
00107 case FAULT_NEED_MODE_CHANGE_TO_COMPLETE:
00108 return "Action delayed, mode change must be completed priod to action";
00109 case FAULT_COMMUNICATION_TIMEOUT:
00110 return "Communication timeout, Gripper is stopped";
00111 case FAULT_INSUFFICIENT_SUPPLY_VOLTAGE:
00112 return "Insufficient supply voltage, Gripper is stoppped";
00113 case FAULT_CHANGING_MODE_INTERFERENCE_SCISSORS:
00114 return "Changing mode fault, interferences detected on Scissors";
00115 case FAULT_OPENING_INTERFERENCE_FINGERS:
00116 return "Gripper opening fault, interferences detected on Fingers";
00117 case FAULT_OPENING_INTERFERENCE_SCISSORS:
00118 return "Gripper opening fault, interferences detected on Scissors";
00119 case FAULT_CLOSING_INTERFERENCE_FINGERS:
00120 return "Gripper closing fault, abnormal displacement of Fingers";
00121 case FAULT_CLOSING_INTERFERENCE_SCISSORS:
00122 return "Gripper closing fault, abnormal displacement of Scissors";
00123 case FAULT_MAJOR_SCISSORS_DISPLACEMENT:
00124 return "Initialization fault, insufficient Scissors displacement";
00125 case FAULT_MAJOR_FINGER_DISPLACEMENT:
00126 return "Initialization fault, insufficient Fingers displacement";
00127 case NO_FAULT:
00128 return "No fault";
00129 default:
00130 return "Unknown fault";
00131 }
00132 }
00133
00134
00135 double RIQHandStateEcat::convertPosition(unsigned position)
00136 {
00137 return double(position) * (1.0 / 255.0);
00138 }
00139
00140
00141 double RIQHandStateEcat::convertCurrent(unsigned current)
00142 {
00143
00144 return double(current) * 0.1 * 0.001;
00145 }
00146
00147 };