This file contains all data structures and all data type(enum and typedef) that you'll need to use this API. More...
Classes | |
| struct | AngularInfo |
| This data structure holds values in an angular(joint by joint) control context. As an example struct could contains position, temperature, torque, ... More... | |
| struct | CartesianInfo |
| This data structure holds values in an cartesian control context. More... | |
| struct | SensorsInfo |
| This data structure holds the values of the robot's sensors. More... | |
| struct | FingersPosition |
| This data structure holds the values of the robot's fingers. More... | |
| struct | CartesianPosition |
| This data structure holds the values of a cartesian position. More... | |
| struct | AngularPosition |
| This data structure holds the values of an angular(actuators) position. More... | |
| struct | Limitation |
| This data structure represents all limitation that can be applied to a control context. More... | |
| struct | UserPosition |
| This data structure represents an abstract position built by a user. Depending on the control type the Cartesian information, the angular information or both will be used. More... | |
| struct | TrajectoryPoint |
| This data structure represents a point of a trajectory. It contains the position a limitation that you can applied. More... | |
| struct | TrajectoryFIFO |
| This data structure represents the informations regarding the robot's trajectory's FIFO. More... | |
| struct | SingularityVector |
| This data structure represents the informations regarding the singularities surrounding the end effector. It is not used for now but will be in the future. More... | |
| struct | JoystickCommand |
| This is a virtual representation of a 6-axis joystick. More... | |
| struct | ClientConfigurations |
| This structure holds informations relative to the client. It is mostly used for rehab clients. As an example, if you need to modify the max velocity or the retract position, it will be done here. The easiest way to modify the client configuration is to get the current one by calling the function GetClientConfigurations, modify all the parameters you need and send the structure back to the robot by calling the function SetClientConfigurations(). Note that some of the parameters are read only. That means that even if you modify them and send the structure to the robot, they will not be modified. More... | |
| struct | StickEvents |
| This is an event from a controller's stick. Each variable of the struct can be mapped with a ControlFunctionalityTypeEnum. More... | |
| struct | ButtonEvents |
| This is an event from a controller's button. Each variable of the struct can be mapped with a ControlFunctionalityTypeEnum. More... | |
| struct | ControlsModeMap |
| Represents one mode map of a control mapping. Each control mapping has 2 list of mode map. More... | |
| struct | ControlMapping |
| This represents a group of functionalities mapped to some events triggered by a specific controller. More... | |
| struct | ControlMappingCharts |
| This structure holds all the control mapping of the system. It is the entry point if you want to use the mapping system. More... | |
| struct | SystemError |
| This represents a system error. Every error generated by the system is logged in the robot's flash memory. More... | |
| struct | ZoneLimitation |
| This represents a group of limitations that can be applied to a trajectory point. More... | |
| struct | ForcesInfo |
| This structure contains informations about the torque and the force of the robotical arm. More... | |
| struct | QuickStatus |
| This structure holds various informations but mostly it is flag status. More... | |
| struct | Finger |
| Structure that represents a finger from the end effector's tool. More... | |
| struct | Gripper |
| Structure that represents the robotical arm's gripper. More... | |
| struct | ZoneShape |
| Represents the 3D shape of a protection zone. More... | |
| struct | Zone |
| that represents a protection zone. More... | |
| struct | ZoneList |
| This structure represents the complete list of protection zone of the robotical arm. More... | |
| struct | SystemStatus |
| This structure holds system status flags. More... | |
| struct | GeneralInformations |
| This is structure hold almost all information of the robotical arm. More... | |
| struct | AngularAcceleration |
| This data structure holds acceleration values(X, Y, Z) in an angular(joint by joint) control context. More... | |
| struct | PeripheralInfo |
| This data structure holds information that describes an abstract peripheral. More... | |
Defines | |
| #define | JOYSTICK_BUTTON_COUNT 16 |
| Size of the ControlsModeMap array in the structure JoystickCommand. | |
| #define | NB_ADVANCE_RETRACT_POSITION 20 |
| Max size of the advance retract trajectory that is stored in the ClientConfigurations. | |
| #define | ERROR_DATA_COUNT_MAX 50 |
| This is the size of the data array stored in a SystemError object. | |
| #define | ERROR_LAYER_COUNT 7 |
| The robot's firmware has several software layers. This describes how many layer there is in the firmware. | |
| #define | LEGACY_CONFIG_NB_ZONES_MAX 10 |
| This represents the max count of protection zones that can be stored in the robot's memory. | |
| #define | LEGACY_CONFIG_NB_POINTS_COUNT 8 |
| This is the size of the array Points in a ZoneShape . | |
| #define | CONTROL_MAPPING_COUNT 6 |
| This is the size of the array Mapping contained in the structure ControlMappingCharts . | |
| #define | MODE_MAP_COUNT 6 |
| This is the size of the arrays ModeControlsA and ModeControlsB contained in the structure ControlMapping . | |
| #define | STICK_EVENT_COUNT 6 |
| This is the size of the array ControlSticks contained in the structure ControlsModeMap . | |
| #define | BUTTON_EVENT_COUNT 26 |
| This is the size of the array ControlButtons contained in the structure ControlsModeMap . | |
| #define | STRING_LENGTH 20 |
| This is the size of all strings stored in the robot's firmware. | |
| #define | JACO_FINGERS_COUNT 3 |
| This is the max finger count in a robot. (Jaco has 3 fingers and Mico has 2 fingers) | |
| #define | ERROR_UNKNOWFILE 5001 |
| This is an error code. It means that the file you are trying to interact with does not exist or is corrupted. Either way, the OS does not recognise it. | |
| #define | ERROR_MEMORY 5002 |
| This is an error code. It means that there was a memory related error. Most of the time it is because the system does not have enough memory. | |
| #define | ERROR_FILEREADING 5003 |
| This is an error code. It means that the function has some problem reading a file. Most of the time it is because the user don't have the privileges to do it. | |
Enumerations | |
| enum | POSITION_TYPE { NOMOVEMENT_POSITION = 0, CARTESIAN_POSITION = 1, ANGULAR_POSITION = 2, CARTESIAN_VELOCITY = 7, ANGULAR_VELOCITY = 8, ANY_TRAJECTORY = 11, TIME_DELAY = 12 } |
| That represents the type of a position. If used during a trajectory, the type of position will change the behaviour of the robot. For example if the position type is CARTESIAN_POSITION, then the robot's end effector will move to that position using the inverse kinematics. But if the type of position is CARTESIAN_VELOCITY then the robot will use the values as velocity command. More... | |
| enum | PERIPHERAL_TYPE { PERIPHERAL_TYPE_NONE = 0, PERIPHERAL_TYPE_ANY = 1, PERIPHERAL_TYPE_ACTUATORK01 = 100, PERIPHERAL_TYPE_FINGERK01 = 200, PERIPHERAL_TYPE_JOYSTICK = 300, PERIPHERAL_TYPE_VIRTUAL_JOYSTICK = 301, PERIPHERAL_TYPE_CAN_INTERFACE = 400 } |
| enum | HAND_MODE { HAND_NOMOVEMENT, POSITION_MODE, VELOCITY_MODE } |
| That indicates how the end effector will be used. More... | |
| enum | ArmLaterality { RIGHTHAND, LEFTHAND } |
| That indicates if the robot will be left handed or right handed. More... | |
| enum | Controller { THREE_AXIS_JOYSTICK = 0, TWO_AXIS_JOYSTICK = 1, API = 2, EASY_RIDER = 3, UNIVERSAL_INTERFACE = 4, EXTERNAL_CUSTOMINTERFACE = 5, NONE = 6, OLED_DISPLAY = 7 } |
| This represents a type of controller. A controller is an entity that can send control commands to the robot. More... | |
| enum | CONTROL_TYPE { CONTROL_TYPE_CARTESIAN = 0, CONTROL_TYPE_ANGULAR = 1 } |
| This represents a type of control. For now, there is 2 type of control, it can either cartesian control or angular control. More... | |
| enum | CONTROL_MODULE { CONTROL_MODULE_NONE, CONTROL_MODULE_ANGULAR_VELOCITY, CONTROL_MODULE_ANGULAR_POSITION, CONTROL_MODULE_CARTESIAN_VELOCITY, CONTROL_MODULE_CARTESIAN_POSITION, CONTROL_MODULE_RETRACT, CONTROL_MODULE_TRAJECTORY, CONTROL_MODULE_PREDEFINED, CONTROL_MODULE_TIMEDELAY } |
| That describes a control module of the robotical arm's firmware. More... | |
| enum | RETRACT_TYPE { RETRACT_TYPE_NORMAL_TO_READY = 0, RETRACT_TYPE_READY_STANDBY = 1, RETRACT_TYPE_READY_TO_RETRACT = 2, RETRACT_TYPE_RETRACT_STANDBY = 3, RETRACT_TYPE_RETRACT_TO_READY = 4, RETRACT_TYPE_NORMAL_STANDBY = 5, RETRACT_TYPE_NOT_INITIALIZED = 6 } |
| This describes the retract type the robotical arm. More... | |
| enum | ControlFunctionalityTypeEnum { CF_NoFunctionality = 0, CF_Disable_EnableJoystick = 1, CF_Retract_ReadyToUse = 2, CF_Change_TwoAxis_ThreeAxis = 3, CF_Change_DrinkingMode = 4, CF_Cycle_ModeA_list = 5, CF_Cycle_ModeB_list = 6, CF_DecreaseSpeed = 7, CF_IncreaseSpeed = 8, CF_Goto_Position1 = 9, CF_Goto_Position2 = 10, CF_Goto_Position3 = 11, CF_Goto_Position4 = 12, CF_Goto_Position5 = 13, CF_RecordPosition1 = 14, CF_RecordPosition2 = 15, CF_RecordPosition3 = 16, CF_RecordPosition4 = 17, CF_RecordPosition5 = 18, CF_X_Positive = 19, CF_X_Negative = 20, CF_Y_Positive = 21, CF_Y_Negative = 22, CF_Z_Positive = 23, CF_Z_Negative = 24, CF_R_Positive = 25, CF_R_Negative = 26, CF_U_Positive = 27, CF_U_Negative = 28, CF_V_Positive = 29, CF_V_Negative = 30, CF_OpenHandOneFingers = 31, CF_CloseHandOneFingers = 32, CF_OpenHandTwoFingers = 33, CF_CloseHandTwoFingers = 34, CF_OpenHandThreeFingers = 35, CF_CloseHandThreeFingers = 36, CF_ForceAngularVelocity = 37, CF_ForceControlStatus = 38 , CF_AutomaticOrientationXPlus = 40, CF_AutomaticOrientationXMinus = 41, CF_AutomaticOrientationYPlus = 42, CF_AutomaticOrientationYMinus = 43, CF_AutomaticOrientationZPlus = 44, CF_AutomaticOrientationZMinus = 45, CF_AdvanceGOTO_1 = 46, CF_AdvanceGOTO_Clear_1 = 47, CF_AdvanceGOTO_Add_1 = 48 } |
| This is the list of available feature that can be mapped with a controller through the mappign system. Every list of mode that a mapping contains is mapped with one of these features. The default value is CF_NoFunctionality. More... | |
| enum | ControlMappingMode { OneAxis, TwoAxis, ThreeAxis, SixAxis } |
| Indicates the type of controller. More... | |
| enum | errorLoggerType { ERROR_NOTINITIALIZED, keos_err1, keos_err2, keos_err3, User_err_start_marker, errorlog_Actuator_Temperature, errorlog_Actuator_TemperatureOK, errorlog_Finger_Temperature, errorlog_Finger_TemperatureOK, errorlog_voltage, errorlog_voltageOK, errorlog_current_FingersClosing, errorlog_current_FingersOpening, errorlog_current_FingersOK, errorlog_current_Actuators, errorlog_current_ActuatorsOK, errorLog_RobotStatus_Build_Incomplete, errorLogger_END } |
| That represents the type of an error. It is used mostly for identification. More... | |
| enum | ShapeType { PrismSquareBase_X = 0, PrismSquareBase_Y = 1, PrismSquareBase_Z = 2, PrismTriangularBase_X = 3, PrismTriangularBase_Y = 4, PrismTriangularBase_Z = 5, Pyramid = 6 } |
| This represents the type of a 3d shape. More... | |
Variables | |
| const unsigned short | PAGE_SIZE = 2048 |
| This represents the size of a memory page used to program the robot. | |
| const int | ADDRESS_PAGE_SIZE = 4 |
| This represents the size of a page's address. | |
| const unsigned short | PACKET_PER_PAGE_QTY = 40 |
| This represents the quantity of USB packet stored in a memory page. | |
| const int | PAGEPACKET_SIZE = 52 |
| That represents the data's size of each USB packet during firmware update. | |
| const int | USB_HEADER_SIZE = 8 |
| That represents the size of a USB packet's header. | |
| const int | USB_DATA_SIZE = 56 |
| That represents the data's size of a normal USB packet. | |
This file contains all data structures and all data type(enum and typedef) that you'll need to use this API.