void setGeometry(const BodyNodePtr& bn) { // Create a BoxShape to be used for both visualization and collision checking std::shared_ptr<BoxShape> box(new BoxShape( Eigen::Vector3d(default_width, default_depth, default_height))); box->setColor(dart::Color::Blue()); // Set the location of the Box Eigen::Isometry3d box_tf(Eigen::Isometry3d::Identity()); Eigen::Vector3d center = Eigen::Vector3d(0, 0, default_height / 2.0); box_tf.translation() = center; box->setLocalTransform(box_tf); // Add it as a visualization and collision shape bn->addVisualizationShape(box); bn->addCollisionShape(box); // Move the center of mass to the center of the object bn->setLocalCOM(center); }
void setGeometry(const BodyNodePtr& bn) { // Create a BoxShape to be used for both visualization and collision checking std::shared_ptr<BoxShape> box(new BoxShape( Eigen::Vector3d(default_width, default_depth, default_height))); // Create a shpae node for visualization and collision checking auto shapeNode = bn->createShapeNodeWith<VisualAspect, CollisionAspect, DynamicsAspect>(box); shapeNode->getVisualAspect()->setColor(dart::Color::Blue()); // Set the location of the shape node Eigen::Isometry3d box_tf(Eigen::Isometry3d::Identity()); Eigen::Vector3d center = Eigen::Vector3d(0, 0, default_height / 2.0); box_tf.translation() = center; shapeNode->setRelativeTransform(box_tf); // Move the center of mass to the center of the object bn->setLocalCOM(center); }