#include <ROSNode.h>
Public Member Functions | |
ResourcePlate | getPlate () const |
Gets the plate. | |
ROSNode (const string &nodeName) | |
Node name constructor. | |
ROSNode (int argc, const char *argv[]) | |
Argc/argv constructor (required by the Scheduler). | |
~ROSNode () | |
Destructor. | |
int | openTopic (const string &topicname, ROSiFaceOpeningModes mode, int queueLength=1, int bufferLength=1, ROSiFaceMessageTypes ty=ROSIFACE_TYPE_STD_STRING) |
Open a topic. | |
bool | updateTopic (int topicSpecifier) |
Read and update a topic. | |
bool | getTopicMessage (int topicSpecifier, string &msg) |
Get the message from a topic. | |
bool | getUpdateTopicMessage (int topicSpecifier, string &msg) |
Update the topic and get the message. | |
bool | writeTopic (int topicSpecifier, const string &msg) |
Write a topic. | |
void | getTopicMessages (int topicSpecifier, deque< string > &msg) |
Get the actual list of the stored topic. | |
void | getUpdateTopicMessages (int topicSpecifier, deque< string > &msg) |
Get and update the actual list of the stored topic. | |
ros::NodeHandle * | getROSNode () |
Get the pointer to the topic handle. | |
int | getOpenTopicsNum () const |
Get the actual number of open topics. | |
Protected Attributes | |
ROSNodeOptions | _options |
MipResources::ROSNode::ROSNode | ( | const string & | nodeName | ) |
Node name constructor.
[in] | &nodeName | Name of the node. This constructor initializes ROS and create a ros node whose name is "nodeName". In normal operation this constructor is never called. |
MipResources::ROSNode::ROSNode | ( | int | argc, | |
const char * | argv[] | |||
) |
Argc/argv constructor (required by the Scheduler).
[in] | &nodeName | Name of the node. This constructor initializes ROS and create a ros node whose name is MIP_{id}, where {id} is the id of the robot. This is the constructor called in normal operation (i.e.: it is the constructor called by the Scheduler). |
MipResources::ROSNode::~ROSNode | ( | ) |
Destructor.
The destructor closes and clears all open topics (hence, all ros::Publisher and ros::Subscriber).
ResourcePlate MipResources::ROSNode::getPlate | ( | ) | const [inline, virtual] |
int MipResources::ROSNode::openTopic | ( | const string & | topicname, | |
ROSiFaceOpeningModes | mode, | |||
int | queueLength = 1 , |
|||
int | bufferLength = 1 , |
|||
ROSiFaceMessageTypes | ty = ROSIFACE_TYPE_STD_STRING | |||
) |
Open a topic.
[in] | &topicname | Name of the topic you want to open. |
[in] | mode | Opening mode of the topic (read, write, read/write). |
[in] | queueLength | (optional) Length of the queue of the node. Default length is 1. |
[in] | bufferLength | (optional) Length of the queue where storing the messages. Default length is 1. |
bool MipResources::ROSNode::updateTopic | ( | int | topicSpecifier | ) |
Read and update a topic.
[in] | topicSpecifier | This is the topic specifier number, and is given when the topic is opened. This method reads the topic specified by "topicSpecifier" and updates the internal variable. The method returns true if ros::ok(), false otherwise. If the specified topic was opened as write-only the method throws an exception and terminate the execution of the process. |
bool MipResources::ROSNode::getTopicMessage | ( | int | topicSpecifier, | |
string & | msg | |||
) |
Get the message from a topic.
[in] | topicSpecifier | This is the topic specifier number, and is given when the topic is opened. |
[out] | msg | String where store the info This method reads the topic specified by "topicSpecifier" and updates the internal variable. The method returns true if ros::ok(), false otherwise. If the specified topic was opened as write-only the method throws an exception and terminate the execution of the process. |
bool MipResources::ROSNode::getUpdateTopicMessage | ( | int | topicSpecifier, | |
string & | msg | |||
) |
Update the topic and get the message.
[in] | topicSpecifier | This is the topic specifier number, and is given when the topic is opened. |
[out] | msg | String where store the info This method reads the topic specified by "topicSpecifier" and updates the internal variable. The method returns true if ros::ok(), false otherwise. If the specified topic was opened as write-only the method throws an exception and terminate the execution of the process. |
bool MipResources::ROSNode::writeTopic | ( | int | topicSpecifier, | |
const string & | msg | |||
) |
Write a topic.
[in] | topicSpecifier | This is the topic specifier number, and is given when the topic is opened. |
[in] | &message | If a message is found on the topic, it is stored in this string. This method writes "message" on the topic specified by "topicSpecifier". The method returns true if ros::ok(), false otherwise. If the specified topic was opened as read-only the method throws an exception and terminate the execution of the process. |
void MipResources::ROSNode::getTopicMessages | ( | int | topicSpecifier, | |
deque< string > & | msg | |||
) |
Get the actual list of the stored topic.
[in] | topicSpecifier | This is the topic specifier number, and is given when the topic is opened. |
[in] | msg | List where the messages will be stored. |
void MipResources::ROSNode::getUpdateTopicMessages | ( | int | topicSpecifier, | |
deque< string > & | msg | |||
) |
Get and update the actual list of the stored topic.
[in] | topicSpecifier | This is the topic specifier number, and is given when the topic is opened. |
[in] | msg | List where the messages will be stored. |
ros::NodeHandle * MipResources::ROSNode::getROSNode | ( | ) |
Get the pointer to the topic handle.
int MipResources::ROSNode::getOpenTopicsNum | ( | ) | const |
Get the actual number of open topics.
ROSNodeOptions MipResources::ROSNode::_options [protected] |