A Class to subscribe the data provided by the publisher node (skin_driver) More...
#include <skin.h>
Public Member Functions | |
void | initialize_sensor_data () |
Initialize all sensor data stored in the object of the class. | |
Skin () | |
A constructor to initialize the sensor data stored in this class and to create a Subscriber. | |
void | skin_Callback (const boost::shared_ptr< proximity_sensor_driver::prox_sensor_measurement const > &msg) |
The function "skin_Callback" subscribs data from the topic and decrypts them. | |
Public Attributes | |
bool | bsens_num_changed |
If true: sensor number was changed. | |
bool | bstatus_err_ |
Status display Err/NoErr. | |
bool | bstatus_go_ |
Status display Go/NoGo. | |
ros::Time | dtime_subscription_ |
Time stamp of the last subscription. | |
uint8_t | u8asensor_data_ [skind_def::max_sensor_number][skind_def::anz_byte_per_sensor] |
Data from sensor skin. | |
uint8_t | u8readadr_hi_ |
High-byte of the address which represents the beginning of the sensor data in the RAM. | |
uint8_t | u8readadr_lo_ |
Low-byte of the address which represents the beginning of the sensor data in the RAM. | |
uint8_t | u8sensor_number_ |
Number of sensor elements connected to the sensor skin. | |
Private Attributes | |
ros::NodeHandle | nh_ |
ros::Subscriber | skin_sub_ |
A Class to subscribe the data provided by the publisher node (skin_driver)
The class Skin handles the subscription of the topic skin_data. The sensor data received from the topic are decrypted and stored in this class. If the publisher node is offline the class initializes the sensor data with default values.
Skin::Skin | ( | ) |
void Skin::initialize_sensor_data | ( | ) |
Initialize all sensor data stored in the object of the class.
Initialization:
void Skin::skin_Callback | ( | const boost::shared_ptr< proximity_sensor_driver::prox_sensor_measurement const > & | msg | ) |
bool Skin::bstatus_err_ |
bool Skin::bstatus_go_ |
ros::NodeHandle Skin::nh_ [private] |
ros::Subscriber Skin::skin_sub_ [private] |
uint8_t Skin::u8readadr_hi_ |
uint8_t Skin::u8readadr_lo_ |
uint8_t Skin::u8sensor_number_ |