Defines | Functions | Variables
rq_sensor_com.cpp File Reference
#include <dirent.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <fcntl.h>
#include "robotiq_force_torque_sensor/rq_sensor_com.h"
Include dependency graph for rq_sensor_com.cpp:

Go to the source code of this file.

Defines

#define REGISTER_FIRMWARE_VERSION   500
#define REGISTER_PRODUCTION_YEAR   514
#define REGISTER_SELECT_OUTPUT   410
#define REGISTER_SERIAL_NUMBER   510
#define RQ_COM_JAM_SIGNAL_CHAR   0xff
#define RQ_COM_JAM_SIGNAL_LENGTH   50
#define RQ_COM_MAX_STR_LENGTH   20
#define RQ_COM_TIMER_FOR_STREAM_DETECTION_MAX_VALUE   20
#define RQ_COM_TIMER_FOR_VALID_STREAM_MAX_VALUE   40

Functions

static UINT_16 rq_com_compute_crc (UINT_8 const *adr, INT_32 length)
void rq_com_do_zero_force_flag ()
 Set the "zero sensor" flag to 1. When the next stream message will be decoded, the effort values will be stored as offsets a substracted from the next values.
float rq_com_get_received_data (UINT_8 i)
 Return an effort component.
void rq_com_get_str_firmware_version (INT_8 *firmware_version)
 Retrieves the sensor firmware version.
void rq_com_get_str_production_year (INT_8 *production_year)
 Retrieves the sensor firmware version.
void rq_com_get_str_serial_number (INT_8 *serial_number)
 Retrieves the sensor serial number.
bool rq_com_get_stream_detected ()
 retrieves the sensor firmware version
bool rq_com_get_valid_stream ()
 returns if the stream message is valid
bool rq_com_got_new_message ()
 Returns true if a new valid stream message has been decoded and is available.
static UINT_8 rq_com_identify_device (INT_8 const *const d_name)
 try to discover a com port by polling each serial port
void rq_com_listen_stream (void)
 Listens and decode a valid stream input.
static INT_32 rq_com_read_port (UINT_8 *const buf, UINT_32 buf_len)
 Reads incomming data on the com port.
static INT_8 rq_com_send_fc_03 (UINT_16 base, UINT_16 n, UINT_16 *const data)
 Sends a read request.
static void rq_com_send_fc_03_request (UINT_16 base, UINT_16 n)
 Compute and send the fc03 request on the com port.
static INT_8 rq_com_send_fc_16 (INT_32 base, INT_32 n, UINT_16 const *const data)
static void rq_com_send_fc_16_request (INT_32 base, INT_32 n, UINT_8 const *const data)
static void rq_com_send_jam_signal (void)
 Send a signal that interrupts the streaming.
INT_8 rq_com_start_stream (void)
 Starts the sensor streaming mode.
static void rq_com_stop_stream_after_boot (void)
 Send a jam signal to stop the sensor stream and retry until the stream stops.
static INT_8 rq_com_tentative_connexion (void)
 Tries connecting to the sensor.
static INT_32 rq_com_wait_for_fc_03_echo (UINT_8 *const data)
static INT_32 rq_com_wait_for_fc_16_echo (void)
 Reads the response to a fc16 write query.
static INT_32 rq_com_write_port (UINT_8 const *const buf, UINT_32 buf_len)
INT_8 rq_sensor_com ()
 Discovers and initialize the communication with the sensor.
void rq_sensor_com_read_info_high_lvl (void)
 Reads and stores high level information from the sensor. These include the firmware version, the serial number and the production year.
void stop_connection ()
 close the serial port.

Variables

static UINT_16 rq_com_computed_crc = 0
static UINT_16 rq_com_crc = 0
static UINT_32 rq_com_msg_received = 0
static bool rq_com_new_message = false
static UINT_8 rq_com_rcv_buff [MP_BUFF_SIZE]
static UINT_8 rq_com_rcv_buff2 [MP_BUFF_SIZE]
static INT_32 rq_com_rcv_len
static INT_32 rq_com_rcv_len2 = 0
static float rq_com_received_data [6] = {0.0}
static float rq_com_received_data_offset [6] = {0.0}
static UINT_8 rq_com_snd_buff [MP_BUFF_SIZE]
static INT_8 rq_com_str_sensor_firmware_version [RQ_COM_MAX_STR_LENGTH]
static INT_8 rq_com_str_sensor_production_year [RQ_COM_MAX_STR_LENGTH]
static INT_8 rq_com_str_sensor_serial_number [RQ_COM_MAX_STR_LENGTH]
static bool rq_com_stream_detected = false
static INT_32 rq_com_timer_for_stream_detection = 0
static INT_32 rq_com_timer_for_valid_stream = 0
static bool rq_com_valid_stream = false
static INT_32 rq_com_zero_force_flag = 0
static INT_32 rq_state_sensor_watchdog = 0

