Aikido
shape_conversions.hpp
Go to the documentation of this file.
1
#ifndef AIKIDO_PERCEPTION_SHAPE_CONVERSIONS_HPP_
2
#define AIKIDO_PERCEPTION_SHAPE_CONVERSIONS_HPP_
3
4
#include <Eigen/Dense>
5
#include <geometry_msgs/Pose.h>
6
#include <tf/LinearMath/Quaternion.h>
7
#include <tf/LinearMath/Vector3.h>
8
#include <tf/transform_listener.h>
9
10
namespace
aikido
{
11
namespace
perception {
12
16
Eigen::Isometry3d
convertROSPoseToEigen
(
const
geometry_msgs::Pose& p);
17
22
Eigen::Isometry3d
convertStampedTransformToEigen
(
const
tf::StampedTransform& t);
23
24
}
// namespace perception
25
}
// namespace aikido
26
27
#endif // AIKIDO_PERCEPTION_SHAPE_CONVERSIONS_HPP_
aikido
Format of serialized trajectory in YAML.
Definition:
algorithm.hpp:4
aikido::perception::convertStampedTransformToEigen
Eigen::Isometry3d convertStampedTransformToEigen(const tf::StampedTransform &t)
Convert a time-stamped ROS transform to a 4 x 4 pose matrix.
aikido::perception::convertROSPoseToEigen
Eigen::Isometry3d convertROSPoseToEigen(const geometry_msgs::Pose &p)
Convert a ROS Pose (position + quaternion) to a 4 x 4 pose matrix.
include
aikido
perception
shape_conversions.hpp
Generated on Fri Mar 10 2023 20:07:57 for Aikido by
1.8.17