Kinova API Documentation
Kinova.API.UsbCommandLayerUbuntu.h File Reference

This file contains header of all available functions of this API. More...

Functions

KINOVAAPIUSBCOMMANDLAYER_API int InitAPI (void)
 This function initialises the API. It is the first function you call if you want the rest of the library.
KINOVAAPIUSBCOMMANDLAYER_API int CloseAPI (void)
 This function must called when your application stop using the API. It closes the USB link and the library properly.
KINOVAAPIUSBCOMMANDLAYER_API int GetCodeVersion (std::vector< int > &Response)
 This function returns the code version of the robotical arm's firmware. The elements of the vector or ordered as:
KINOVAAPIUSBCOMMANDLAYER_API int GetAPIVersion (std::vector< int > &Response)
 This function returns the API's version(major.minor.version). Basically, it returns COMMAND_LAYER_VERSION. The vector contains 3 values. The first one is the version, the second one is the major and the last one is the minor.
KINOVAAPIUSBCOMMANDLAYER_API int GetCartesianPosition (CartesianPosition &Response)
 This function returns the cartesian position of the robotical arm's end effector. The orientation is defined by Euler angles(Convention XYZ).
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularPosition (AngularPosition &Response)
 This function returns the angular position of the robotical arm's end effector. Unit is degree.
KINOVAAPIUSBCOMMANDLAYER_API int GetCartesianForce (CartesianPosition &Response)
 This function returns the cartesian force at the robotical arm's end effector. Translation unit is N and orientation unit is N * m .
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularForce (AngularPosition &Response)
 This function returns the torque of each actuator. Unit is Newton * meter.
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularCurrent (AngularPosition &Response)
 This function returns the current that each actuator consume on the main supply. Unit are A.
KINOVAAPIUSBCOMMANDLAYER_API int GetActualTrajectoryInfo (TrajectoryPoint &Response)
 This function returns information about the actual trajectory point.
KINOVAAPIUSBCOMMANDLAYER_API int GetGlobalTrajectoryInfo (TrajectoryFIFO &Response)
 This function returns informations about the trajectories FIFO stored inside the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int GetSensorsInfo (SensorsInfo &Response)
 This function returns information about the robotical arm's sensors. (Voltage, Total current, Temperature, acceleration)
KINOVAAPIUSBCOMMANDLAYER_API int GetSingularityVector (SingularityVector &Response)
 ONLY AVAILABLE WITH FIRMWARE 4.2.9 AND BELOW. This function gets informations about the nearest singularities.
KINOVAAPIUSBCOMMANDLAYER_API int SetAngularControl ()
 This function sets the robotical arm in angular control mode.
KINOVAAPIUSBCOMMANDLAYER_API int SetCartesianControl ()
 This function sets the robotical arm in cartesian control mode if this is possible.
KINOVAAPIUSBCOMMANDLAYER_API int StartControlAPI ()
 This function tells the robotical arm that from now on, the API will control the robotical arm. It must been call before sending trajectories or joystick command.
KINOVAAPIUSBCOMMANDLAYER_API int StopControlAPI ()
 This function tells the robotical arm the from now on the API is not controlling the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int RestoreFactoryDefault ()
 This function restores the factory default settings of the robotical arm. WARNING: this will erase all your configuration, all your protection zones and all your mapping modification.
KINOVAAPIUSBCOMMANDLAYER_API int SendJoystickCommand (JoystickCommand joystickCommand)
 This function sends a virtual joystick command to the robotical arm. the behaviour of the robotical arm is determined by the the control mapping associated with the API. (index 2) In the example, we assume that the robotical arm use the default mapping of the API and that it is in mode B0(Joystick translation). Assuming that, the robotical arm should move along the Z axis.
KINOVAAPIUSBCOMMANDLAYER_API int SendAdvanceTrajectory (TrajectoryPoint trajectory)
 This function sends trajectory point(With limitation) that will be added in the robotical arm's FIFO.
KINOVAAPIUSBCOMMANDLAYER_API int SendBasicTrajectory (TrajectoryPoint trajectory)
 This function sends trajectory point(Without limitation) that will be added in the robotical arm's FIFO.
KINOVAAPIUSBCOMMANDLAYER_API int GetClientConfigurations (ClientConfigurations &config)
 This function gets the client confgurations of the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int SetClientConfigurations (ClientConfigurations config)
 This function set the client configurations of the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int EraseAllTrajectories ()
 This function erases all the trajectories inside the robotical arm's FIFO.
KINOVAAPIUSBCOMMANDLAYER_API int GetPositionCurrentActuators (std::vector< float > &Response)
 This function get the position and the current of all actuators.
KINOVAAPIUSBCOMMANDLAYER_API int SetActuatorPID (unsigned int address, float P, float I, float D)
 This function set the PID of a specific actuator.
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularCommand (AngularPosition &Response)
 This function get the angular command of all actuators.
KINOVAAPIUSBCOMMANDLAYER_API int GetCartesianCommand (CartesianPosition &Response)
 This function get the cartesian command of the end effector. The orientation is defined by Euler angles(Convention XYZ).
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularCurrentMotor (AngularPosition &Response)
 This function get motor's current of each actuator.
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularVelocity (AngularPosition &Response)
 This function get the velocity of each actuator.
KINOVAAPIUSBCOMMANDLAYER_API int GetControlType (int &Response)
 This function get the actual control type.
KINOVAAPIUSBCOMMANDLAYER_API int StartForceControl ()
 This function activates the force control.
