43 #include <Eigen/Geometry> 48 #include <openvdb/openvdb.h> 50 #include <geometry_msgs/Point.h> 51 #include <visualization_msgs/Marker.h> 52 #include <visualization_msgs/MarkerArray.h> 53 #include <geometry_msgs/Quaternion.h> 54 #include <geometry_msgs/PointStamped.h> 55 #include <geometry_msgs/Pose.h> 66 const double& z_,
const Eigen::Vector3d& p0) : \
83 Eigen::Vector3d vec_t = homogeneous_transform.rotation() * Eigen::Vector3d(
x,
y,
z);
85 x = vec_t[0];
y = vec_t[1];
z = vec_t[2];
102 virtual bool IsInside(
const openvdb::Vec3d& pt) = 0;
105 virtual void SetPosition(
const geometry_msgs::Point& origin) = 0;
106 virtual void SetOrientation(
const geometry_msgs::Quaternion& quat) = 0;
109 virtual void TransformModel(
void) = 0;
Eigen::Vector3d initial_point
Eigen::Quaterniond _orientation
void TransformFrames(const Eigen::Affine3d &homogeneous_transform)
VectorWithPt3D(const double &x_, const double &y_, const double &z_, const Eigen::Vector3d &p0)
VectorWithPt3D operator*(double a)
Eigen::Vector3d _position