$search
Namespaces | |
namespace | message_collection |
Classes | |
struct | DbConnectException |
Couldn't find matching message in collection. More... | |
class | MessageCollection |
struct | MessageWithMetadata |
Class that wraps (via inheritance) a ROS message type, together with additional metadata (a yaml dictionary). More... | |
class | Metadata |
Represents metadata attached to a message. Automatically includes a unique id and creation time. More... | |
class | MongoRosException |
A base class for all pose_graph exceptions; provides a handy boost::format parent constructor. More... | |
struct | NoMatchingMessageException |
Couldn't find matching message in collection. More... | |
class | Query |
Represents a query to the db. More... | |
struct | QueryResults |
A templated typedef for convenience. More... | |
class | ResultIterator |
class | WrappedBSON |
Internal parent class. More... | |
Typedefs | |
typedef auto_ptr < mongo::DBClientCursor > | Cursor |
typedef boost::shared_ptr< Cursor > | CursorPtr |
Functions | |
void | dropDatabase (const string &db_name) |
void | dropDatabase (const std::string &db) |
template<class P > | |
P | getParam (const ros::NodeHandle &nh, const string &name, const P &default_val) |
Get a parameter, with default values. | |
boost::shared_ptr < mongo::DBClientConnection > | makeDbConnection (const ros::NodeHandle &nh, const string &host="", const unsigned &port=0) |
string | messageType (mongo::DBClientConnection &conn, const string &db, const string &coll) |
std::string | messageType (mongo::DBClientConnection &conn, const std::string &db, const std::string &coll) |
Return the ROS Message type of a given collection. |
typedef auto_ptr<mongo::DBClientCursor> mongo_ros::Cursor |
Definition at line 50 of file query_results.h.
typedef boost::shared_ptr<Cursor> mongo_ros::CursorPtr |
Definition at line 51 of file query_results.h.
void mongo_ros::dropDatabase | ( | const string & | db_name | ) |
Definition at line 95 of file mongo_ros.cpp.
void mongo_ros::dropDatabase | ( | const std::string & | db | ) |
Drop a db and all its collections Uses the connection parameters given by the warehouse_host and warehouse_port ROS parameters
P mongo_ros::getParam | ( | const ros::NodeHandle & | nh, | |
const string & | name, | |||
const P & | default_val | |||
) | [inline] |
Get a parameter, with default values.
Definition at line 49 of file mongo_ros.cpp.
boost::shared_ptr< mongo::DBClientConnection > mongo_ros::makeDbConnection | ( | const ros::NodeHandle & | nh, | |
const string & | host = "" , |
|||
const unsigned & | port = 0 | |||
) |
Definition at line 58 of file mongo_ros.cpp.
string mongo_ros::messageType | ( | mongo::DBClientConnection & | conn, | |
const string & | db, | |||
const string & | coll | |||
) |
Definition at line 102 of file mongo_ros.cpp.
std::string mongo_ros::messageType | ( | mongo::DBClientConnection & | conn, | |
const std::string & | db, | |||
const std::string & | coll | |||
) |
Return the ROS Message type of a given collection.