Classes | |
| class | BufferCore |
| A Class which provides coordinate transforms between any two frames in a system. More... | |
| struct | CanTransformAccum |
| class | ConnectivityException |
| An exception class to notify of no connection. More... | |
| class | ExtrapolationException |
| An exception class to notify that the requested value would have required extrapolation beyond current limits. More... | |
| class | InvalidArgumentException |
| An exception class to notify that one of the arguments is invalid. More... | |
| class | LookupException |
| An exception class to notify of bad frame number. More... | |
| class | Stamped |
| The data type which will be cross compatable with geometry_msgs This is the tf2 datatype equivilant of a MessageStamped. More... | |
| class | StaticCache |
| struct | TimeAndFrameIDFrameComparator |
| class | TimeCache |
| A class to keep a sorted linked list in time This builds and maintains a list of timestamped data. And provides lookup functions to get data out as a function of time. More... | |
| class | TimeCacheInterface |
| class | TimeoutException |
| An exception class to notify that a timeout has occured. More... | |
| struct | TransformAccum |
| class | TransformException |
| A base class for all tf2 exceptions This inherits from ros::exception which inherits from std::runtime_exception. More... | |
| class | TransformStorage |
| Storage for transforms and their parent. More... | |
Typedefs | |
| typedef uint32_t | CompactFrameID |
| typedef std::pair< ros::Time, CompactFrameID > | P_TimeAndFrameID |
| typedef uint32_t | TransformableCallbackHandle |
| typedef uint64_t | TransformableRequestHandle |
Enumerations | |
| enum | TransformableResult { TransformAvailable, TransformFailure } |
| enum | WalkEnding { Identity, TargetParentOfSource, SourceParentOfTarget, FullPath } |
Functions | |
| template<typename T > | |
| bool | operator== (const Stamped< T > &a, const Stamped< T > &b) |
| Comparison Operator for Stamped datatypes. | |
| void | setIdentity (geometry_msgs::Transform &tx) |
| bool | startsWithSlash (const std::string &frame_id) |
| std::string | stripSlash (const std::string &in) |
| void | transformMsgToTF2 (const geometry_msgs::Transform &msg, btTransform &bt) |
| convert Transform msg to Transform | |
| void | transformTF2ToMsg (const btQuaternion &orient, const btVector3 &pos, geometry_msgs::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id) |
| void | transformTF2ToMsg (const btQuaternion &orient, const btVector3 &pos, geometry_msgs::Transform &msg) |
| void | transformTF2ToMsg (const btTransform &bt, geometry_msgs::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id) |
| convert Transform to Transform msg | |
| void | transformTF2ToMsg (const btTransform &bt, geometry_msgs::Transform &msg) |
| convert Transform to Transform msg | |
| typedef uint32_t tf2::CompactFrameID |
Definition at line 50 of file transform_storage.h.
| typedef std::pair< ros::Time, CompactFrameID > tf2::P_TimeAndFrameID |
Definition at line 46 of file buffer_core.h.
| typedef uint32_t tf2::TransformableCallbackHandle |
Definition at line 47 of file buffer_core.h.
| typedef uint64_t tf2::TransformableRequestHandle |
Definition at line 48 of file buffer_core.h.
Definition at line 52 of file buffer_core.h.
| enum tf2::WalkEnding |
Definition at line 280 of file buffer_core.cpp.
| bool tf2::operator== | ( | const Stamped< T > & | a, | |
| const Stamped< T > & | b | |||
| ) | [inline] |
Comparison Operator for Stamped datatypes.
Definition at line 68 of file transform_datatypes.h.
| void tf2::setIdentity | ( | geometry_msgs::Transform & | tx | ) |
Definition at line 87 of file buffer_core.cpp.
| bool tf2::startsWithSlash | ( | const std::string & | frame_id | ) |
Definition at line 98 of file buffer_core.cpp.
| std::string tf2::stripSlash | ( | const std::string & | in | ) |
Definition at line 106 of file buffer_core.cpp.
| void tf2::transformMsgToTF2 | ( | const geometry_msgs::Transform & | msg, | |
| btTransform & | bt | |||
| ) |
convert Transform msg to Transform
Definition at line 44 of file buffer_core.cpp.
| void tf2::transformTF2ToMsg | ( | const btQuaternion & | orient, | |
| const btVector3 & | pos, | |||
| geometry_msgs::TransformStamped & | msg, | |||
| ros::Time | stamp, | |||
| const std::string & | frame_id, | |||
| const std::string & | child_frame_id | |||
| ) |
Definition at line 79 of file buffer_core.cpp.
| void tf2::transformTF2ToMsg | ( | const btQuaternion & | orient, | |
| const btVector3 & | pos, | |||
| geometry_msgs::Transform & | msg | |||
| ) |
Definition at line 68 of file buffer_core.cpp.
| void tf2::transformTF2ToMsg | ( | const btTransform & | bt, | |
| geometry_msgs::TransformStamped & | msg, | |||
| ros::Time | stamp, | |||
| const std::string & | frame_id, | |||
| const std::string & | child_frame_id | |||
| ) |
convert Transform to Transform msg
Definition at line 60 of file buffer_core.cpp.
| void tf2::transformTF2ToMsg | ( | const btTransform & | bt, | |
| geometry_msgs::Transform & | msg | |||
| ) |
convert Transform to Transform msg
Definition at line 48 of file buffer_core.cpp.