MipResources::ROSNode Class Reference
[ROSNode]

This resource represents a ROS node and handles all the topics. More...

#include <ROSNode.h>

Inheritance diagram for MipResources::ROSNode:

MipResources::Resource MIPObject

List of all members.

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


Detailed Description

This resource represents a ROS node and handles all the topics.

Author:
Paolo Stegagno While allocating this resource, the MIP process becomes a ROS node with name "MIP_{id}", where {id} is the robot id defined in the CommonOptions. This class provides basic ROS functionalities, such as opening a topic, reading and writing on it. It is reccomended that any ROS communication in MIP is implemented through the use of this Resource.

Constructor & Destructor Documentation

MipResources::ROSNode::ROSNode ( const string &  nodeName  ) 

Node name constructor.

Parameters:
[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).

Parameters:
[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).


Member Function Documentation

ResourcePlate MipResources::ROSNode::getPlate (  )  const [inline, virtual]

Gets the plate.

Implements MipResources::Resource.

int MipResources::ROSNode::openTopic ( const string &  topicname,
ROSiFaceOpeningModes  mode,
int  queueLength = 1,
int  bufferLength = 1,
ROSiFaceMessageTypes  ty = ROSIFACE_TYPE_STD_STRING 
)

Open a topic.

Parameters:
[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.
Returns:
An int representing the number of the used topic. The user must reuse this number to read or write on the specified topic. This method opens a topic allocating a ROSiFace. THe ROSiFace can be allocated as read, write or read/write depending on the value of "mode". The name of the topic must be specified in "topicname", while the queue length is an optional parameter that can be specified in "queueLength", whose default value is 1.
The method returns an integer representing the topic specifier, and is needed to read or write on the topic.

bool MipResources::ROSNode::updateTopic ( int  topicSpecifier  ) 

Read and update a topic.

Parameters:
[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.

Parameters:
[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.

Parameters:
[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.

Parameters:
[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.

Parameters:
[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.

Parameters:
[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.

Returns:
Pointer to the topic handle
Note:
It is useful for external usage of topic with the same nodeHandle

int MipResources::ROSNode::getOpenTopicsNum (  )  const

Get the actual number of open topics.

Returns:
Return the actual number of open topics


Member Data Documentation


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

Generated on Mon Feb 20 07:01:13 2017 for MIP by  doxygen 1.5.6