#include "ensenso_camera/ros2/namespace.h"
#include "ensenso_camera/ros2/time.h"
#include "ensenso_camera/ros2/geometry_msgs/pose.h"
#include "ensenso_camera/ros2/geometry_msgs/pose_stamped.h"
#include "ensenso_camera/ros2/geometry_msgs/transform.h"
#include "ensenso_camera/ros2/geometry_msgs/transform_stamped.h"
#include "ensenso_camera/ros2/tf2_geometry_msgs/tf2_geometry_msgs.h"
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/buffer.h>
#include <string>
#include "nxLib.h"
Go to the source code of this file.
Namespaces | |
tf2 | |
Typedefs | |
using | PoseMsg = geometry_msgs::msg::Pose |
using | StampedPoseMsg = geometry_msgs::msg::PoseStamped |
using | StampedTransformMsg = geometry_msgs::msg::TransformStamped |
using | Transform = tf2::Transform |
using | TransformMsg = geometry_msgs::msg::Transform |
Functions | |
void | tf2::convertMsg (PoseMsg const &pose, TransformMsg &transform) |
void | tf2::convertMsg (StampedPoseMsg const &pose, StampedTransformMsg &transform) |
void | tf2::convertMsg (StampedTransformMsg const &transform, StampedPoseMsg &pose) |
void | tf2::convertMsg (TransformMsg const &transform, PoseMsg &pose) |
Transform | fromMsg (PoseMsg const &pose) |
Transform | fromMsg (StampedPoseMsg const &pose) |
Transform | fromMsg (StampedTransformMsg const &transform) |
Transform | fromMsg (TransformMsg const &transform) |
StampedTransformMsg | fromTf (Transform const &transform, std::string parentFrame, std::string childFrame, ensenso::ros::Time timestamp) |
Transform | getLatestTransform (tf2_ros::Buffer const &tfBuffer, std::string const &cameraFrame, std::string const &targetFrame) |
bool | isIdentity (Transform const &transform) |
bool | isValid (Transform const &transform) |
bool | isValid (TransformMsg const &transform) |
StampedPoseMsg | poseFromTransform (StampedTransformMsg const &transform) |
PoseMsg | poseFromTransform (Transform const &transform) |
StampedPoseMsg | stampedPoseFromNxLib (NxLibItem const &node, std::string const &parentFrame, ensenso::ros::Time timestamp) |
Transform | transformFromNxLib (NxLibItem const &node) |
StampedTransformMsg | transformFromPose (StampedPoseMsg const &pose, std::string const &childFrame) |
void | writeTransformToNxLib (Transform const &transform, NxLibItem const &node) |
using PoseMsg = geometry_msgs::msg::Pose |
Definition at line 24 of file pose_utilities.h.
using StampedPoseMsg = geometry_msgs::msg::PoseStamped |
Definition at line 25 of file pose_utilities.h.
using StampedTransformMsg = geometry_msgs::msg::TransformStamped |
Definition at line 23 of file pose_utilities.h.
using Transform = tf2::Transform |
Definition at line 21 of file pose_utilities.h.
Definition at line 22 of file pose_utilities.h.
Create a tf transform from a pose msg.
Definition at line 217 of file pose_utilities.cpp.
Transform fromMsg | ( | StampedPoseMsg const & | pose | ) |
Create a tf transform from a stamped pose msg.
Definition at line 198 of file pose_utilities.cpp.
Transform fromMsg | ( | StampedTransformMsg const & | transform | ) |
Create a tf transform from a stamped transform msg.
Definition at line 190 of file pose_utilities.cpp.
Transform fromMsg | ( | TransformMsg const & | transform | ) |
Create a tf transform from a transform msg.
Definition at line 209 of file pose_utilities.cpp.
StampedTransformMsg fromTf | ( | Transform const & | transform, |
std::string | parentFrame, | ||
std::string | childFrame, | ||
ensenso::ros::Time | timestamp | ||
) |
Create a stamped geometry transform from a tf transform in combination with parent and child frame.
Definition at line 239 of file pose_utilities.cpp.
Transform getLatestTransform | ( | tf2_ros::Buffer const & | tfBuffer, |
std::string const & | cameraFrame, | ||
std::string const & | targetFrame | ||
) |
Return the latest transform from the given buffer. Returns an uninitialized tf transform if the lookup throws and prints a warning.
Definition at line 251 of file pose_utilities.cpp.
bool isIdentity | ( | Transform const & | transform | ) |
Check whether the given tf transform is an identity transformation.
Definition at line 55 of file pose_utilities.cpp.
bool isValid | ( | Transform const & | transform | ) |
Check whether the given transform is valid, i.e. not containing NaNs.
An invalid transform is e.g. produced by converting an uninitialized transform msg to a tf transform.
Definition at line 32 of file pose_utilities.cpp.
bool isValid | ( | TransformMsg const & | transform | ) |
Definition at line 50 of file pose_utilities.cpp.
StampedPoseMsg poseFromTransform | ( | StampedTransformMsg const & | transform | ) |
Convert a stamped transform msg to a stamped pose msg, where the pose has the same rotation and translation as the transform.
Definition at line 182 of file pose_utilities.cpp.
Convert a tf transform to a pose msg.
Definition at line 228 of file pose_utilities.cpp.
StampedPoseMsg stampedPoseFromNxLib | ( | NxLibItem const & | node, |
std::string const & | parentFrame, | ||
ensenso::ros::Time | timestamp | ||
) |
Create a stamped pose msg from the given link described in the node.
Definition at line 159 of file pose_utilities.cpp.
Transform transformFromNxLib | ( | NxLibItem const & | node | ) |
Convert the given NxLib transformation node to a tf transform.
Definition at line 144 of file pose_utilities.cpp.
StampedTransformMsg transformFromPose | ( | StampedPoseMsg const & | pose, |
std::string const & | childFrame | ||
) |
Convert a stamped pose msg to a stamped transform msg that defines the child frame at the position of the given pose.
Definition at line 173 of file pose_utilities.cpp.
void writeTransformToNxLib | ( | Transform const & | transform, |
NxLibItem const & | node | ||
) |
Convert the given tf transform to an NxLib transformation and write it into the given NxLib node.
Definition at line 70 of file pose_utilities.cpp.