Define Documentation

#define REGISTER_FIRMWARE_VERSION   500

Definition at line 68 of file rq_sensor_com.cpp.

#define REGISTER_PRODUCTION_YEAR   514

Definition at line 67 of file rq_sensor_com.cpp.

#define REGISTER_SELECT_OUTPUT   410

Definition at line 65 of file rq_sensor_com.cpp.

#define REGISTER_SERIAL_NUMBER   510

Definition at line 66 of file rq_sensor_com.cpp.

#define RQ_COM_JAM_SIGNAL_CHAR   0xff

Definition at line 70 of file rq_sensor_com.cpp.

#define RQ_COM_JAM_SIGNAL_LENGTH   50

Definition at line 71 of file rq_sensor_com.cpp.

#define RQ_COM_MAX_STR_LENGTH   20

Definition at line 69 of file rq_sensor_com.cpp.

Definition at line 72 of file rq_sensor_com.cpp.

Definition at line 73 of file rq_sensor_com.cpp.


Function Documentation

static UINT_16 rq_com_compute_crc ( UINT_8 const *  adr,
INT_32  length 
) [static]

Definition at line 719 of file rq_sensor_com.cpp.

void rq_com_do_zero_force_flag ( void  )

Set the "zero sensor" flag to 1. When the next stream message will be decoded, the effort values will be stored as offsets a substracted from the next values.

Definition at line 1139 of file rq_sensor_com.cpp.

Return an effort component.

Parameters:
iIndex of the component. 0 to 2 for Fx, Fy and Fz. 3 to 5 for Mx, My and Mz.

Definition at line 1110 of file rq_sensor_com.cpp.

void rq_com_get_str_firmware_version ( INT_8 firmware_version)

Retrieves the sensor firmware version.

Parameters:
firmware_versionAddress of the return buffer

Definition at line 1074 of file rq_sensor_com.cpp.

void rq_com_get_str_production_year ( INT_8 production_year)

Retrieves the sensor firmware version.

Parameters:
production_yearAddress of the return buffer

Definition at line 1083 of file rq_sensor_com.cpp.

void rq_com_get_str_serial_number ( INT_8 serial_number)

Retrieves the sensor serial number.

Parameters:
serial_numberaddress of the return buffer

Definition at line 1065 of file rq_sensor_com.cpp.

bool rq_com_get_stream_detected ( void  )

retrieves the sensor firmware version

Parameters:
production_yearAddress of the return buffer

Definition at line 1092 of file rq_sensor_com.cpp.

bool rq_com_get_valid_stream ( void  )

returns if the stream message is valid

Definition at line 1100 of file rq_sensor_com.cpp.

bool rq_com_got_new_message ( void  )

Returns true if a new valid stream message has been decoded and is available.

When this function is called, the variable that indicates if a new message is available is set to false even if the message hasn't beed read.

Definition at line 1127 of file rq_sensor_com.cpp.

static UINT_8 rq_com_identify_device ( INT_8 const *const  d_name) [static]

try to discover a com port by polling each serial port

Author:
Pierre-Olivier Proulx
Returns:
1 if a device is found, 0 otherwise

Definition at line 1162 of file rq_sensor_com.cpp.

void rq_com_listen_stream ( void  )

Listens and decode a valid stream input.

Definition at line 319 of file rq_sensor_com.cpp.

static INT_32 rq_com_read_port ( UINT_8 *const  buf,
UINT_32  buf_len 
) [static]

Reads incomming data on the com port.

Parameters:
buf,containsthe incomming data
buf_lenmaximum number of data to read
Returns:
The number of character read

Definition at line 679 of file rq_sensor_com.cpp.

static INT_8 rq_com_send_fc_03 ( UINT_16  base,
UINT_16  n,
UINT_16 *const  data 
) [static]

Sends a read request.