KINOVAAPIUSBCOMMANDLAYER_API int StopForceControl ()
 This function stops the force control.
KINOVAAPIUSBCOMMANDLAYER_API int StartCurrentLimitation ()
 This function activates the current limitation.
KINOVAAPIUSBCOMMANDLAYER_API int StopCurrentLimitation ()
 This function stops the current limitation.
KINOVAAPIUSBCOMMANDLAYER_API int GetSystemErrorCount (unsigned int &Response)
 This function gets the error count of the robotical arm's error's log.
KINOVAAPIUSBCOMMANDLAYER_API int GetSystemError (unsigned int indexError, SystemError &Response)
 This function gets a specific error from the robotical arm's error log.
KINOVAAPIUSBCOMMANDLAYER_API int ClearErrorLog ()
 This function clears the robotical arm's error log.
KINOVAAPIUSBCOMMANDLAYER_API int EraseAllProtectionZones ()
 This function erases all protection zones.
KINOVAAPIUSBCOMMANDLAYER_API int SetSerialNumber (char Command[STRING_LENGTH])
 This function sets a new serial number to the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int GetControlMapping (ControlMappingCharts &Response)
 This function gets the control mapping charts.
KINOVAAPIUSBCOMMANDLAYER_API int GetProtectionZone (ZoneList &Response)
 This function gets the list of all protection zones.
KINOVAAPIUSBCOMMANDLAYER_API int SetProtectionZone (ZoneList Command)
 This function sets a new list of protection zones.
KINOVAAPIUSBCOMMANDLAYER_API int GetGripperStatus (Gripper &Response)
 BETA version - This function gets informations about the robotical arm's gripper. Some information may be missing, it is still in development.
KINOVAAPIUSBCOMMANDLAYER_API int GetQuickStatus (QuickStatus &Response)
 This function gets information regarding some status flag of the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int GetForcesInfo (ForcesInfo &Response)
 This function gets information regarding all forces.
KINOVAAPIUSBCOMMANDLAYER_API int SetControlMapping (ControlMappingCharts Command)
 This function sets a new control mapping charts to the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int ProgramFlash (char *filename)
 This function program a new version of the robotical arm's firmware.
KINOVAAPIUSBCOMMANDLAYER_API int SetJointZero (int ActuatorAdress)
 This function sets the current position of a specific actuator as a zero. Mainly used for calibration.
KINOVAAPIUSBCOMMANDLAYER_API int SetTorqueZero (int ActuatorAdress)
 This function sets the current position of a specific actuator as a torque zero. Mainly used for calibration.
KINOVAAPIUSBCOMMANDLAYER_API int SetTorqueGain (int ActuatorAdress, int Gain)
 This function sets the gain value of a torque sensor on a specific actuator. Mainly used for calibration.
KINOVAAPIUSBCOMMANDLAYER_API int SetActuatorPIDFilter (int ActuatorAdress, float filterP, float filterI, float filterD)
 This function sets a PID filter value on a specific actuator. Mainly used for calibration.
KINOVAAPIUSBCOMMANDLAYER_API int SetActuatorAddress (int ActuatorAdress, int newAddress)
 This function sets a new address to a specific actuator.
KINOVAAPIUSBCOMMANDLAYER_API int GetGeneralInformations (GeneralInformations &Response)
 This function gets general informations about the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int SetFrameType (int frameType)
 This function sets the frame type of the robotical arm.
KINOVAAPIUSBCOMMANDLAYER_API int SetCartesianForceMinMax (CartesianInfo min, CartesianInfo max)
 This function set the Cartesian force's maximum and minimum values.
KINOVAAPIUSBCOMMANDLAYER_API int SetCartesianInertiaDamping (CartesianInfo inertia, CartesianInfo damping)
 This function set the Cartesian inertia and damping value.
KINOVAAPIUSBCOMMANDLAYER_API int SetAngularTorqueMinMax (AngularInfo min, AngularInfo max)
 This function set the angular torque's maximum and minimum values.
KINOVAAPIUSBCOMMANDLAYER_API int SetAngularInertiaDamping (AngularInfo inertia, AngularInfo damping)
 This function set the angular inertia and damping value.
KINOVAAPIUSBCOMMANDLAYER_API int SetSpasmFilterValues (std::vector< float > Response, int activationStatus)
 This function set the active spasm filter values from the robotical arm. This function is only used by the rehab client. Normal application should not use it.
KINOVAAPIUSBCOMMANDLAYER_API int GetSpasmFilterValues (std::vector< float > &Response, int &activationStatus)
 This function get the active spasm filter values from the robotical arm. This function is only used by the rehab client. Normal application should not use it.
KINOVAAPIUSBCOMMANDLAYER_API int MoveHome ()
 This Moce the robot to the HOME position also known as READY position.
KINOVAAPIUSBCOMMANDLAYER_API int GetAngularForceGravityFree (AngularPosition &Response)
 This function returns the torque without gravity of each actuator. Unit is Newton * meter.
KINOVAAPIUSBCOMMANDLAYER_API int GetActuatorAcceleration (AngularAcceleration &Response)
 This function get the acceleration values of each actuator. Units are G.
KINOVAAPIUSBCOMMANDLAYER_API int InitFingers ()
 This function initializes the fingers of the robotical arm. After the initialization, the robotical arm is in angular control mode. If you want to use the cartesian control mode, use the function SetCartesianControl().

Detailed Description

This file contains header of all available functions of this API.

 All Classes Files Functions Variables Enumerations Enumerator Defines