Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
moveit_warehouse::TrajectoryConstraintsStorage Class Reference

#include <trajectory_constraints_storage.h>

Inheritance diagram for moveit_warehouse::TrajectoryConstraintsStorage:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void addTrajectoryConstraints (const moveit_msgs::TrajectoryConstraints &msg, const std::string &name, const std::string &robot="", const std::string &group="")
void getKnownTrajectoryConstraints (std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
void getKnownTrajectoryConstraints (const std::string &regex, std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
bool getTrajectoryConstraints (TrajectoryConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
 Get the constraints named name. Return false on failure.
bool hasTrajectoryConstraints (const std::string &name, const std::string &robot="", const std::string &group="") const
void removeTrajectoryConstraints (const std::string &name, const std::string &robot="", const std::string &group="")
void renameTrajectoryConstraints (const std::string &old_name, const std::string &new_name, const std::string &robot="", const std::string &group="")
void reset (void)
 TrajectoryConstraintsStorage (const std::string &host="", const unsigned int port=0, double wait_seconds=5.0)
 Initialize the trajectory constraints storage to connect to a specified host and port for the MongoDB. If defaults are used for the parameters (empty host name, 0 port), the constructor looks for ROS params specifying which host/port to use. NodeHandle::searchParam() is used starting from ~ to look for warehouse_port and warehouse_host. If no values are found, the defaults are left to be the ones MongoDB uses. If wait_seconds is above 0, then a maximum number of seconds can elapse until connection is successful, or a runtime exception is thrown.

Static Public Attributes

static const std::string CONSTRAINTS_GROUP_NAME = "group_id"
static const std::string CONSTRAINTS_ID_NAME = "constraints_id"
static const std::string DATABASE_NAME = "moveit_trajectory_constraints"
static const std::string ROBOT_NAME = "robot_id"

Private Member Functions

void createCollections (void)

Private Attributes

TrajectoryConstraintsCollection constraints_collection_

Detailed Description

Definition at line 49 of file trajectory_constraints_storage.h.


Constructor & Destructor Documentation

moveit_warehouse::TrajectoryConstraintsStorage::TrajectoryConstraintsStorage ( const std::string &  host = "",
const unsigned int  port = 0,
double  wait_seconds = 5.0 
)

Initialize the trajectory constraints storage to connect to a specified host and port for the MongoDB. If defaults are used for the parameters (empty host name, 0 port), the constructor looks for ROS params specifying which host/port to use. NodeHandle::searchParam() is used starting from ~ to look for warehouse_port and warehouse_host. If no values are found, the defaults are left to be the ones MongoDB uses. If wait_seconds is above 0, then a maximum number of seconds can elapse until connection is successful, or a runtime exception is thrown.

Definition at line 45 of file trajectory_constraints_storage.cpp.


Member Function Documentation

void moveit_warehouse::TrajectoryConstraintsStorage::addTrajectoryConstraints ( const moveit_msgs::TrajectoryConstraints &  msg,
const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
)

Definition at line 64 of file trajectory_constraints_storage.cpp.

Definition at line 52 of file trajectory_constraints_storage.cpp.

void moveit_warehouse::TrajectoryConstraintsStorage::getKnownTrajectoryConstraints ( std::vector< std::string > &  names,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Definition at line 97 of file trajectory_constraints_storage.cpp.

void moveit_warehouse::TrajectoryConstraintsStorage::getKnownTrajectoryConstraints ( const std::string &  regex,
std::vector< std::string > &  names,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Definition at line 91 of file trajectory_constraints_storage.cpp.

bool moveit_warehouse::TrajectoryConstraintsStorage::getTrajectoryConstraints ( TrajectoryConstraintsWithMetadata msg_m,
const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Get the constraints named name. Return false on failure.

Definition at line 111 of file trajectory_constraints_storage.cpp.

bool moveit_warehouse::TrajectoryConstraintsStorage::hasTrajectoryConstraints ( const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Definition at line 79 of file trajectory_constraints_storage.cpp.

void moveit_warehouse::TrajectoryConstraintsStorage::removeTrajectoryConstraints ( const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
)

Definition at line 140 of file trajectory_constraints_storage.cpp.

void moveit_warehouse::TrajectoryConstraintsStorage::renameTrajectoryConstraints ( const std::string &  old_name,
const std::string &  new_name,
const std::string &  robot = "",
const std::string &  group = "" 
)

Definition at line 128 of file trajectory_constraints_storage.cpp.

Definition at line 57 of file trajectory_constraints_storage.cpp.


Member Data Documentation

Definition at line 85 of file trajectory_constraints_storage.h.

Definition at line 56 of file trajectory_constraints_storage.h.

const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_ID_NAME = "constraints_id" [static]

Definition at line 55 of file trajectory_constraints_storage.h.

const std::string moveit_warehouse::TrajectoryConstraintsStorage::DATABASE_NAME = "moveit_trajectory_constraints" [static]

Definition at line 53 of file trajectory_constraints_storage.h.

const std::string moveit_warehouse::TrajectoryConstraintsStorage::ROBOT_NAME = "robot_id" [static]

Definition at line 57 of file trajectory_constraints_storage.h.


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


warehouse
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:32:09