qbmove_communications.h
Go to the documentation of this file.
1 
2 // BSD 3-Clause License
3 
4 // Copyright (c) 2015-2018, qbrobotics®
5 // All rights reserved.
6 
7 // Redistribution and use in source and binary forms, with or without
8 // modification, are permitted provided that the following conditions are met:
9 
10 // * Redistributions of source code must retain the above copyright notice, this
11 // list of conditions and the following disclaimer.
12 
13 // * Redistributions in binary form must reproduce the above copyright notice,
14 // this list of conditions and the following disclaimer in the documentation
15 // and/or other materials provided with the distribution.
16 
17 // * Neither the name of the copyright holder nor the names of its
18 // contributors may be used to endorse or promote products derived from
19 // this software without specific prior written permission.
20 
21 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25 // FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26 // DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27 // SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29 // OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31 
66 #ifndef QBMOVE_SERIALPORT_H_INCLUDED
67 #define QBMOVE_SERIALPORT_H_INCLUDED
68 
69 #if (defined(_WIN32) || defined(_WIN64))
70  #include <windows.h>
71 #else
72  #define INVALID_HANDLE_VALUE -1
73 #endif
74 
75 #if !(defined(_WIN32) || defined(_WIN64)) && !(defined(__APPLE__)) //only for linux
76  #include <termios.h>
77 #endif
78 
79 #define BAUD_RATE_T_2000000 0 //< Define to identify 2M baudrate
80 #define BAUD_RATE_T_460800 1 //< Define to identify 460.8k baudrate
81 #define MAX_WATCHDOG_TIME 500 //< Maximum watchdog timer time
82 #define READ_TIMEOUT 4000 //< Timeout on readings
83 
84 #include "commands.h"
85 #include <stdint.h>
86 
87 
88 //==============================================================================
89 // structures/enums
90 //==============================================================================
91 
93 
95 {
96 #if (defined(_WIN32) || defined(_WIN64))
97  HANDLE file_handle;
98 #else
100 #endif
101 };
102 
103 
104 //==============================================================================
105 // function definitions
106 //==============================================================================
107 
111 //=========================================================== RS485listPorts
112 
136 int RS485listPorts( char list_of_ports[10][255] );
137 
138 //================================================================ openRS485
139 
163 #if !(defined(_WIN32) || defined(_WIN64)) && !(defined(__APPLE__)) //only for linux
164  void openRS485( comm_settings *comm_settings_t, const char *port_s, int BAUD_RATE = B2000000);
165 #elif !(defined(_WIN32) || defined(_WIN64)) && (defined(__APPLE__)) //only for mac
166  void openRS485( comm_settings *comm_settings_t, const char *port_s, int BAUD_RATE = 2000000);
167 #else
168  void openRS485( comm_settings *comm_settings_t, const char *port_s, int BAUD_RATE = 2000000);
169 #endif
170 
171 
172 //=============================================================== closeRS485
173 
174 
191 void closeRS485( comm_settings *comm_settings_t );
192 
193 //================================================================ RS485read
194 
222 int RS485read( comm_settings *comm_settings_t, int id, char *package );
223 
224 //========================================================= RS485ListDevices
225 
254 int RS485ListDevices( comm_settings *comm_settings_t, char list_of_ids[255] );
255 
256 //============================================================= RS485GetInfo
257 
283 void RS485GetInfo( comm_settings *comm_settings_t, char *buffer );
284 
291 //================================================================ commPing
292 
320 int commPing( comm_settings *comm_settings_t, int id );
321 
322 //============================================================= commActivate
323 
346 void commActivate( comm_settings *comm_settings_t, int id, char activate );
347 
348 //============================================================ commSetBaudRate
349 
372 void commSetBaudRate( comm_settings *comm_settings_t, int id, short int baudrate);
373 
374 //============================================================ commSetWatchDog
375 
399 void commSetWatchDog( comm_settings *comm_settings_t, int id, short int wdt);
400 
401 //============================================================ commSetInputs
402 
429 void commSetInputs( comm_settings *comm_settings_t, int id, short int inputs[]);
430 
431 //============================================================ commSetInputsAck
432 
461 int commSetInputsAck( comm_settings *comm_settings_t, int id, short int inputs[]);
462 
463 //============================================================ commSetPosStiff
464 
492 void commSetPosStiff(comm_settings *comm_settings_t, int id, short int inputs[]);
493 
494 //============================================================ commGetInputs
495 
527 int commGetInputs( comm_settings *comm_settings_t, int id, short int inputs[2] );
528 
529 //====================================================== commGetMeasurements
530 
562 int commGetMeasurements( comm_settings *comm_settings_t, int id, short int measurements[3] );
563 
564 //====================================================== commGetCounters
565 
597 int commGetCounters( comm_settings *comm_settings_t, int id, short unsigned int counters[20] );
598 
599 //====================================================== commGetCurrents
600 
632 int commGetCurrents( comm_settings *comm_settings_t, int id, short int currents[2] );
633 
634 //======================================================= commGetCurrAndMeas
635 
670 int commGetCurrAndMeas( comm_settings *comm_settings_t, int id, short int *values);
671 
672 //=============================================================== commGetEmg
673 
705 int commGetEmg(comm_settings *comm_settings_t, int id, short int emg[2]);
706 
707 //======================================================== commGetVelocities
708 
740 int commGetVelocities(comm_settings *comm_settings_t, int id, short int measurements[]);
741 
742 
743 //======================================================== commGetAccelerations
744 
776 int commGetAccelerations(comm_settings *comm_settings_t, int id, short int measurements[] );
777 
778 //========================================================== commGetActivate
779 
811 int commGetActivate( comm_settings *comm_settings_t, int id, char *activate );
812 
813 
814 //============================================================== commGetInfo
815 
842 int commGetInfo( comm_settings *comm_settings_t, int id, short int info_type, char *info );
843 
844 
845 //============================================================== commBootloader
846 
870 int commBootloader(comm_settings *comm_settings_t, int id);
871 
872 
873 //============================================================== commCalibrate
874 
897 int commCalibrate(comm_settings *comm_settings_t, int id);
898 
899 //============================================================== commHandCalibrate
900 
925 int commHandCalibrate(comm_settings *comm_settings_t, int id, short int speed, short int repetitions);
926 
933 //============================================================ commSetZeros
934 
963 int commSetZeros( comm_settings *comm_settings_t,
964  int id,
965  void *values,
966  unsigned short num_of_values );
967 
968 //============================================================ commGetParamList
969 
1012 int commGetParamList(comm_settings *comm_settings_t, int id, unsigned short index,
1013  void *values, unsigned short value_size, unsigned short num_of_values,
1014  uint8_t *buffer);
1015 
1016 //============================================================ commStoreParams
1017 
1040 int commStoreParams( comm_settings *comm_settings_t, int id);
1041 
1042 //========================================================== commStoreDefaultParams
1043 
1064 int commStoreDefaultParams( comm_settings *comm_settings_t, int id);
1065 
1066 //========================================================== commRestoreParams
1067 
1068 
1091 int commRestoreParams( comm_settings *comm_settings_t, int id );
1092 
1093 //========================================================== commInitMem
1094 
1095 
1119 int commInitMem(comm_settings *comm_settings_t, int id);
1120 
1128 //========================================================== timevaldiff
1129 
1153 long timevaldiff (struct timeval *starttime, struct timeval *finishtime);
1154 
1155 
1156 //================================================================= checksum
1157 
1158 
1178 char checksum ( char * data_buffer, int data_length );
1179 
1197 int commExtDrive(comm_settings *comm_settings_t, int id, char ext_input);
1198 
1199 //============================================================ commSetCuffInputs
1200 
1227 void commSetCuffInputs(comm_settings *comm_settings_t, int id, int flag);
1228 
1229 //====================================================== commGetJoystick
1230 
1262 int commGetJoystick( comm_settings *comm_settings_t, int id, short int joystick[2]);
1263 
1264 
1267 // ----------------------------------------------------------------------------
1268 #endif
1269 
1270 /* [] END OF FILE */
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.
int commSetZeros(comm_settings *comm_settings_t, int id, void *values, unsigned short num_of_values)
This function sets the encoders&#39;s zero positon value that remains stored in the qbMove or qbHand memo...
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.
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 relati...
int commPing(comm_settings *comm_settings_t, int id)
This function is used to ping the qbMove or the qbHand.
void closeRS485(comm_settings *comm_settings_t)
This function is used to close a serial port being used with the qbMove or an qbHand.
char checksum(char *data_buffer, int data_length)
This functions returns an 8 bit LCR checksum over the lenght of a buffer.
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 ...
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...
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 seri...
void commSetWatchDog(comm_settings *comm_settings_t, int id, short int wdt)
This function sets watchdog timer of a qbMove or a qbHand.
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 por...
int commGetEmg(comm_settings *comm_settings_t, int id, short int emg[2])
This function gets measurements from electomyographics sensors connected to the qbHand.
int commStoreDefaultParams(comm_settings *comm_settings_t, int id)
This function stores the factory default parameters.
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.
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...
int commStoreParams(comm_settings *comm_settings_t, int id)
This function stores all parameters that were set in the qbMove or the qbHand memory.
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...
int commExtDrive(comm_settings *comm_settings_t, int id, char ext_input)
This function is used with the armslider device.
int commRestoreParams(comm_settings *comm_settings_t, int id)
This function restores the factory default parameters.
int commCalibrate(comm_settings *comm_settings_t, int id)
This function is used to calibrate the maximum stiffness value of the qbMove.
Definitions for qbMove or qbHand commands, parameters and packages.
void commSetBaudRate(comm_settings *comm_settings_t, int id, short int baudrate)
This function sets the baudrate of communication.
int commInitMem(comm_settings *comm_settings_t, int id)
This function initialize the EEPROM memory of the board by loading the default factory parameters...
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.
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.
int RS485listPorts(char list_of_ports[10][255])
This function is used to return a list of available serial ports.
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...
int RS485read(comm_settings *comm_settings_t, int id, char *package)
This function is used to read a package from the device.
int commGetAccelerations(comm_settings *comm_settings_t, int id, short int measurements[])
This function gets the acceleration of the qbHand motor.
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...
long timevaldiff(struct timeval *starttime, struct timeval *finishtime)
This functions returns a difference between two timeval structures in order to obtain time elapsed be...
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 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...
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 ...
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.
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...
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...


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