Classes | Macros | Typedefs
qbmove_communications.h File Reference

Library of functions for SERIAL PORT communication with a qbMove. More...

#include <termios.h>
#include "commands.h"
#include <stdint.h>
Include dependency graph for qbmove_communications.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  comm_settings
 

Macros

#define BAUD_RATE_T_2000000   0
 
#define BAUD_RATE_T_460800   1
 
#define INVALID_HANDLE_VALUE   -1
 
#define MAX_WATCHDOG_TIME   500
 
#define READ_TIMEOUT   4000
 

Typedefs

typedef struct comm_settings comm_settings
 

Functions

Virtual COM (RS485) functions
int RS485listPorts (char list_of_ports[10][255])
 This function is used to return a list of available serial ports. More...
 
void openRS485 (comm_settings *comm_settings_t, const char *port_s, int BAUD_RATE=B2000000)
 This function is used to open a serial port for using with the qbMove or the qbHand. More...
 
void closeRS485 (comm_settings *comm_settings_t)
 This function is used to close a serial port being used with the qbMove or an qbHand. More...
 
int RS485read (comm_settings *comm_settings_t, int id, char *package)
 This function is used to read a package from the device. More...
 
int RS485ListDevices (comm_settings *comm_settings_t, char list_of_ids[255])
 This function is used to list the number of devices connected to the serial port and get their relative IDs. More...
 
void RS485GetInfo (comm_settings *comm_settings_t, char *buffer)
 This function is used to ping the serial port for a qbMove or a qbHand and to get information about the device. More...
 
qbAPI Commands
int commPing (comm_settings *comm_settings_t, int id)
 This function is used to ping the qbMove or the qbHand. More...
 
void commActivate (comm_settings *comm_settings_t, int id, char activate)
 This function activates or deactivates a qbMove or a qbHand connected to the serial port. More...
 
void commSetBaudRate (comm_settings *comm_settings_t, int id, short int baudrate)
 This function sets the baudrate of communication. More...
 
void commSetWatchDog (comm_settings *comm_settings_t, int id, short int wdt)
 This function sets watchdog timer of a qbMove or a qbHand. More...
 
void commSetInputs (comm_settings *comm_settings_t, int id, short int inputs[])
 This function send reference inputs to a qbMove or a qbHand connected to the serial port. More...
 
int commSetInputsAck (comm_settings *comm_settings_t, int id, short int inputs[])
 This function send reference inputs to a qbMove or a qbHand connected to the serial port and expects an acknowledgment reply from the device. More...
 
void commSetPosStiff (comm_settings *comm_settings_t, int id, short int inputs[])
 This function send reference inputs to a qbMove connected to the serial port. More...
 
int commGetInputs (comm_settings *comm_settings_t, int id, short int inputs[2])
 This function gets input references from a qbMove or a qbHand connected to the serial port. More...
 
int commGetMeasurements (comm_settings *comm_settings_t, int id, short int measurements[3])
 This function gets position measurements from a qbMove or a qbHand connected to the serial port. More...
 
int commGetCounters (comm_settings *comm_settings_t, int id, short unsigned int counters[20])
 This function gets counters values from a qbMove connected to the serial port. More...
 
int commGetCurrents (comm_settings *comm_settings_t, int id, short int currents[2])
 This function gets currents from a qbMove or a qbHand connected to the serial port. More...
 
int commGetCurrAndMeas (comm_settings *comm_settings_t, int id, short int *values)
 This function gets currents and position measurements from a qbMove or a qbHand connected to the serial port. More...
 
int commGetEmg (comm_settings *comm_settings_t, int id, short int emg[2])
 This function gets measurements from electomyographics sensors connected to the qbHand. More...
 
int commGetVelocities (comm_settings *comm_settings_t, int id, short int measurements[])
 This function gets velocities of the two motors and the shaft from a qbMove connected to a serial port or from the only shaft of the qbHand. More...
 
int commGetAccelerations (comm_settings *comm_settings_t, int id, short int measurements[])
 This function gets the acceleration of the qbHand motor. More...
 
int commGetActivate (comm_settings *comm_settings_t, int id, char *activate)
 This function gets the activation status of a qbMove or a qbHand connected to the serial port. More...
 
