Skin Class Reference

A Class to subscribe the data provided by the publisher node (skin_driver). More...

#include <skin.h>

List of all members.

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< skin_driver::skin_meas 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_

Detailed Description

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.

Definition at line 57 of file skin.h.


Constructor & Destructor Documentation

Skin::Skin (  ) 

A constructor to initialize the sensor data stored in this class and to create a Subscriber.

The construktor uses the function "initialize_sensor_data" to set the sensor data to default values.

Definition at line 37 of file skin.cpp.


Member Function Documentation

void Skin::initialize_sensor_data (  ) 

Initialize all sensor data stored in the object of the class.

Initialization:

  • sensor values = 0 (1536 values);
  • sensor number = skind_def::max_sensor_number
  • high-byte of the address which represents the beginnign of the sensor data in the RAM = 1
  • low-byte of the address which represents the beginnign of the sensor data in the RAM = 0
  • Status display Flag Go/NoGo (bstatus_go_)= 0
  • Status display Flag Err/NoErr (bstatus_err_)= 1

Definition at line 48 of file skin.cpp.

void Skin::skin_Callback ( const boost::shared_ptr< skin_driver::skin_meas const > &  msg  ) 

The function "skin_Callback" subscribs data from the topic and decrypts them.

Definition at line 65 of file skin.cpp.


Member Data Documentation

If true: sensor number was changed.

Definition at line 112 of file skin.h.

Status display Err/NoErr.

Conditions:

  • "bstatus_err_ == true" equals Err
  • "bstatus_err_ == false" equals NoErr

Definition at line 109 of file skin.h.

Status display Go/NoGo.

Conditions:

  • "bstatus_go_ == true" equals GO
  • "bstatus_go_ == false" equals NoGO

Definition at line 101 of file skin.h.

Time stamp of the last subscription.

Definition at line 82 of file skin.h.

ros::NodeHandle Skin::nh_ [private]

Definition at line 133 of file skin.h.

ros::Subscriber Skin::skin_sub_ [private]

Definition at line 134 of file skin.h.

Data from sensor skin.

sensor_data layout

Index: 0 1 2 3 4 5 6 7

sensor_data[0][0..7] = Stat | X | Ini | Limit | U1 | U2 | U3 | Dyn sensor_data[1][0..7] = Stat | X | Ini ...

Definition at line 127 of file skin.h.

High-byte of the address which represents the beginning of the sensor data in the RAM.

Definition at line 89 of file skin.h.

Low-byte of the address which represents the beginning of the sensor data in the RAM.

Definition at line 91 of file skin.h.

Number of sensor elements connected to the sensor skin.

Definition at line 93 of file skin.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables


skin_dashboard
Author(s): Joerg Wagner
autogenerated on Fri Jan 11 09:39:20 2013