Go to the source code of this file.
Defines | |
#define | COMMAND_LAYER_VERSION 10001 |
#define | ERROR_INIT_API 2001 |
#define | ERROR_LOAD_COMM_DLL 2002 |
#define | JACO_COMM_FAILED 2004 |
#define | JACO_NACK_FIRST 2003 |
#define | JACO_NACK_NORMAL 2005 |
#define | KINOVAAPIUSBCOMMANDLAYER_API __declspec(dllimport) |
#define | WIN32_LEAN_AND_MEAN |
Functions | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | CloseAPI (void) |
Stop the API, must be called at the end of an API session. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | EraseAllTrajectories () |
Erase all trajectories in the FIFO (The arm stops immediatly) | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetActualTrajectoryInfo (TrajectoryPoint &Response) |
Get info about actual ongoing trajectory. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetAngularCurrent (AngularPosition &Response) |
Get actuator current consumption (A). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetAngularForce (AngularPosition &Response) |
Get actuators applied force (Nm). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetAngularPosition (AngularPosition &Response) |
Get absolute angular position (degrees). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetCartesianForce (CartesianPosition &Response) |
Get cartesian force (N). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetCartesianPosition (CartesianPosition &Response) |
Get absolute cartesian position (m, rad). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetClientConfigurations (ClientConfigurations &config) |
Get a ClientConfigurations from the arm. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetCodeVersion (std::vector< int > &Response) |
Get the code version. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetGlobalTrajectoryInfo (TrajectoryFIFO &Response) |
Get information about trajectories FIFO. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetJacoCount (DWORD &) |
Get the number of connected arms. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetPositionCurrentActuators (std::vector< float > &Response) |
Get current position of actuators (degrees) | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetSensorsInfo (SensorsInfo &Response) |
Get sensors values (voltage(V), current(A), [X,Y,Z] accelerations(m/s^2 , Actuators temperature(deg. C) and finger temperature(deg. C) ). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | GetSingularityVector (SingularityVector &Response) |
Get information about singularities from the actual hand position. Singularities concern the hand translation and it's rotation (changement or orientation) | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | InitAPI (void) |
Init the API, must be called before any API session. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | RestoreFactoryDefault () |
Restore the arm ClientConfigurations to its factory default settings (Clear all current settings). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SendAdvanceTrajectory (TrajectoryPoint trajectory) |
Send all trajectory infos to the arm. The trajectory is push into the FIFO. If it's a velocity trajectory, refresh the command each 10ms to keep movement. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SendBasicTrajectory (TrajectoryPoint trajectory) |
Send only essential TrajectoryPoint info (Positions for moving) to the arm (faster than SendAdvanceTrajectory) The trajectory is push into the FIFO. If it's a velocity trajectory, refresh the command each 10ms to keep movement. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SendJoystickCommand (JoystickCommand joystickCommand) |
Send a virtual joystick command (This has the same behavior than the hard-wired joystick). The control has to be refresh in a control loop around each 10ms. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SetActuatorPID (unsigned int address, float P, float I, float D) |
Set an actuator PID. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SetAngularControl () |
Set the joystick (virtual or real one) control to angular mode (moves actuators one by one). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SetCartesianControl () |
Set the joystick (virtual or real one) control to cartesian (X,Y,Z). | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | SetClientConfigurations (ClientConfigurations config) |
Set arm client configuration. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | StartControlAPI () |
Allow the API to control the arm. This function must be called before any control over the arm using API (Ex.: SendBasicTrajectory() ) If the joystick is used while API control, it's desactivated and need to call the function again to recover control. This method has only effect on the arm movements, other kind of methods work without calling a StartControlAPI() before. | |
KINOVAAPIUSBCOMMANDLAYER_API DWORD | StopControlAPI () |
Disable API control over the arm. Control functions has no more effects on the arm (Ex.: SendBasicTrajectory() ). |
#define COMMAND_LAYER_VERSION 10001 |
Definition at line 19 of file Kinova.API.UsbCommandLayer.h.
#define ERROR_INIT_API 2001 |
Definition at line 13 of file Kinova.API.UsbCommandLayer.h.
#define ERROR_LOAD_COMM_DLL 2002 |
Definition at line 14 of file Kinova.API.UsbCommandLayer.h.
#define JACO_COMM_FAILED 2004 |
Definition at line 16 of file Kinova.API.UsbCommandLayer.h.
#define JACO_NACK_FIRST 2003 |
Definition at line 15 of file Kinova.API.UsbCommandLayer.h.
#define JACO_NACK_NORMAL 2005 |
Definition at line 17 of file Kinova.API.UsbCommandLayer.h.
#define KINOVAAPIUSBCOMMANDLAYER_API __declspec(dllimport) |
Definition at line 4 of file Kinova.API.UsbCommandLayer.h.
#define WIN32_LEAN_AND_MEAN |
Definition at line 11 of file Kinova.API.UsbCommandLayer.h.
KINOVAAPIUSBCOMMANDLAYER_API DWORD CloseAPI | ( | void | ) |
Stop the API, must be called at the end of an API session.
Erase all trajectories in the FIFO (The arm stops immediatly)
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetActualTrajectoryInfo | ( | TrajectoryPoint & | Response | ) |
Get info about actual ongoing trajectory.
Response | A TrajectoryPoint struture to be filled |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetAngularCurrent | ( | AngularPosition & | Response | ) |
Get actuator current consumption (A).
Response | A AngularPosition structure to be filled with electrical currents in Ampers |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetAngularForce | ( | AngularPosition & | Response | ) |
Get actuators applied force (Nm).
Response | A AngularPosition structure to be filled with applied force in Newton-meters |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetAngularPosition | ( | AngularPosition & | Response | ) |
Get absolute angular position (degrees).
Response | A AngularPosition struture to be filled with absolute angular positions in degrees |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetCartesianForce | ( | CartesianPosition & | Response | ) |
Get cartesian force (N).
Response | A CartesianPosition struture to be filled with cartesian forces in Newton |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetCartesianPosition | ( | CartesianPosition & | Response | ) |
Get absolute cartesian position (m, rad).
Response | A CartesianPosition struture to be filled with absolute position in meters and rad |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetClientConfigurations | ( | ClientConfigurations & | config | ) |
Get a ClientConfigurations from the arm.
config | A ClientConfigurations structure to be filled |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetCodeVersion | ( | std::vector< int > & | Response | ) |
Get the code version.
Response | A vector to be filled with all version numbers |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetGlobalTrajectoryInfo | ( | TrajectoryFIFO & | Response | ) |
Get information about trajectories FIFO.
Response | A TrajectoryFIFO structure to be filled containing information about the FIFO |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetJacoCount | ( | DWORD & | ) |
Get the number of connected arms.
A DWORD | The number connected arms |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetPositionCurrentActuators | ( | std::vector< float > & | Response | ) |
Get current position of actuators (degrees)
Response | A vector to be filled containing position of all activated actuators in degrees |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetSensorsInfo | ( | SensorsInfo & | Response | ) |
Get sensors values (voltage(V), current(A), [X,Y,Z] accelerations(m/s^2 , Actuators temperature(deg. C) and finger temperature(deg. C) ).
Response | A SensorsInfo structure to be filled |
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetSingularityVector | ( | SingularityVector & | Response | ) |
Get information about singularities from the actual hand position.
Singularities concern the hand translation and it's rotation (changement or orientation)
Response | A SingularityVector structure to be filled |
KINOVAAPIUSBCOMMANDLAYER_API DWORD InitAPI | ( | void | ) |
Init the API, must be called before any API session.
Restore the arm ClientConfigurations to its factory default settings (Clear all current settings).
KINOVAAPIUSBCOMMANDLAYER_API DWORD SendAdvanceTrajectory | ( | TrajectoryPoint | trajectory | ) |
Send all trajectory infos to the arm. The trajectory is push into the FIFO. If it's a velocity trajectory, refresh the command each 10ms to keep movement.
trajectory | A TrajectoryPoint structure to send |
KINOVAAPIUSBCOMMANDLAYER_API DWORD SendBasicTrajectory | ( | TrajectoryPoint | trajectory | ) |
Send only essential TrajectoryPoint info (Positions for moving) to the arm (faster than SendAdvanceTrajectory) The trajectory is push into the FIFO. If it's a velocity trajectory, refresh the command each 10ms to keep movement.
trajectory | A TrajectoryPoint structure to send |
KINOVAAPIUSBCOMMANDLAYER_API DWORD SendJoystickCommand | ( | JoystickCommand | joystickCommand | ) |
Send a virtual joystick command (This has the same behavior than the hard-wired joystick). The control has to be refresh in a control loop around each 10ms.
JoystickCommand | A JoystickCommand filled structure with desired joystick controller values |
KINOVAAPIUSBCOMMANDLAYER_API DWORD SetActuatorPID | ( | unsigned int | address, |
float | P, | ||
float | I, | ||
float | D | ||
) |
Set an actuator PID.
address | Actuator address, from 16 (first actuator) to 21 |
P | Kp have to be between 0 and 3(high vibrations), tune with increments of 0.1 |
I | Ki have to be around 0.01, tune with increments of 0.01 |
D | Kd set it to 0 , useless for now |
Set the joystick (virtual or real one) control to angular mode (moves actuators one by one).
Set the joystick (virtual or real one) control to cartesian (X,Y,Z).
KINOVAAPIUSBCOMMANDLAYER_API DWORD SetClientConfigurations | ( | ClientConfigurations | config | ) |
Set arm client configuration.
config | A defined ClientConfigurations structure to send and set |
KINOVAAPIUSBCOMMANDLAYER_API DWORD StartControlAPI | ( | ) |
Allow the API to control the arm. This function must be called before any control over the arm using API (Ex.: SendBasicTrajectory() ) If the joystick is used while API control, it's desactivated and need to call the function again to recover control. This method has only effect on the arm movements, other kind of methods work without calling a StartControlAPI() before.
KINOVAAPIUSBCOMMANDLAYER_API DWORD StopControlAPI | ( | ) |
Disable API control over the arm. Control functions has no more effects on the arm (Ex.: SendBasicTrajectory() ).