int commGetInfo (comm_settings *comm_settings_t, int id, short int info_type, char *info)
 This function is used to ping the qbMove or the qbHand and get information about the device. More...
 
int commBootloader (comm_settings *comm_settings_t, int id)
 This function sends the board in bootloader modality in order to update the firmware on the board. More...
 
int commCalibrate (comm_settings *comm_settings_t, int id)
 This function is used to calibrate the maximum stiffness value of the qbMove. More...
 
int commHandCalibrate (comm_settings *comm_settings_t, int id, short int speed, short int repetitions)
 This function is used to make a series of opening and closures of the qbHand. More...
 
qbAPI Parameters
int commSetZeros (comm_settings *comm_settings_t, int id, void *values, unsigned short num_of_values)
 This function sets the encoders's zero positon value that remains stored in the qbMove or qbHand memory. More...
 
int commGetParamList (comm_settings *comm_settings_t, int id, unsigned short index, void *values, unsigned short value_size, unsigned short num_of_values, uint8_t *buffer)
 This function gets all the parameters that are stored in the qbMove or qbHand memory and sets one of them if requested. More...
 
int commStoreParams (comm_settings *comm_settings_t, int id)
 This function stores all parameters that were set in the qbMove or the qbHand memory. More...
 
int commStoreDefaultParams (comm_settings *comm_settings_t, int id)
 This function stores the factory default parameters. More...
 
int commRestoreParams (comm_settings *comm_settings_t, int id)
 This function restores the factory default parameters. More...
 
int commInitMem (comm_settings *comm_settings_t, int id)
 This function initialize the EEPROM memory of the board by loading the default factory parameters. More...
 
General Functions
long timevaldiff (struct timeval *starttime, struct timeval *finishtime)
 This functions returns a difference between two timeval structures in order to obtain time elapsed between the two timeval;. More...
 
char checksum (char *data_buffer, int data_length)
 This functions returns an 8 bit LCR checksum over the lenght of a buffer. More...
 
Functions for other devices
int commExtDrive (comm_settings *comm_settings_t, int id, char ext_input)
 This function is used with the armslider device. More...
 
void commSetCuffInputs (comm_settings *comm_settings_t, int id, int flag)
 This function send reference inputs to a qbMove board connected to the serial port. More...
 
int commGetJoystick (comm_settings *comm_settings_t, int id, short int joystick[2])
 This function gets joystick measurementes from a softhand connected to the serial port. More...
 

Detailed Description

Library of functions for SERIAL PORT communication with a qbMove.

Function Prototypes.

This library contains all necessary functions for communicating with a qbMove when using a USB to RS485 connector that provides a Virtual COM interface.

Definition in file qbmove_communications.h.

Macro Definition Documentation

#define BAUD_RATE_T_2000000   0

Definition at line 79 of file qbmove_communications.h.

#define BAUD_RATE_T_460800   1

Definition at line 80 of file qbmove_communications.h.

#define INVALID_HANDLE_VALUE   -1

Definition at line 72 of file qbmove_communications.h.

#define MAX_WATCHDOG_TIME   500

Definition at line 81 of file qbmove_communications.h.

#define READ_TIMEOUT   4000

Definition at line 82 of file qbmove_communications.h.

Typedef Documentation

typedef struct comm_settings comm_settings

Definition at line 92 of file qbmove_communications.h.

Function Documentation

char checksum ( char *  data_buffer,
int  data_length 
)

This functions returns an 8 bit LCR checksum over the lenght of a buffer.

Parameters
data_bufferBuffer.
data_lengthBuffer length.
Example
1 char aux;
2 char buffer[5];
3 
4 buffer = "abcde";
5 aux = checksum(buffer,5);
6 printf("Checksum: %d", (int) aux)
void closeRS485 ( comm_settings comm_settings_t)

This function is used to close a serial port being used with the qbMove or an qbHand.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
Example
1 comm_settings comm_settings_t;
2 
3 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
4 closeRS485(&comm_settings_t);
void commActivate ( comm_settings comm_settings_t,
int  id,
char  activate 
)

This function activates or deactivates a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
activateTRUE to turn motors on. FALSE to turn motors off.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 commActivate(&comm_settings_t, device_id, TRUE);
6 closeRS485(&comm_settings_t);
int commBootloader ( comm_settings comm_settings_t,
int  id 
)

