Public Member Functions | Protected Attributes
pcan_receive Class Reference

#include <pcan_receive.h>

List of all members.

Public Member Functions

void hlpMsg ()
void init (int argc, char **argv)
 pcan_receive ()
void receive ()
std_msgs::String TPCANRdMsgToString (TPCANRdMsg m)

Protected Attributes

HANDLE h
std_msgs::String msg
ros::NodeHandle n
ros::Publisher pcan_pub
std::stringstream ss

Detailed Description

Definition at line 18 of file pcan_receive.h.


Constructor & Destructor Documentation

The constructor of the pcan_receive class is based on the first part of the main() function of the receivetest program.

In the contructor the default parameters of the node are defined.

Definition at line 50 of file pcan_receive.cpp.


Member Function Documentation

The help message that is displayed when using the "-?" argument.

The help message only prints a number of strings.

Definition at line 22 of file pcan_receive.cpp.

void pcan_receive::init ( int  argc,
char **  argv 
)

The init() function is based on the middle part of the main() function of the receivetest program.

Compared to the receivetest program a lot of cases have been removed. Therefore, only the PCAN-USB adapter is, and standard messages are, supported.

Definition at line 64 of file pcan_receive.cpp.

The receive() function is based on the read_loop() function of the receivetest program.

In this part the program enters a loop untill it receives a CAN message. A string representation of this message is then published on the pcan_received topic.

Definition at line 175 of file pcan_receive.cpp.

std_msgs::String pcan_receive::TPCANRdMsgToString ( TPCANRdMsg  m)

The TPCANRdMsgToString() function converts an object instance of a received CAN message into a string.

The representing string also contains the time at which the message is received. First the time, and then the message, is converted to a string.

Definition at line 216 of file pcan_receive.cpp.


Member Data Documentation

HANDLE pcan_receive::h [protected]

Definition at line 21 of file pcan_receive.h.

std_msgs::String pcan_receive::msg [protected]

Definition at line 24 of file pcan_receive.h.

Definition at line 22 of file pcan_receive.h.

Definition at line 23 of file pcan_receive.h.

std::stringstream pcan_receive::ss [protected]

Definition at line 25 of file pcan_receive.h.


The documentation for this class was generated from the following files:


pcan_topics
Author(s):
autogenerated on Thu Jun 6 2019 17:40:04