#include <structs.h>

Public Member Functions | |
| void | addPose (geometry_msgs::PoseStamped pose1, geometry_msgs::PoseStamped pose2, size_t id1, size_t id2, KinematicParams ¶ms) |
| virtual PoseMap | getObservation (double timestamp) |
| std::vector< double > | intersectionOfStamps () |
| void | updateModel (size_t id1, size_t id2, KinematicParams ¶ms) |
Public Attributes | |
| std::map< int, double > | latestTimestamp |
| std::map< int, std::map < double, articulation_structure::PoseStampedIdMsgConstPtr > > | markerStamped |
| std::map< int, std::map< int, articulation_models::GenericModelPtr > > | models |
| std::map< int, std::map< int, std::vector < articulation_models::GenericModelPtr > > > | models_all |
| PoseIndex | poseIndex |
| std::map< double, std::map < int, articulation_structure::PoseStampedIdMsgConstPtr > > | stampedMarker |
| std::map< double, std::map < int, articulation_structure::PoseStampedIdMsgConstPtr > > | stampedMarkerProjected |
| std::map< int, std::map< int, articulation_msgs::TrackMsgPtr > > | trajectories |
| void KinematicData::addPose | ( | geometry_msgs::PoseStamped | pose1, |
| geometry_msgs::PoseStamped | pose2, | ||
| size_t | id1, | ||
| size_t | id2, | ||
| KinematicParams & | params | ||
| ) |
Definition at line 58 of file structs.cpp.
| PoseMap KinematicData::getObservation | ( | double | timestamp | ) | [virtual] |
Definition at line 174 of file structs.cpp.
| std::vector< double > KinematicData::intersectionOfStamps | ( | ) |
Definition at line 151 of file structs.cpp.
| void KinematicData::updateModel | ( | size_t | id1, |
| size_t | id2, | ||
| KinematicParams & | params | ||
| ) |
Definition at line 95 of file structs.cpp.
| std::map<int, double > KinematicData::latestTimestamp |
| std::map<int, std::map<double, articulation_structure::PoseStampedIdMsgConstPtr> > KinematicData::markerStamped |
| std::map< int, std::map<int,articulation_models::GenericModelPtr> > KinematicData::models |
| std::map< int, std::map<int,std::vector<articulation_models::GenericModelPtr> > > KinematicData::models_all |
| std::map<double, std::map<int, articulation_structure::PoseStampedIdMsgConstPtr> > KinematicData::stampedMarker |
| std::map<double, std::map<int, articulation_structure::PoseStampedIdMsgConstPtr> > KinematicData::stampedMarkerProjected |
| std::map< int, std::map<int,articulation_msgs::TrackMsgPtr> > KinematicData::trajectories |