#include <ROSiFace.h>
Public Member Functions | |
ROSiFace (const string &topicName, ros::NodeHandle *_node, ROSiFaceOpeningModes op, int queue=1, int bufferDim=1) | |
Complete constructor. | |
~ROSiFace () | |
Destructor. | |
bool | sendMessage (const msg_type &message) |
Send message on topic. | |
bool | updateMessage () |
Update message in topic. | |
bool | getMessage (msg_type &msg) |
Get message from topic. | |
void | getMsgList (deque< msg_type > &listMsg) |
Get the stored messages in the list. |
MipBaselib::ROSiFace< msg_type, msg_type_ptr >::~ROSiFace | ( | ) |
Destructor.
This destructor deletes the ros::Publisher and/or ros::Subscriber.
bool MipBaselib::ROSiFace< msg_type, msg_type_ptr >::sendMessage | ( | const msg_type & | message | ) |
bool MipBaselib::ROSiFace< msg_type, msg_type_ptr >::updateMessage | ( | ) | [virtual] |
Update message in topic.
Implements MipBaselib::ROSiFaceBoss.
bool MipBaselib::ROSiFace< msg_type, msg_type_ptr >::getMessage | ( | msg_type & | msg | ) |
Get message from topic.
[out] | msg | Variable where the message will be stored |
void MipBaselib::ROSiFace< msg_type, msg_type_ptr >::getMsgList | ( | deque< msg_type > & | listMsg | ) |
Get the stored messages in the list.
[out] | msg | List where the messages will be stored If this ROSiFace is ROSIFACE_R or ROSIFACE_RW, this method writes in "listMsg" the list of received messages (max dimension is bufferDim). If this ROSiFace is ROSIFACE_W, this method throw an exception and terminate the execution of the program. |