Public Member Functions | Protected Member Functions | Protected Attributes
rail::spatial_temporal_learning::worldlib::remote::Node Class Reference

Abstract ROS node extension for use with common worldlib clients. More...

#include <Node.h>

List of all members.

Public Member Functions

 Node ()
 Create a new Node.
bool okay () const
 A check for a valid Node.

Protected Member Functions

InteractiveWorldModelClientcreateInteractiveWorldModelClient (const bool verbose=true) const
 Create a new InteractiveWorldModelClient.
SpatialWorldClientcreateSpatialWorldClient (const bool verbose=true) const
 Create a new SpatialWorldClient.
bool loadWorldYamlFile (const bool verbose=true)
 Load world configuration data from a YAML file.
geometry::Pose transformToWorld (const geometry::Pose &pose, const std::string &pose_frame_id) const
 Transform the given Pose into the World frame.

Protected Attributes

ros::NodeHandle node_
bool okay_
ros::NodeHandle private_node_
tf2_ros::TransformListener tf_listener_
tf2_ros::Buffer tfs_
worldlib::world::World world_

Detailed Description

Abstract ROS node extension for use with common worldlib clients.

A worldlib node includes common functionality that is useful for use with the worldlib such as setting up clients based on global parameters.

Definition at line 40 of file Node.h.


Constructor & Destructor Documentation

Create a new Node.

Create a new Node which creates both a public and private ROS node handle.

Definition at line 22 of file Node.cpp.


Member Function Documentation

InteractiveWorldModelClient * Node::createInteractiveWorldModelClient ( const bool  verbose = true) const [protected]

Create a new InteractiveWorldModelClient.

Create a new InteractiveWorldModelClient by pulling connection parameters from the ROS parameter server.

Parameters:
verboseIf client connection information should be printed to ROS_INFO.
Returns:
A pointer to a new InteractiveWorldModelClient.

Definition at line 40 of file Node.cpp.

SpatialWorldClient * Node::createSpatialWorldClient ( const bool  verbose = true) const [protected]

Create a new SpatialWorldClient.

Create a new SpatialWorldClient by pulling connection parameters from the ROS parameter server.

Parameters:
verboseIf client connection information should be printed to ROS_INFO.
Returns:
A pointer to a new SpatialWorldClient.

Definition at line 62 of file Node.cpp.

bool Node::loadWorldYamlFile ( const bool  verbose = true) [protected]

Load world configuration data from a YAML file.

Loads world configuration data from a YML file by pulling parameters from the ROS parameter server.

Parameters:
verboseIf parameter information should be printed to ROS_INFO.
Returns:
If the load was successful.

Definition at line 27 of file Node.cpp.

bool Node::okay ( ) const

A check for a valid Node.

This function will return true if the appropriate connections were created successfully during initialization.

Returns:
True if the appropriate connections were created successfully during initialization.

Definition at line 92 of file Node.cpp.

Pose Node::transformToWorld ( const geometry::Pose pose,
const std::string &  pose_frame_id 
) const [protected]

Transform the given Pose into the World frame.

Transform the given Pose into the World frame based on TF data from the TF buffer.

Parameters:
poseThe Pose to transform.
pose_frame_idThe frame ID that the Pose is in.
Returns:
The Pose in respect to the World fixed frame.

Definition at line 97 of file Node.cpp.


Member Data Documentation

The public and private ROS node handles.

Definition at line 106 of file Node.h.

The okay check flag.

Definition at line 102 of file Node.h.

Definition at line 106 of file Node.h.

TF client.

Definition at line 110 of file Node.h.

TF lookup buffer.

Definition at line 108 of file Node.h.

The world configuration.

Definition at line 104 of file Node.h.


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


worldlib
Author(s): Russell Toris
autogenerated on Fri Feb 12 2016 00:24:19