This function sends the board in bootloader modality in order to update the firmware on the board.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
Returns
Return 0 on success, -1 otherwise
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 commBootloader(&comm_settings_t, device_id);
6 closeRS485(&comm_settings_t);
int commCalibrate ( comm_settings comm_settings_t,
int  id 
)

This function is used to calibrate the maximum stiffness value of the qbMove.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
Returns
Returns 0 on success, -1 otherwise
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 commCalibrate(&comm_settings_t, device_id);
6 closeRS485(&comm_settings_t);
int commExtDrive ( comm_settings comm_settings_t,
int  id,
char  ext_input 
)

This function is used with the armslider device.

Is used to drive another board with the inputs of the first one

Parameters
comm_settings_tA comm_settings structure containing info about the comunication settings.
idThe id of the board drive.
ext_inputA flag used to activate the external drive functionality of the board.
Returns
A negative value if something went wrong, a zero if everything went fine.
int commGetAccelerations ( comm_settings comm_settings_t,
int  id,
short int  measurements[] 
)

This function gets the acceleration of the qbHand motor.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
measurementsVelocity measurements.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int acc_measurements[3];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetAccelerations(&comm_settings_t, device_id, acc_measurements))
8  printf("Measurements: %d\t%d\t%d\n", acc_measurements[0], acc_measurements[1], acc_measurements[2]);
9 else
10  puts("Couldn't retrieve accelerations.");
11 
12 closeRS485(&comm_settings_t);
int commGetActivate ( comm_settings comm_settings_t,
int  id,
char *  activate 
)

This function gets the activation status of a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
activationActivation status.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 char activation_status;
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetActivate(&comm_settings_t, DEVICE_ID, activation_status))
8  printf("Activation status: %d\n", &activation_status);
9 else
10  puts("Couldn't retrieve activation status.");
11 
12 closeRS485(&comm_settings_t);
int commGetCounters ( comm_settings comm_settings_t,
int  id,
short unsigned int  counters[20] 
)

This function gets counters values from a qbMove connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
countersCounters
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short unsigned int counters[20];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetCounters(&comm_settings_t, DEVICE_ID, counters))
8  printf("Counters: %d\t%d\t {...} %d\n", counters[0], counters[1], {...}, counters[20]);
9 else
10  puts("Couldn't retrieve counters.");
11 
12 closeRS485(&comm_settings_t);
int commGetCurrAndMeas ( comm_settings comm_settings_t,
int  id,
short int *  values 
)

This function gets currents and position measurements from a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
valuesCurrent and position measurements. Currents are in first two positions
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int values[5];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7  if(!commGetCurrAndMeas(&comm_settings_t, device_id, currents)){
8  printf("Currents: %d\t%d\t%d\n",values[0], values[1]);
9  printf("Measurements: %d\t%d\t%d\n", values[2], values[3], values[4]);
10  }
11  else
12  puts("Couldn't retrieve currents.");
13 
14 closeRS485(&comm_settings_t);
int commGetCurrents ( comm_settings comm_settings_t,
int  id,
short int  currents[2] 
)

This function gets currents from a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
currentsCurrents.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int currents[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetCurrents(&comm_settings_t, device_id, currents))
8  printf("Measurements: %d\t%d\t%d\n",currents[0], currents[1]);
9 else
10  puts("Couldn't retrieve currents.");
11 
12 closeRS485(&comm_settings_t);
int commGetEmg ( comm_settings comm_settings_t,
int  id,
short int  emg[2] 
)

This function gets measurements from electomyographics sensors connected to the qbHand.

IS USED ONLY WHEN THE BOARD IS USED FOR A QBHAND

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
valuesEmg sensors measurements.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int values[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetEmg(&comm_settings_t, device_id, values));
8  printf("Measurements: %d\t%d\t%d\n", values[0], values[1]);
9 else
10  puts("Couldn't retrieve emg values.");
11 
12 closeRS485(&comm_settings_t);
int commGetInfo ( comm_settings comm_settings_t,
int  id,
short int  info_type,
char *  info 
)

This function is used to ping the qbMove or the qbHand and get information about the device.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
bufferBuffer that stores a string with information about the device. BUFFER SIZE MUST BE AT LEAST 500.
info_typeInformation to be retrieved.
Example
1 comm_settings comm_settings_t;
2 char auxstring[500];
3 int device_id = 65;
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 commGetInfo(&comm_settings_t, device_id, INFO_ALL, auxstring);
7 puts(auxstring);
8 closeRS485(&comm_settings_t);
int commGetInputs ( comm_settings comm_settings_t,
int  id,
short int  inputs[2] 
)

