Abstract ROS node extension for use with common worldlib clients. More...
#include <Node.h>
Public Member Functions | |
Node () | |
Create a new Node. | |
bool | okay () const |
A check for a valid Node. | |
Protected Member Functions | |
InteractiveWorldModelClient * | createInteractiveWorldModelClient (const bool verbose=true) const |
Create a new InteractiveWorldModelClient. | |
SpatialWorldClient * | createSpatialWorldClient (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_ |
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.
Node::Node | ( | ) |
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.
verbose | If client connection information should be printed to ROS_INFO. |
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.
verbose | If client connection information should be printed to ROS_INFO. |
bool Node::loadWorldYamlFile | ( | const bool | verbose = true | ) | [protected] |
bool Node::okay | ( | ) | const |
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.
pose | The Pose to transform. |
pose_frame_id | The frame ID that the Pose is in. |
bool rail::spatial_temporal_learning::worldlib::remote::Node::okay_ [protected] |