Parameters:
baseAddress of the first register to read
nNumber of bytes to read
datatable into which data will be written

Definition at line 533 of file rq_sensor_com.cpp.

static void rq_com_send_fc_03_request ( UINT_16  base,
UINT_16  n 
) [static]

Compute and send the fc03 request on the com port.

Parameters:
baseAddress of the first register to read
nNumber of bytes to read

Definition at line 777 of file rq_sensor_com.cpp.

static INT_8 rq_com_send_fc_16 ( INT_32  base,
INT_32  n,
UINT_16 const *const  data 
) [static]

Definition at line 579 of file rq_sensor_com.cpp.

static void rq_com_send_fc_16_request ( INT_32  base,
INT_32  n,
UINT_8 const *const  data 
) [static]

Definition at line 917 of file rq_sensor_com.cpp.

static void rq_com_send_jam_signal ( void  ) [static]

Send a signal that interrupts the streaming.

Definition at line 453 of file rq_sensor_com.cpp.

Starts the sensor streaming mode.

Returns:
0 if the stream started, -1 otherwise

Definition at line 501 of file rq_sensor_com.cpp.

static void rq_com_stop_stream_after_boot ( void  ) [static]

Send a jam signal to stop the sensor stream and retry until the stream stops.

Definition at line 468 of file rq_sensor_com.cpp.

static INT_8 rq_com_tentative_connexion ( void  ) [static]

Tries connecting to the sensor.

Returns:
1 if the connection attempt succeeds, -1 otherwise

Definition at line 238 of file rq_sensor_com.cpp.

static INT_32 rq_com_wait_for_fc_03_echo ( UINT_8 *const  data) [static]

Definition at line 822 of file rq_sensor_com.cpp.

static INT_32 rq_com_wait_for_fc_16_echo ( void  ) [static]

Reads the response to a fc16 write query.

Returns:
0 for an invalid response, 1 otherwise

Definition at line 986 of file rq_sensor_com.cpp.

static INT_32 rq_com_write_port ( UINT_8 const *const  buf,
UINT_32  buf_len 
) [static]

Definition at line 697 of file rq_sensor_com.cpp.

INT_8 rq_sensor_com ( void  )

Discovers and initialize the communication with the sensor.

The functions loops through all the serial com ports and polls them to discover the sensor

Definition at line 141 of file rq_sensor_com.cpp.

Reads and stores high level information from the sensor. These include the firmware version, the serial number and the production year.

Definition at line 630 of file rq_sensor_com.cpp.

void stop_connection ( void  )

close the serial port.

Warning:
Only valid under Windows.

Definition at line 1148 of file rq_sensor_com.cpp.


Variable Documentation

Definition at line 80 of file rq_sensor_com.cpp.

UINT_16 rq_com_crc = 0 [static]

Definition at line 81 of file rq_sensor_com.cpp.

Definition at line 87 of file rq_sensor_com.cpp.

bool rq_com_new_message = false [static]

Definition at line 101 of file rq_sensor_com.cpp.

Definition at line 89 of file rq_sensor_com.cpp.

Definition at line 91 of file rq_sensor_com.cpp.

Definition at line 92 of file rq_sensor_com.cpp.

INT_32 rq_com_rcv_len2 = 0 [static]

Definition at line 93 of file rq_sensor_com.cpp.

float rq_com_received_data[6] = {0.0} [static]

Definition at line 77 of file rq_sensor_com.cpp.

float rq_com_received_data_offset[6] = {0.0} [static]

Definition at line 78 of file rq_sensor_com.cpp.

Definition at line 90 of file rq_sensor_com.cpp.

Definition at line 85 of file rq_sensor_com.cpp.

Definition at line 84 of file rq_sensor_com.cpp.

Definition at line 83 of file rq_sensor_com.cpp.

bool rq_com_stream_detected = false [static]

Definition at line 99 of file rq_sensor_com.cpp.

Definition at line 102 of file rq_sensor_com.cpp.

Definition at line 103 of file rq_sensor_com.cpp.

bool rq_com_valid_stream = false [static]

Definition at line 100 of file rq_sensor_com.cpp.

Definition at line 95 of file rq_sensor_com.cpp.

Definition at line 96 of file rq_sensor_com.cpp.



robotiq_force_torque_sensor
Author(s): Jonathan Savoie
autogenerated on Thu Aug 27 2015 14:44:30