This function gets input references from a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
inputsInput references.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int inputs[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetInputs(&comm_settings_t, DEVICE_ID, inputs))
8  printf("Inputs: %d\t%d\n",inputs[0], inputs[1]);
9 else
10  puts("Couldn't retrieve device inputs.");
11 
12 closeRS485(&comm_settings_t);
int commGetJoystick ( comm_settings comm_settings_t,
int  id,
short int  joystick[2] 
)

This function gets joystick measurementes from a softhand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
joystickJoystick analog measurements.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int joystick[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetJoystick(&comm_settings_t, device_id, joystick))
8  printf("Measurements: %d\t%d\t%d\n",joystick[0], joystick[1]);
9 else
10  puts("Couldn't retrieve joystick measurements.");
11 
12 closeRS485(&comm_settings_t);
int commGetMeasurements ( comm_settings comm_settings_t,
int  id,
short int  measurements[3] 
)

This function gets position measurements from a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
measurementsMeasurements.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int measurements[3];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetMeasurements(&comm_settings_t, DEVICE_ID, measurements))
8  printf("Measurements: %d\t%d\t%d\n",measurements[0], measurements[1], measurements[2]);
9 else
10  puts("Couldn't retrieve measurements.");
11 
12 closeRS485(&comm_settings_t);
int commGetParamList ( comm_settings comm_settings_t,
int  id,
unsigned short  index,
void *  values,
unsigned short  value_size,
unsigned short  num_of_values,
uint8_t *  buffer 
)

This function gets all the parameters that are stored in the qbMove or qbHand memory and sets one of them if requested.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
indexThe index relative to the parameter to be get.
valuesAn array with the parameter values.
value_sizeThe byte size of the parameter to be get
num_of_valuesThe size of the array of the parameter to be get
bufferThe array where the parameters' values and descriptions are saved
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 unsigned char aux_string[2000];
4 int index = 0;
5 int value_size = 0;
6 int num_of_values = 0;
7 
8 // Get parameters
9 commGetParamList(&comm_settings_t, device_id, index, NULL, value_size, num_of_values, aux_string);
10 string_unpacking_and_printing(aux_string);
11 
12 // Set parameters
13 
14 float pid[3];
15 pid[0] = 0.1;
16 pid[1] = 0.2;
17 pid[2] = 0.3;
18 index = 2;
19 value_size = 4;
20 num_of_values = 3;
21 commGetParamList(&comm_settings_t, device_id, index, pid, value_size, num_of_values, NULL);
int commGetVelocities ( comm_settings comm_settings_t,
int  id,
short int  measurements[] 
)

This function gets velocities of the two motors and the shaft from a qbMove connected to a serial port or from the only shaft of the qbHand.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
measurementsVelocity measurements.
Returns
Returns 0 if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int vel_measurements[3];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 if(!commGetVelocities(&comm_settings_t, device_id, vel_measurements))
8  printf("Measurements: %d\t%d\t%d\n", vel_measurements[0], vel_measurements[1], vel_measurements[2]);
9 else
10  puts("Couldn't retrieve velocities.");
11 
12 closeRS485(&comm_settings_t);
int commHandCalibrate ( comm_settings comm_settings_t,
int  id,
short int  speed,
short int  repetitions 
)

This function is used to make a series of opening and closures of the qbHand.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
speedThe speed of hand closure and opening [0 - 200]
repetitionsThe nnumber of closures needed to be done [0 - 32767]
Example
1 comm_settings comm_settings_t;
2 int speed = 200
3 int repetitions = 400;
4 int device_id = 65;
5 
6 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
7 commHandCalibrate(&comm_settings_t, device_id, speed, repetitions);
8 closeRS485(&comm_settings_t);
int commInitMem ( comm_settings comm_settings_t,
int  id 
)

This function initialize the EEPROM memory of the board by loading the default factory parameters.

After the initialization a flag is set.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 
6 commInitMem(&comm_settings_t, device_id)
7 
8 closeRS485(&comm_settings_t);
int commPing ( comm_settings comm_settings_t,
int  id 
)

