pose_utilities.h
Go to the documentation of this file.
1 #pragma once
2 
4 #include <geometry_msgs/PoseStamped.h>
5 #include <string>
6 
7 #include "nxLib.h"
8 
16 bool poseIsValid(tf::Pose const& transform);
17 
22 void writePoseToNxLib(tf::Pose const& pose, NxLibItem const& node);
23 
27 tf::Pose poseFromNxLib(NxLibItem const& node);
28 tf::Stamped<tf::Pose> poseFromNxLib(NxLibItem const& node, ros::Time const& timestamp, std::string const& frame);
29 
34 tf::StampedTransform transformFromPose(geometry_msgs::PoseStamped const& pose, std::string const& childFrame);
void writePoseToNxLib(tf::Pose const &pose, NxLibItem const &node)
bool poseIsValid(tf::Pose const &transform)
tf::StampedTransform transformFromPose(geometry_msgs::PoseStamped const &pose, std::string const &childFrame)
tf::Pose poseFromNxLib(NxLibItem const &node)


ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 16 2019 02:44:23