39 #include <fcl/config.h> 40 #if FCL_MAJOR_VERSION > 0 || FCL_MINOR_VERSION > 5 41 #include <fcl/geometry/shape/utility.h> 46 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION <= 5 52 const Eigen::Matrix3d&
r = transform.rotation();
53 const Eigen::Vector3d& t = transform.translation();
55 double x_range = 0.5 * (fabs(r(0, 0) * box[0]) + fabs(r(0, 1) * box[1]) + fabs(r(0, 2) * box[2]));
56 double y_range = 0.5 * (fabs(r(1, 0) * box[0]) + fabs(r(1, 1) * box[1]) + fabs(r(1, 2) * box[2]));
57 double z_range = 0.5 * (fabs(r(2, 0) * box[0]) + fabs(r(2, 1) * box[1]) + fabs(r(2, 2) * box[2]));
59 const Eigen::Vector3d v_delta(x_range, y_range, z_range);
64 fcl::computeBV(fcl::Boxd(box), transform, aabb);
void extendWithTransformedBox(const Eigen::Isometry3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.