$search
#include <blob_store.h>
Public Member Functions | |
| BlobStore (const std::string &canonical_frame, const std::string &rgb_camera_frame, const std::string &db_name, const std::string &collection_namespace) | |
| bool | switchDb (SwitchDB::Request &req, SwitchDB::Response &resp) |
| Switch to using a new db. | |
| void | update (const std::vector< Blob * > &blobs, const sensor_msgs::Image &img, const sensor_msgs::CameraInfo &info) |
| Update the database with the current visible set of blobs. This will add any new blobs (based on id) and leave existing ones alone. | |
Private Types | |
| typedef mongo_ros::MessageCollection < BlobMessage > | BlobCollection |
| typedef mongo_ros::MessageCollection < sensor_msgs::Image > | ImageCollection |
Private Member Functions | |
| geometry_msgs::Pose2D | getViewpoint (const sensor_msgs::Image &img) |
| btQuaternion | headAngleAt (const ros::Time &t) |
| double | headAngularSpeed (const ros::Time &t) |
| sensor_msgs::Image::Ptr | highlightBlobInImage (const Blob &blob, const sensor_msgs::Image &img, const sensor_msgs::CameraInfo &info) |
Private Attributes | |
| const std::string | base_frame_ |
| boost::shared_ptr< BlobCollection > | blobs_ |
| image_geometry::PinholeCameraModel | cam_model_ |
| const std::string | canonical_frame_ |
| const std::string | db_name_ |
| boost::shared_ptr < ImageCollection > | images_ |
| image_transport::ImageTransport | it_ |
| const double | max_head_angular_speed_ |
| boost::mutex | mutex_ |
| ros::NodeHandle | nh_ |
| image_transport::Publisher | pub_ |
| const std::string | rgb_camera_frame_ |
| ros::ServiceServer | switch_srv_ |
| tf::TransformListener | tf_ |
Definition at line 60 of file blob_store.h.
typedef mongo_ros::MessageCollection<BlobMessage> semanticmodel::BlobStore::BlobCollection [private] |
Definition at line 114 of file blob_store.h.
typedef mongo_ros::MessageCollection<sensor_msgs::Image> semanticmodel::BlobStore::ImageCollection [private] |
Definition at line 115 of file blob_store.h.
| semanticmodel::BlobStore::BlobStore | ( | const std::string & | canonical_frame, | |
| const std::string & | rgb_camera_frame, | |||
| const std::string & | db_name, | |||
| const std::string & | collection_namespace | |||
| ) |
| gm::Pose2D semanticmodel::BlobStore::getViewpoint | ( | const sensor_msgs::Image & | img | ) | [private] |
Definition at line 373 of file blob_store.cc.
| btQuaternion semanticmodel::BlobStore::headAngleAt | ( | const ros::Time & | t | ) | [private] |
Definition at line 119 of file blob_store.cc.
| double semanticmodel::BlobStore::headAngularSpeed | ( | const ros::Time & | t | ) | [private] |
Definition at line 133 of file blob_store.cc.
| sm::Image::Ptr semanticmodel::BlobStore::highlightBlobInImage | ( | const Blob & | blob, | |
| const sensor_msgs::Image & | img, | |||
| const sensor_msgs::CameraInfo & | info | |||
| ) | [private] |
Definition at line 159 of file blob_store.cc.
| bool semanticmodel::BlobStore::switchDb | ( | SwitchDB::Request & | req, | |
| SwitchDB::Response & | resp | |||
| ) |
Switch to using a new db.
Definition at line 95 of file blob_store.cc.
| void semanticmodel::BlobStore::update | ( | const std::vector< Blob * > & | blobs, | |
| const sensor_msgs::Image & | img, | |||
| const sensor_msgs::CameraInfo & | info | |||
| ) |
Update the database with the current visible set of blobs. This will add any new blobs (based on id) and leave existing ones alone.
const std::string semanticmodel::BlobStore::base_frame_ [private] |
Definition at line 101 of file blob_store.h.
boost::shared_ptr<BlobCollection> semanticmodel::BlobStore::blobs_ [private] |
Definition at line 118 of file blob_store.h.
Definition at line 112 of file blob_store.h.
const std::string semanticmodel::BlobStore::canonical_frame_ [private] |
Definition at line 99 of file blob_store.h.
const std::string semanticmodel::BlobStore::db_name_ [private] |
Definition at line 102 of file blob_store.h.
boost::shared_ptr<ImageCollection> semanticmodel::BlobStore::images_ [private] |
Definition at line 121 of file blob_store.h.
Definition at line 107 of file blob_store.h.
const double semanticmodel::BlobStore::max_head_angular_speed_ [private] |
Definition at line 103 of file blob_store.h.
boost::mutex semanticmodel::BlobStore::mutex_ [private] |
Definition at line 105 of file blob_store.h.
ros::NodeHandle semanticmodel::BlobStore::nh_ [private] |
Definition at line 106 of file blob_store.h.
Definition at line 124 of file blob_store.h.
const std::string semanticmodel::BlobStore::rgb_camera_frame_ [private] |
Definition at line 100 of file blob_store.h.
Definition at line 127 of file blob_store.h.
Definition at line 109 of file blob_store.h.