A Class to handle the communication with the publisher node (skin_driver). More...
#include <config_skin.h>
Public Member Functions | |
bool | OnRequestChanges (const uint8_t start_adr[2], const uint8_t steps, const uint8_t number_of_bytes, uint8_t write_data, bool sens_num_change) |
Calls the Service "skin_serv" with provided parameters. | |
void | skin_Callback (const boost::shared_ptr< skin_driver::skin_meas const > &msg) |
The function "skin_Callback" subscribs data from the topic. | |
SkinConfig () | |
A constructor to initialize values and to create a Subscriber and Client. | |
Public Attributes | |
bool | bskin_driver_node_online |
if bskin_driver_node_online == true: node cmo_ecu is online | |
ros::Time | dtime_subscription_ |
Time stamp of last message. | |
uint8_t | ui8dyn_thres_currentvalue_ |
Current value of dynamic threshold. | |
uint8_t | ui8sensor_number_ |
Number of sensors connected to the sensor skin. | |
Private Attributes | |
ros::ServiceClient | config_client |
ros::NodeHandle | nh_ |
ros::Subscriber | skin_sub_ |
skin_driver::skin_serv | srv_ |
ROS service. |
A Class to handle the communication with the publisher node (skin_driver).
The class SkinConfig handles the communication with the publisher node. It subscribes the topic "skin_data" and uses the Service "skin_serv". The data received from the topic are stored in this class.
Definition at line 53 of file config_skin.h.
SkinConfig::SkinConfig | ( | ) |
A constructor to initialize values and to create a Subscriber and Client.
Default values:
Definition at line 35 of file config_skin.cpp.
bool SkinConfig::OnRequestChanges | ( | const uint8_t | start_adr[2], | |
const uint8_t | steps, | |||
const uint8_t | number_of_bytes, | |||
uint8_t | write_data, | |||
bool | sens_num_change | |||
) |
Calls the Service "skin_serv" with provided parameters.
OnRequestChanges: - calls the Service skin_serv (request a write to RAM command from node "skin_driver")
start_adr | Memory address of first byte in which the node "skin_driver" should write a value | |
steps | The node "skin_driver" will increment the address "start_adr" (a copy of "start_adr") by "steps" after one "write to RAM" transaction | |
number_of_bytes | Number of bytes which the node "skin_driver" should write into the RAM | |
write_data | Data which the node "skin_driver" should write into RAM | |
sens_num_change | If "sens_num_change" is true and "write_data" equals 254 the node "skin_driver" will delete the old end of chain marker |
return The returned value is an indicator for the success of the service call
Definition at line 58 of file config_skin.cpp.
void SkinConfig::skin_Callback | ( | const boost::shared_ptr< skin_driver::skin_meas const > & | msg | ) |
The function "skin_Callback" subscribs data from the topic.
Definition at line 49 of file config_skin.cpp.
if bskin_driver_node_online == true: node cmo_ecu is online
Definition at line 86 of file config_skin.h.
ros::ServiceClient SkinConfig::config_client [private] |
Definition at line 106 of file config_skin.h.
ros::Time SkinConfig::dtime_subscription_ |
Time stamp of last message.
Definition at line 78 of file config_skin.h.
ros::NodeHandle SkinConfig::nh_ [private] |
Definition at line 104 of file config_skin.h.
ros::Subscriber SkinConfig::skin_sub_ [private] |
Definition at line 105 of file config_skin.h.
skin_driver::skin_serv SkinConfig::srv_ [private] |
ROS service.
Definition at line 109 of file config_skin.h.
Current value of dynamic threshold.
Definition at line 96 of file config_skin.h.
uint8_t SkinConfig::ui8sensor_number_ |
Number of sensors connected to the sensor skin.
Definition at line 94 of file config_skin.h.