Classes | |
| class | PairSortMod |
Public Member Functions | |
| template<class MSGPTR > | |
| void | Callback (const MSGPTR &msg) |
| template<typename V > | |
| std::string | get_value_string (V value) |
| std::string | get_value_string (char value) |
| void | JoyCallback (const sensor_msgs::JoyConstPtr &msg) |
| template<typename V > | |
| void | progressValue (V value) |
| PublishMFD (ros::NodeHandle *n) | |
| A char is interpreted as integer if this is 1 or as unsigned integer if this is 2 and as char on any other value. | |
| template<class MSG , class MSGPTR > | |
| void | start () |
| void | startJoy () |
| ~PublishMFD () | |
Private Types | |
| enum | { LEFT, CENTER, RIGHT } |
Private Attributes | |
| int | align |
| Align of the text in the field, 0=Left, 1=Center, 2 (or anything else)=Right. | |
| int | axis_button |
| The button or axis number if using Joy topic. | |
| bool | axis_or_button |
| Joy topic addition. | |
| int | char_as_int |
| int | field_length |
| Field length. | |
| int | line |
| The line where the string will be placed. | |
| ros::NodeHandle * | n |
| The node handler. | |
| std::string | negative_oversize |
| String to show if the integer part of a value is bigger then the size (negative) | |
| int | pos |
| Position from the beginning of the line. | |
| std::string | positive_oversize |
| String to show if the integer part of a value is bigger then the size (positiv) | |
| ros::Publisher | pub |
| The publisher. | |
| std::set< PairSortMod > | ranges |
| bool | stringprint |
| If this is true, there will be strings instead of values. | |
| std::string | stringprint_setup |
| if stringprint is enabled, this will store the strings to be displayed | |
| ros::Subscriber | sub |
| The subscriber. | |
Definition at line 185 of file mfd_writer.cpp.
anonymous enum [private] |
Definition at line 187 of file mfd_writer.cpp.
| PublishMFD< T >::PublishMFD | ( | ros::NodeHandle * | n | ) | [inline] |
A char is interpreted as integer if this is 1 or as unsigned integer if this is 2 and as char on any other value.
Definition at line 220 of file mfd_writer.cpp.
| PublishMFD< T >::~PublishMFD | ( | ) | [inline] |
Definition at line 312 of file mfd_writer.cpp.
| void PublishMFD< T >::Callback | ( | const MSGPTR & | msg | ) | [inline] |
Definition at line 492 of file mfd_writer.cpp.
| std::string PublishMFD< T >::get_value_string | ( | V | value | ) | [inline] |
Definition at line 318 of file mfd_writer.cpp.
| std::string PublishMFD< T >::get_value_string | ( | char | value | ) | [inline] |
Definition at line 331 of file mfd_writer.cpp.
| void PublishMFD< T >::JoyCallback | ( | const sensor_msgs::JoyConstPtr & | msg | ) | [inline] |
Definition at line 463 of file mfd_writer.cpp.
Definition at line 371 of file mfd_writer.cpp.
Definition at line 498 of file mfd_writer.cpp.
| void PublishMFD< T >::startJoy | ( | ) | [inline] |
Definition at line 505 of file mfd_writer.cpp.
int PublishMFD< T >::align [private] |
Align of the text in the field, 0=Left, 1=Center, 2 (or anything else)=Right.
Definition at line 210 of file mfd_writer.cpp.
int PublishMFD< T >::axis_button [private] |
The button or axis number if using Joy topic.
Definition at line 214 of file mfd_writer.cpp.
bool PublishMFD< T >::axis_or_button [private] |
Joy topic addition.
Definition at line 213 of file mfd_writer.cpp.
int PublishMFD< T >::char_as_int [private] |
Definition at line 217 of file mfd_writer.cpp.
int PublishMFD< T >::field_length [private] |
Field length.
Definition at line 209 of file mfd_writer.cpp.
int PublishMFD< T >::line [private] |
The line where the string will be placed.
Definition at line 207 of file mfd_writer.cpp.
ros::NodeHandle* PublishMFD< T >::n [private] |
The node handler.
Definition at line 203 of file mfd_writer.cpp.
std::string PublishMFD< T >::negative_oversize [private] |
String to show if the integer part of a value is bigger then the size (negative)
Definition at line 212 of file mfd_writer.cpp.
int PublishMFD< T >::pos [private] |
Position from the beginning of the line.
Definition at line 208 of file mfd_writer.cpp.
std::string PublishMFD< T >::positive_oversize [private] |
String to show if the integer part of a value is bigger then the size (positiv)
Definition at line 211 of file mfd_writer.cpp.
ros::Publisher PublishMFD< T >::pub [private] |
The publisher.
Definition at line 204 of file mfd_writer.cpp.
std::set<PairSortMod> PublishMFD< T >::ranges [private] |
Definition at line 202 of file mfd_writer.cpp.
bool PublishMFD< T >::stringprint [private] |
If this is true, there will be strings instead of values.
Definition at line 215 of file mfd_writer.cpp.
std::string PublishMFD< T >::stringprint_setup [private] |
if stringprint is enabled, this will store the strings to be displayed
Definition at line 216 of file mfd_writer.cpp.
ros::Subscriber PublishMFD< T >::sub [private] |
The subscriber.
Definition at line 205 of file mfd_writer.cpp.