#include <pcan_transmit.h>
Public Member Functions | |
void | hlpMsg () |
void | init (int argc, char **argv) |
pcan_transmit () | |
TPCANMsg | StringToTPCANRdMsg (std_msgs::String msg) |
void | transmit (const std_msgs::String can_message) |
Protected Attributes | |
HANDLE | h |
std_msgs::String | msg |
ros::NodeHandle | n |
ros::Subscriber | pcan_sub |
std::stringstream | ss |
Definition at line 22 of file pcan_transmit.h.
The constructor of the pcan_transmit class is based on the first part of the main() function of the transmitest program.
In the contructor the default parameters of the node are defined.
Definition at line 49 of file pcan_transmit.cpp.
void pcan_transmit::hlpMsg | ( | ) |
The help message that is displayed when using the "-?" argument.
The help message only prints a number of strings.
Definition at line 20 of file pcan_transmit.cpp.
void pcan_transmit::init | ( | int | argc, |
char ** | argv | ||
) |
The init() function is based on the middle part of the main() function of the transmitest program.
Compared to the transmitest program a lot of cases have been removed. Therefore, only the PCAN-USB adapter is, and standard messages are, supported.
Definition at line 62 of file pcan_transmit.cpp.
TPCANMsg pcan_transmit::StringToTPCANRdMsg | ( | std_msgs::String | msg | ) |
This function checks whether the string can be converted into a CAN message. If this is a possibility the corresponding CAN message is send.
Definition at line 175 of file pcan_transmit.cpp.
void pcan_transmit::transmit | ( | const std_msgs::String | can_message | ) |
The transmit() function is based on the write_loop() function of the transmitest program.
In this part the program waits for a string publication on the pcan_transmitted topic and then sends a CAN message based on this string.
Definition at line 207 of file pcan_transmit.cpp.
HANDLE pcan_transmit::h [protected] |
Definition at line 25 of file pcan_transmit.h.
std_msgs::String pcan_transmit::msg [protected] |
Definition at line 28 of file pcan_transmit.h.
ros::NodeHandle pcan_transmit::n [protected] |
Definition at line 26 of file pcan_transmit.h.
ros::Subscriber pcan_transmit::pcan_sub [protected] |
Definition at line 27 of file pcan_transmit.h.
std::stringstream pcan_transmit::ss [protected] |
Definition at line 29 of file pcan_transmit.h.