37 #include <gtest/gtest.h> 
   48 #include <urdf_parser/urdf_parser.h> 
   49 #include <geometric_shapes/shape_operations.h> 
   55   double joint2 = -0.785;
 
   56   double joint4 = -2.356;
 
   57   double joint6 = 1.571;
 
   58   double joint7 = 0.785;
 
   66 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_collision_detection_fcl.test.test_fcl_env");
 
   76     acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
robot_model_->getLinkModelNames(), 
false);
 
   78     acm_->setEntry(
"panda_link0", 
"panda_link1", 
true);
 
   79     acm_->setEntry(
"panda_link1", 
"panda_link2", 
true);
 
   80     acm_->setEntry(
"panda_link2", 
"panda_link3", 
true);
 
   81     acm_->setEntry(
"panda_link3", 
"panda_link4", 
true);
 
   82     acm_->setEntry(
"panda_link4", 
"panda_link5", 
true);
 
   83     acm_->setEntry(
"panda_link5", 
"panda_link6", 
true);
 
   84     acm_->setEntry(
"panda_link6", 
"panda_link7", 
true);
 
   85     acm_->setEntry(
"panda_link7", 
"panda_hand", 
true);
 
   86     acm_->setEntry(
"panda_hand", 
"panda_rightfinger", 
true);
 
   87     acm_->setEntry(
"panda_hand", 
"panda_leftfinger", 
true);
 
   88     acm_->setEntry(
"panda_rightfinger", 
"panda_leftfinger", 
true);
 
   89     acm_->setEntry(
"panda_link5", 
"panda_link7", 
true);
 
   90     acm_->setEntry(
"panda_link6", 
"panda_hand", 
true);
 
  108   collision_detection::CollisionEnvPtr 
c_env_;
 
  110   collision_detection::AllowedCollisionMatrixPtr 
acm_;
 
  118   ASSERT_TRUE(robot_model_ok_);
 
  126   c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
 
  134   robot_state_->setToDefaultValues();
 
  135   robot_state_->update();
 
  139   c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
 
  149   shapes::Shape* shape = 
new shapes::Box(.1, .1, .1);
 
  150   shapes::ShapeConstPtr shape_ptr(shape);
 
  152   Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
 
  153   pos1.translation().z() = 0.3;
 
  154   c_env_->getWorld()->addToObject(
"box", shape_ptr, pos1);
 
  156   c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
 
  160   c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
 
  164   c_env_->getWorld()->moveObject(
"box", pos1);
 
  165   c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
 
  169   c_env_->getWorld()->moveObject(
"box", pos1);
 
  182   shapes::Shape* shape = 
new shapes::Box(.4, .4, .4);
 
  183   shapes::ShapeConstPtr shape_ptr(shape);
 
  185   Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
 
  186   pos1.translation().z() = 0.3;
 
  187   c_env_->getWorld()->addToObject(
"box", shape_ptr, pos1);
 
  188   c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
 
  202   c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
 
  207   shapes::Shape* shape = 
new shapes::Box(0.1, 0.1, 0.1);
 
  208   shapes::ShapeConstPtr shape_ptr(shape);
 
  210   Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
 
  211   pos.translation().x() = 0.43;
 
  212   pos.translation().y() = 0;
 
  213   pos.translation().z() = 0.55;
 
  214   c_env_->getWorld()->addToObject(
"box", shape_ptr, pos);
 
  216   c_env_->setLinkPadding(
"panda_hand", 0.08);
 
  217   c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
 
  221   c_env_->setLinkPadding(
"panda_hand", 0.0);
 
  222   c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
 
  238   double joint2 = 0.15;
 
  239   double joint4 = -3.0;
 
  240   double joint5 = -0.8;
 
  241   double joint7 = -0.785;
 
  248   c_env_->checkSelfCollision(req, res, state1, *acm_);
 
  253   double joint_5_other = 0.8;
 
  260   c_env_->checkSelfCollision(req, res, state2, *acm_);
 
  265   RCLCPP_INFO(LOGGER, 
"Continuous to continuous collisions are not supported yet, therefore fail here.");
 
  287   double joint_2{ 0.05 };
 
  288   double joint_4{ -1.6 };
 
  293   c_env_->checkRobotCollision(req, res, state1, state2, *acm_);
 
  298   shapes::Shape* shape = 
new shapes::Box(0.1, 0.1, 0.1);
 
  299   shapes::ShapeConstPtr shape_ptr(shape);
 
  301   Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
 
  302   pos.translation().x() = 0.43;
 
  303   pos.translation().y() = 0;
 
  304   pos.translation().z() = 0.55;
 
  305   c_env_->getWorld()->addToObject(
"box", shape_ptr, pos);
 
  307   c_env_->checkRobotCollision(req, res, state1, *acm_);
 
  311   c_env_->checkRobotCollision(req, res, state2, *acm_);
 
  315   c_env_->checkRobotCollision(req, res, state1, state2, *acm_);
 
  321 int main(
int argc, 
char** argv)
 
  323   testing::InitGoogleTest(&argc, argv);
 
  324   return RUN_ALL_TESTS();
 
moveit::core::RobotStatePtr robot_state_
 
moveit::core::RobotModelPtr robot_model_
 
collision_detection::CollisionEnvPtr c_env_
 
collision_detection::AllowedCollisionMatrixPtr acm_
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
void update(bool force=false)
Update all transforms.
 
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
 
void setJointPositions(const std::string &joint_name, const double *position)
 
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
 
Representation of a collision checking request.
 
bool verbose
Flag indicating whether information about detected collisions should be reported.
 
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
 
std::size_t max_contacts
Overall maximum number of contacts to compute.
 
Representation of a collision checking result.
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
 
bool collision
True if collision was found, false otherwise.
 
std::size_t contact_count
Number of contacts returned.
 
int main(int argc, char **argv)
 
void setToHome(moveit::core::RobotState &panda_state)
Brings the panda robot in user defined home position.
 
TEST_F(CollisionDetectionEnvTest, InitOK)
Correct setup testing.