#include <Object.h>
Public Types | |
| typedef boost::shared_ptr < Object const > | ConstPtr |
| typedef worldmodel_msgs::ObjectState::_state_type | StateType |
Public Member Functions | |
| void | addSupport (float support) |
| const std::string & | getClassId () const |
| const Eigen::Matrix3f & | getCovariance () const |
| void | getCovariance (geometry_msgs::PoseWithCovariance::_covariance_type &covariance) const |
| std_msgs::Header | getHeader () const |
| void | getMessage (worldmodel_msgs::Object &object) const |
| worldmodel_msgs::Object | getMessage () const |
| const std::string & | getName () const |
| const std::string & | getObjectId () const |
| const Eigen::Quaternionf & | getOrientation () const |
| void | getPose (geometry_msgs::Pose &pose) const |
| void | getPose (tf::Pose &pose) const |
| void | getPoseWithCovariance (geometry_msgs::PoseWithCovariance &pose) const |
| const Eigen::Vector3f & | getPosition () const |
| ros::Time | getStamp () const |
| StateType | getState () const |
| float | getSupport () const |
| void | getVisualization (visualization_msgs::MarkerArray &markers) const |
| void | intersect (const Eigen::Vector3f &position, const Eigen::Matrix3f &covariance, float support) |
| Object (const std::string class_id="", const std::string object_id="") | |
| Object (const worldmodel_msgs::Object &other) | |
| Object & | operator= (const worldmodel_msgs::Object &other) |
| void | setCovariance (const Eigen::Matrix3f &covariance) |
| void | setCovariance (const tf::Matrix3x3 &covariance) |
| void | setCovariance (const geometry_msgs::PoseWithCovariance::_covariance_type &covariance) |
| void | setHeader (const std_msgs::Header &header) |
| void | setName (const std::string &name) |
| void | setObjectId (const std::string &object_id) |
| void | setOrientation (const geometry_msgs::Quaternion &orientation) |
| void | setOrientation (const tf::Quaternion &orientation) |
| void | setPose (const geometry_msgs::PoseWithCovariance &pose) |
| void | setPose (const geometry_msgs::Pose &pose) |
| void | setPose (const tf::Pose &pose) |
| void | setPosition (const Eigen::Vector3f &position) |
| void | setPosition (const geometry_msgs::Point &position) |
| void | setPosition (const tf::Point &point) |
| void | setState (const StateType &state) |
| void | setSupport (float support) |
| ObjectPtr | transform (tf::Transformer &tf, const std::string &target_frame) const |
| ObjectPtr | transform (tf::Transformer &tf, const std::string &target_frame, const ros::Time &target_time) const |
| void | update (const Eigen::Vector3f &position, const Eigen::Matrix3f &covariance, float support) |
| virtual | ~Object () |
Static Public Member Functions | |
| static void | reset () |
| static void | setNamespace (const std::string &ns) |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr < Object > | Ptr |
Private Attributes | |
| Eigen::Matrix3f | covariance |
| std_msgs::Header | header |
| ObjectInfo | info |
| ros::NodeHandle | nh |
| Eigen::Quaternionf | orientation |
| Eigen::Vector3f | position |
| ObjectState | state |
Static Private Attributes | |
| static std::map< std::string, unsigned int > | object_count |
| static std::string | object_namespace |
| typedef boost::shared_ptr<Object const> hector_object_tracker::Object::ConstPtr |
| hector_object_tracker::Object::Object | ( | const std::string | class_id = "", |
| const std::string | object_id = "" |
||
| ) |
Definition at line 13 of file Object.cpp.
| hector_object_tracker::Object::Object | ( | const worldmodel_msgs::Object & | other | ) |
Definition at line 30 of file Object.cpp.
| hector_object_tracker::Object::~Object | ( | ) | [virtual] |
Definition at line 34 of file Object.cpp.
| void hector_object_tracker::Object::addSupport | ( | float | support | ) | [inline] |
| const std::string& hector_object_tracker::Object::getClassId | ( | ) | const [inline] |
| const Eigen::Matrix3f & hector_object_tracker::Object::getCovariance | ( | ) | const |
Definition at line 127 of file Object.cpp.
| void hector_object_tracker::Object::getCovariance | ( | geometry_msgs::PoseWithCovariance::_covariance_type & | covariance | ) | const |
Definition at line 131 of file Object.cpp.
| std_msgs::Header hector_object_tracker::Object::getHeader | ( | ) | const [inline] |
| void hector_object_tracker::Object::getMessage | ( | worldmodel_msgs::Object & | object | ) | const |
Definition at line 41 of file Object.cpp.
Definition at line 48 of file Object.cpp.
| const std::string& hector_object_tracker::Object::getName | ( | ) | const [inline] |
| const std::string& hector_object_tracker::Object::getObjectId | ( | ) | const [inline] |
| const Eigen::Quaternionf & hector_object_tracker::Object::getOrientation | ( | ) | const |
Definition at line 112 of file Object.cpp.
| void hector_object_tracker::Object::getPose | ( | geometry_msgs::Pose & | pose | ) | const |
Definition at line 64 of file Object.cpp.
| void hector_object_tracker::Object::getPose | ( | tf::Pose & | pose | ) | const |
| void hector_object_tracker::Object::getPoseWithCovariance | ( | geometry_msgs::PoseWithCovariance & | pose | ) | const |
Definition at line 54 of file Object.cpp.
| const Eigen::Vector3f & hector_object_tracker::Object::getPosition | ( | ) | const |
Definition at line 95 of file Object.cpp.
| ros::Time hector_object_tracker::Object::getStamp | ( | ) | const [inline] |
| StateType hector_object_tracker::Object::getState | ( | ) | const [inline] |
| float hector_object_tracker::Object::getSupport | ( | ) | const [inline] |
| void hector_object_tracker::Object::getVisualization | ( | visualization_msgs::MarkerArray & | markers | ) | const |
Definition at line 192 of file Object.cpp.
| void hector_object_tracker::Object::intersect | ( | const Eigen::Vector3f & | position, |
| const Eigen::Matrix3f & | covariance, | ||
| float | support | ||
| ) |
Definition at line 165 of file Object.cpp.
| Object & hector_object_tracker::Object::operator= | ( | const worldmodel_msgs::Object & | other | ) |
Definition at line 255 of file Object.cpp.
| void hector_object_tracker::Object::reset | ( | ) | [static] |
Definition at line 37 of file Object.cpp.
| void hector_object_tracker::Object::setCovariance | ( | const Eigen::Matrix3f & | covariance | ) |
Definition at line 143 of file Object.cpp.
| void hector_object_tracker::Object::setCovariance | ( | const tf::Matrix3x3 & | covariance | ) |
Definition at line 147 of file Object.cpp.
| void hector_object_tracker::Object::setCovariance | ( | const geometry_msgs::PoseWithCovariance::_covariance_type & | covariance | ) |
Definition at line 153 of file Object.cpp.
| void hector_object_tracker::Object::setHeader | ( | const std_msgs::Header & | header | ) | [inline] |
| void hector_object_tracker::Object::setName | ( | const std::string & | name | ) | [inline] |
| void hector_object_tracker::Object::setNamespace | ( | const std::string & | ns | ) | [static] |
Definition at line 251 of file Object.cpp.
| void hector_object_tracker::Object::setObjectId | ( | const std::string & | object_id | ) | [inline] |
| void hector_object_tracker::Object::setOrientation | ( | const geometry_msgs::Quaternion & | orientation | ) |
Definition at line 117 of file Object.cpp.
| void hector_object_tracker::Object::setOrientation | ( | const tf::Quaternion & | orientation | ) |
Definition at line 122 of file Object.cpp.
| void hector_object_tracker::Object::setPose | ( | const geometry_msgs::PoseWithCovariance & | pose | ) |
Definition at line 59 of file Object.cpp.
| void hector_object_tracker::Object::setPose | ( | const geometry_msgs::Pose & | pose | ) |
Definition at line 81 of file Object.cpp.
| void hector_object_tracker::Object::setPose | ( | const tf::Pose & | pose | ) |
| void hector_object_tracker::Object::setPosition | ( | const Eigen::Vector3f & | position | ) |
Definition at line 99 of file Object.cpp.
| void hector_object_tracker::Object::setPosition | ( | const geometry_msgs::Point & | position | ) |
Definition at line 103 of file Object.cpp.
| void hector_object_tracker::Object::setPosition | ( | const tf::Point & | point | ) |
| void hector_object_tracker::Object::setState | ( | const StateType & | state | ) |
Definition at line 159 of file Object.cpp.
| void hector_object_tracker::Object::setSupport | ( | float | support | ) | [inline] |
| ObjectPtr hector_object_tracker::Object::transform | ( | tf::Transformer & | tf, |
| const std::string & | target_frame | ||
| ) | const |
Definition at line 263 of file Object.cpp.
| ObjectPtr hector_object_tracker::Object::transform | ( | tf::Transformer & | tf, |
| const std::string & | target_frame, | ||
| const ros::Time & | target_time | ||
| ) | const |
Definition at line 268 of file Object.cpp.
| void hector_object_tracker::Object::update | ( | const Eigen::Vector3f & | position, |
| const Eigen::Matrix3f & | covariance, | ||
| float | support | ||
| ) |
Definition at line 180 of file Object.cpp.
Eigen::Matrix3f hector_object_tracker::Object::covariance [private] |
std::map< std::string, unsigned int > hector_object_tracker::Object::object_count [static, private] |
std::string hector_object_tracker::Object::object_namespace [static, private] |
Eigen::Quaternionf hector_object_tracker::Object::orientation [private] |
Eigen::Vector3f hector_object_tracker::Object::position [private] |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr<Object> hector_object_tracker::Object::Ptr |