This function is used to ping the qbMove or the qbHand.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
bufferBuffer that stores a string with information about the device. BUFFER SIZE MUST BE AT LEAST 500.
Returns
Returns 0 if ping was ok, -1 otherwise.
Example
1  comm_settings comm_settings_t;
2  int device_id = 65;
3 
4  openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5  if ( commPing(&comm_settings_t, device_id) )
6  puts("Device exists.");
7  else
8  puts("Device does not exist.");
9 
10 closeRS485(&comm_settings_t);
int commRestoreParams ( comm_settings comm_settings_t,
int  id 
)

This function restores the factory default parameters.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 
6 commRestoreParams(&comm_settings_t, device_id)
7 
8 closeRS485(&comm_settings_t);
void commSetBaudRate ( comm_settings comm_settings_t,
int  id,
short int  baudrate 
)

This function sets the baudrate of communication.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
baudrateBaudRate requested 0 = 2M baudrate, 1 = 460.8k baudrate
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int baudrate = 0;
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 commSetBaudRate(&comm_settings_t, global_args.device_id, baudrate);
7 closeRS485(&comm_settings_t);
void commSetCuffInputs ( comm_settings comm_settings_t,
int  id,
int  flag 
)

This function send reference inputs to a qbMove board connected to the serial port.

Is used only when the device is a Cuff.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
flagA flag that indicates used to activate the cuff driving functionality of the board.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int cuff_inputs[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 int flag = 1;
8 commSetCuffInputs(&comm_settings_t, device_id, flag);
9 closeRS485(&comm_settings_t);
void commSetInputs ( comm_settings comm_settings_t,
int  id,
short int  inputs[] 
)

This function send reference inputs to a qbMove or a qbHand connected to the serial port.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
inputsInput references.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int inputs[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 inputs[0] = 1000;
8 inputs[1] = -1000;
9 commSetInputs(&comm_settings_t, device_id, inputs);
10 closeRS485(&comm_settings_t);
int commSetInputsAck ( comm_settings comm_settings_t,
int  id,
short int  inputs[] 
)

This function send reference inputs to a qbMove or a qbHand connected to the serial port and expects an acknowledgment reply from the device.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
inputsInput references.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int inputs[2];
4 char package_in[2];
5 
6 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
7 
8 inputs[0] = 1000;
9 inputs[1] = -1000;
10 commSetInputsAck(&comm_settings_t, device_id, inputs);
11 RS485Read(&comm_settings_t, device_id, package_in);
12 closeRS485(&comm_settings_t);
void commSetPosStiff ( comm_settings comm_settings_t,
int  id,
short int  inputs[] 
)

This function send reference inputs to a qbMove connected to the serial port.

The reference is in shaft position and stiffness preset. IS VALID ONLY WHEN USED FOR THE qbMove, NOT FOR THE qbHand

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
inputsInput references.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int inputs[2];
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
6 
7 inputs[0] = 100; //Degrees
8 inputs[1] = 30; //stiffness preset
9 commSetPosStiff(&comm_settings_t, device_id, inputs);
10 closeRS485(&comm_settings_t);
void commSetWatchDog ( comm_settings comm_settings_t,
int  id,
short int  wdt 
)

This function sets watchdog timer of a qbMove or a qbHand.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
wdtWatchdog timer in [csec], max value: 500 [cs] / min value: 0 (disable) [cs]
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int wdt = 60;
4 
5 openRS485(&comm_settings_t,"/dev/tty.usbserial-128);
6 commSetWatchDog(&comm_settings_t, global_args.device_id, wdt);
7 closeRS485(&comm_settings_t);
int commSetZeros ( comm_settings comm_settings_t,
int  id,
void *  values,
unsigned short  num_of_values 
)

This function sets the encoders's zero positon value that remains stored in the qbMove or qbHand memory.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
valueAn array with the encoder readings values.
num_of_valuesThe size of the values array, equal to the sensor number.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 short int measurements[3];
4 
5 
6 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
7 commGetMeasurements(comm_settings_t, device_id, measurements)
8 for(i = 0; i<3; i++)
9  measurements[i] = -measurements[i];
10 commSetZeros(&comm_settings_t, global_args.device_id, measurements, 3);
11 closeRS485(&comm_settings_t);
int commStoreDefaultParams ( comm_settings comm_settings_t,
int  id 
)

This function stores the factory default parameters.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 commStoreDefaultParams(&comm_settings_t, device_id)
6 closeRS485(&comm_settings_t);
int commStoreParams ( comm_settings comm_settings_t,
int  id 
)

This function stores all parameters that were set in the qbMove or the qbHand memory.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 
6 commStoreParams(&comm_settings_t, device_id)
7 
8 closeRS485(&comm_settings_t);
void openRS485 ( comm_settings comm_settings_t,
const char *  port_s,
int  BAUD_RATE = B2000000 
)

This function is used to open a serial port for using with the qbMove or the qbHand.

Parameters
comm_settingsA comm_settings structure containing info about the communication settings.
port_sThe string to the serial port path.
BAUD_RATEThe default baud rate value of the serial port
Returns
Returns the file descriptor associated to the serial port.
Example
1 comm_settings comm_settings_t;
2 
3 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
4 if(comm_settings_t.file_handle == INVALID_HANDLE_VALUE)
5 {
6 // ERROR
7 }
void RS485GetInfo ( comm_settings comm_settings_t,
char *  buffer 
)

This function is used to ping the serial port for a qbMove or a qbHand and to get information about the device.

ONLY USE WHEN ONE DEVICE IS CONNECTED ONLY.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
bufferBuffer that stores a string with information about the device. BUFFER SIZE MUST BE AT LEAST 500.
Example
1 comm_settings comm_settings_t;
2 char auxstring[500];
3 
4 openRS485(&comm_settings_t,"/dev/tty.usbserial-128");
5 RS485GetInfo(&comm_settings_t, auxstring);
6 puts(auxstring);
7 closeRS485(&comm_settings_t);
int RS485ListDevices ( comm_settings comm_settings_t,
char  list_of_ids[255] 
)

This function is used to list the number of devices connected to the serial port and get their relative IDs.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
list_of_ids[255]Buffer that stores a list of IDs to ping, in order to see which of those IDs is connected. Is then filled with the IDs connected to the serial port.
Returns
Returns the number of devices connected
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 int device_num;
4 char list_of_ids[255];
5 
6 openRS485(&comm_settings_t, device_id);
7 device_num = RS485ListDevices(&comm_settings_t, &list_of_ids);
8 closeRS485(&comm_settings_t);
9 printf("Number of devices connected: %d", i);
int RS485listPorts ( char  list_of_ports[10][255])

This function is used to return a list of available serial ports.

A maximum of 10 ports are found.

Parameters
list_of_portsAn array of strings with the serial ports paths.
Returns
Returns the number of serial ports found.
Example
1 int i, num_ports;
2 char list_of_ports[10][255];
3 
4 num_ports = RS485listPorts(ports);
5 
6 for(i = 0; i < num_ports; ++i)
7 {
8  puts(ports[i]);
9 }
int RS485read ( comm_settings comm_settings_t,
int  id,
char *  package 
)

This function is used to read a package from the device.

Parameters
comm_settings_tA comm_settings structure containing info about the communication settings.
idThe device's id number.
packagePackage will be stored here.
Returns
Returns package length if communication was ok, -1 otherwise.
Example
1 comm_settings comm_settings_t;
2 int device_id = 65;
3 char data_read[1000];
4 
5 openRS485(&comm_settings_t, "/dev/tty.usbserial-128");
6 commPing(&comm_settings_t, device_id);
7 RS485read(&comm_settings_t, device_id, data_read);
8 closeRS485(&comm_settings_t);
9 
10 printf(data_read);
long timevaldiff ( struct timeval *  starttime,
struct timeval *  finishtime 
)

This functions returns a difference between two timeval structures in order to obtain time elapsed between the two timeval;.

Parameters
starttimeThe timeval structure containing the start time
finishtimeThe timeval structure containing the finish time
Returns
Returns the elapsed time between the two timeval structures.
Example
1 struct timeval start, finish;
2 gettimeofday(&start, NULL);
3 // other instructions
4 gettimeofday(&now, NULL);
5 long diff = timevaldiff(&start, &now);
6 
7 printf(Time elapsed: %ld, diff);


qb_device_driver
Author(s): qbroboticsĀ®
autogenerated on Thu Jun 6 2019 19:46:36