Defines | Functions
Kinova.API.UsbCommandLayer.h File Reference
#include <vector>
#include "KinovaTypes.h"
#include <windows.h>
Include dependency graph for Kinova.API.UsbCommandLayer.h:

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 Documentation

#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.

Definition at line 11 of file Kinova.API.UsbCommandLayer.h.


Function Documentation

Stop the API, must be called at the end of an API session.

Returns:
Error code

Erase all trajectories in the FIFO (The arm stops immediatly)

Returns:
Error code

Get info about actual ongoing trajectory.

Parameters:
ResponseA TrajectoryPoint struture to be filled
Returns:
Error code

Get actuator current consumption (A).

Parameters:
ResponseA AngularPosition structure to be filled with electrical currents in Ampers
Returns:
Error code

Get actuators applied force (Nm).

Parameters:
ResponseA AngularPosition structure to be filled with applied force in Newton-meters
Returns:
Error code

Get absolute angular position (degrees).

Parameters:
ResponseA AngularPosition struture to be filled with absolute angular positions in degrees
Returns:
Error code

Get cartesian force (N).

Parameters:
ResponseA CartesianPosition struture to be filled with cartesian forces in Newton
Returns:
Error code

Get absolute cartesian position (m, rad).

Parameters:
ResponseA CartesianPosition struture to be filled with absolute position in meters and rad
Returns:
Error code

Get a ClientConfigurations from the arm.

Parameters:
configA ClientConfigurations structure to be filled
Returns:
Error code
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetCodeVersion ( std::vector< int > &  Response)

Get the code version.

Parameters:
ResponseA vector to be filled with all version numbers
Returns:
Error code

Get information about trajectories FIFO.

Parameters:
ResponseA TrajectoryFIFO structure to be filled containing information about the FIFO
Returns:
Error code

Get the number of connected arms.

Parameters:
A DWORDThe number connected arms
Returns:
Error code
KINOVAAPIUSBCOMMANDLAYER_API DWORD GetPositionCurrentActuators ( std::vector< float > &  Response)

Get current position of actuators (degrees)

Parameters:
ResponseA vector to be filled containing position of all activated actuators in degrees
Returns:
Error code

Get sensors values (voltage(V), current(A), [X,Y,Z] accelerations(m/s^2 , Actuators temperature(deg. C) and finger temperature(deg. C) ).

Parameters:
ResponseA SensorsInfo structure to be filled
Returns:
Error code


Get information about singularities from the actual hand position.
Singularities concern the hand translation and it's rotation (changement or orientation)

Parameters:
ResponseA SingularityVector structure to be filled
Returns:
Error code

Init the API, must be called before any API session.

Returns:
Error code

Restore the arm ClientConfigurations to its factory default settings (Clear all current settings).

Returns:
Error code

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.

Parameters:
trajectoryA TrajectoryPoint structure to send
Returns:
Error code

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.

Parameters:
trajectoryA TrajectoryPoint structure to send
Returns:
Error code

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.

Parameters:
JoystickCommandA JoystickCommand filled structure with desired joystick controller values
Returns:
Error code
KINOVAAPIUSBCOMMANDLAYER_API DWORD SetActuatorPID ( unsigned int  address,
float  P,
float  I,
float  D 
)

Set an actuator PID.

Parameters:
addressActuator address, from 16 (first actuator) to 21
PKp have to be between 0 and 3(high vibrations), tune with increments of 0.1
IKi have to be around 0.01, tune with increments of 0.01
DKd set it to 0 , useless for now
Returns:
Error code

Set the joystick (virtual or real one) control to angular mode (moves actuators one by one).

Returns:
Error code

Set the joystick (virtual or real one) control to cartesian (X,Y,Z).

Returns:
Error code

Set arm client configuration.

Parameters:
configA defined ClientConfigurations structure to send and set
Returns:
Error code

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.

Returns:
Error code

Disable API control over the arm. Control functions has no more effects on the arm (Ex.: SendBasicTrajectory() ).

Returns:
Error code


jaco_driver
Author(s): Jeff Schmidt (Clearpath), Alex Bencz (Clearpath), Matt DeDonato (WPI)
autogenerated on Mon Jan 6 2014 11:23:43