38 #include <geometric_shapes/check_isometry.h>
48 ASSERT_ISOMETRY(transform)
49 const Eigen::Matrix3d&
r = transform.linear();
52 double x_range = 0.5 * (fabs(
r(0, 0) * box[0]) + fabs(
r(0, 1) * box[1]) + fabs(
r(0, 2) * box[2]));
53 double y_range = 0.5 * (fabs(
r(1, 0) * box[0]) + fabs(
r(1, 1) * box[1]) + fabs(
r(1, 2) * box[2]));
54 double z_range = 0.5 * (fabs(
r(2, 0) * box[0]) + fabs(
r(2, 1) * box[1]) + fabs(
r(2, 2) * box[2]));
void extendWithTransformedBox(const Eigen::Isometry3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
Vec3fX< details::Vec3Data< double > > Vector3d