#include <ObjectModel.h>
|
ObjectPtr | add (const std::string &class_id="", const std::string &object_id="") |
|
ObjectPtr | add (ObjectPtr object) |
|
iterator | begin () |
|
const_iterator | begin () const |
|
ObjectPtr | create (const std::string &class_id="", const std::string &object_id="") |
|
iterator | end () |
|
const_iterator | end () const |
|
float | getBestCorrespondence (ObjectPtr &object, const tf::Pose &pose, const Eigen::Matrix3f &covariance, const std::string &class_id, const std::string &name, float max_distance=0.0) const |
|
std_msgs::Header | getHeader () const |
|
void | getMessage (hector_worldmodel_msgs::ObjectModel &model) const |
|
hector_worldmodel_msgs::ObjectModelPtr | getMessage () const |
|
ObjectPtr | getObject (const std::string &object_id) const |
|
ObjectList | getObjects () const |
|
ObjectList | getObjects (const std::string &class_id) const |
|
void | getVisualization (visualization_msgs::MarkerArray &markers) const |
|
void | lock () const |
|
void | merge (const ObjectPtr &other, tf::TransformListener &tf, const std::string &prefix=std::string()) |
|
void | mergeWith (const ObjectModel &other, tf::TransformListener &tf, const std::string &prefix=std::string()) |
|
| ObjectModel (const std::string &frame_id=std::string()) |
|
| ObjectModel (const ObjectModel &) |
|
ObjectModel & | operator= (const ObjectModel &other) |
|
ObjectModel & | operator= (const hector_worldmodel_msgs::ObjectModel &other) |
|
void | remove (ObjectPtr object) |
|
void | remove (iterator it) |
|
void | reset () |
|
void | setFrameId (const std::string &frame_id) |
|
bool | try_lock () const |
|
void | unlock () const |
|
virtual | ~ObjectModel () |
|
Definition at line 19 of file ObjectModel.h.
hector_object_tracker::ObjectModel::ObjectModel |
( |
const std::string & |
frame_id = std::string() | ) |
|
hector_object_tracker::ObjectModel::ObjectModel |
( |
const ObjectModel & |
other | ) |
|
hector_object_tracker::ObjectModel::~ObjectModel |
( |
| ) |
|
|
virtual |
ObjectPtr hector_object_tracker::ObjectModel::add |
( |
const std::string & |
class_id = "" , |
|
|
const std::string & |
object_id = "" |
|
) |
| |
iterator hector_object_tracker::ObjectModel::begin |
( |
| ) |
|
|
inline |
ObjectPtr hector_object_tracker::ObjectModel::create |
( |
const std::string & |
class_id = "" , |
|
|
const std::string & |
object_id = "" |
|
) |
| |
iterator hector_object_tracker::ObjectModel::end |
( |
| ) |
|
|
inline |
float hector_object_tracker::ObjectModel::getBestCorrespondence |
( |
ObjectPtr & |
object, |
|
|
const tf::Pose & |
pose, |
|
|
const Eigen::Matrix3f & |
covariance, |
|
|
const std::string & |
class_id, |
|
|
const std::string & |
name, |
|
|
float |
max_distance = 0.0 |
|
) |
| const |
void hector_object_tracker::ObjectModel::getMessage |
( |
hector_worldmodel_msgs::ObjectModel & |
model | ) |
const |
hector_worldmodel_msgs::ObjectModelPtr hector_object_tracker::ObjectModel::getMessage |
( |
| ) |
const |
ObjectPtr hector_object_tracker::ObjectModel::getObject |
( |
const std::string & |
object_id | ) |
const |
ObjectList hector_object_tracker::ObjectModel::getObjects |
( |
| ) |
const |
ObjectList hector_object_tracker::ObjectModel::getObjects |
( |
const std::string & |
class_id | ) |
const |
void hector_object_tracker::ObjectModel::getVisualization |
( |
visualization_msgs::MarkerArray & |
markers | ) |
const |
void hector_object_tracker::ObjectModel::lock |
( |
| ) |
const |
|
inline |
ObjectModel & hector_object_tracker::ObjectModel::operator= |
( |
const hector_worldmodel_msgs::ObjectModel & |
other | ) |
|
void hector_object_tracker::ObjectModel::remove |
( |
ObjectPtr |
object | ) |
|
void hector_object_tracker::ObjectModel::remove |
( |
iterator |
it | ) |
|
void hector_object_tracker::ObjectModel::reset |
( |
| ) |
|
void hector_object_tracker::ObjectModel::setFrameId |
( |
const std::string & |
frame_id | ) |
|
bool hector_object_tracker::ObjectModel::try_lock |
( |
| ) |
const |
|
inline |
void hector_object_tracker::ObjectModel::unlock |
( |
| ) |
const |
|
inline |
ObjectList hector_object_tracker::ObjectModel::objects |
|
private |
boost::recursive_mutex hector_object_tracker::ObjectModel::objectsMutex |
|
mutableprivate |
The documentation for this class was generated from the following files: