Typedefs | Functions | Variables
rq_sensor.cpp File Reference
#include <string.h>
#include <stdio.h>
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "geometry_msgs/WrenchStamped.h"
#include "robotiq_ft_sensor/rq_sensor_state.h"
#include "robotiq_ft_sensor/ft_sensor.h"
#include "robotiq_ft_sensor/sensor_accessor.h"
Include dependency graph for rq_sensor.cpp:

Go to the source code of this file.

Typedefs

typedef robotiq_ft_sensor::sensor_accessor::Request Request
 

Functions

static bool decode_message_and_do (robotiq_ft_sensor::sensor_accessor::Request &req, robotiq_ft_sensor::sensor_accessor::Response &res)
 decode_message_and_do Decode the message received and do the associated action More...
 
static void decode_message_and_do (INT_8 const *const buff, INT_8 *const ret)
 Decode the message received and do the associated action. More...
 
static robotiq_ft_sensor::ft_sensor get_data (void)
 Builds the message with the force/torque data. More...
 
int main (int argc, char **argv)
 
static int max_retries_ (100)
 
bool receiverCallback (robotiq_ft_sensor::sensor_accessor::Request &req, robotiq_ft_sensor::sensor_accessor::Response &res)
 
static INT_8 sensor_state_machine ()
 
static void wait_for_other_connection ()
 Each second, checks for a sensor that has been connected. More...
 

Variables

std::string ftdi_id
 
ros::Publisher sensor_pub_acc
 

Detailed Description

Date
July 14, 2014
Author
Jonathan Savoie jonat.nosp@m.han..nosp@m.savoi.nosp@m.e@ro.nosp@m.botiq.nosp@m..com Jean-Philippe Roberge ros@r.nosp@m.obot.nosp@m.iq.co.nosp@m.m

Definition in file rq_sensor.cpp.

Typedef Documentation

typedef robotiq_ft_sensor::sensor_accessor::Request Request

Definition at line 53 of file rq_sensor.cpp.

Function Documentation

static bool decode_message_and_do ( robotiq_ft_sensor::sensor_accessor::Request req,
robotiq_ft_sensor::sensor_accessor::Response &  res 
)
static

decode_message_and_do Decode the message received and do the associated action

Parameters
reqrequest (of which the command_id is used)
resresult with requested data
Returns
true iff a valid command_id was given in the request

Definition at line 66 of file rq_sensor.cpp.

static void decode_message_and_do ( INT_8 const *const  buff,
INT_8 *const  ret 
)
static

Decode the message received and do the associated action.

Parameters
buffmessage to decode
retbuffer containing the return value from a GET command

Definition at line 92 of file rq_sensor.cpp.

void get_data ( void  )
static

Builds the message with the force/torque data.

Returns
ft_sensor updated with the latest data

Definition at line 178 of file rq_sensor.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 192 of file rq_sensor.cpp.

static int max_retries_ ( 100  )
static
bool receiverCallback ( robotiq_ft_sensor::sensor_accessor::Request req,
robotiq_ft_sensor::sensor_accessor::Response &  res 
)

Support for old string-based interface

New interface with numerical commands

Definition at line 119 of file rq_sensor.cpp.

static INT_8 sensor_state_machine ( )
static

Definition at line 139 of file rq_sensor.cpp.

static void wait_for_other_connection ( )
static

Each second, checks for a sensor that has been connected.

Definition at line 153 of file rq_sensor.cpp.

Variable Documentation

std::string ftdi_id

Definition at line 55 of file rq_sensor.cpp.

ros::Publisher sensor_pub_acc

Definition at line 57 of file rq_sensor.cpp.



robotiq_ft_sensor
Author(s): Jonathan Savoie
autogenerated on Tue Jun 1 2021 02:30:04