50 #include <gtest/gtest.h> 
   51 #include <Eigen/Dense> 
   58 #include <moveit_msgs/msg/constraints.hpp> 
   60 #include <ompl/util/Exception.h> 
   61 #include <ompl/base/spaces/RealVectorStateSpace.h> 
   62 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h> 
   63 #include <ompl/base/ConstrainedSpaceInformation.h> 
   65 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.test.test_ompl_constraints");
 
   83   shape_msgs::msg::SolidPrimitive box_constraint;
 
   84   box_constraint.type = shape_msgs::msg::SolidPrimitive::BOX;
 
   85   box_constraint.dimensions = { 0.05, 0.4, 0.05 }; 
 
   87   geometry_msgs::msg::Pose box_pose;
 
   88   box_pose.position.x = 0.9;
 
   89   box_pose.position.y = 0.0;
 
   90   box_pose.position.z = 0.2;
 
   91   box_pose.orientation.w = 1.0;
 
   93   moveit_msgs::msg::PositionConstraint position_constraint;
 
   94   position_constraint.header.frame_id = base_link;
 
   95   position_constraint.link_name = ee_link;
 
   96   position_constraint.constraint_region.primitives.push_back(box_constraint);
 
   97   position_constraint.constraint_region.primitive_poses.push_back(box_pose);
 
   99   return position_constraint;
 
  119   const Eigen::Isometry3d 
fk(
const Eigen::VectorXd& q, 
const std::string& link_name)
 const 
  128     Eigen::VectorXd joint_positions;
 
  130     return joint_positions;
 
  135     const double h = 1e-6; 
 
  137     Eigen::MatrixXd jacobian = Eigen::MatrixXd::Zero(3, 
num_dofs_);
 
  142     for (std::size_t dim = 0; dim < 
num_dofs_; ++dim)
 
  147       jacobian.col(dim) = col;
 
  154     moveit_msgs::msg::Constraints constraint_msgs;
 
  166     RCLCPP_DEBUG_STREAM(LOGGER, different_link);
 
  168     moveit_msgs::msg::Constraints constraint_msgs;
 
  181     pos_con_msg.constraint_region.primitives.at(0).dimensions[0] = 0.0005;
 
  184     pos_con_msg.constraint_region.primitives.at(0).dimensions[1] = 1.0;
 
  185     pos_con_msg.constraint_region.primitives.at(0).dimensions[2] = 1.0;
 
  187     moveit_msgs::msg::Constraints constraint_msgs;
 
  188     constraint_msgs.position_constraints.push_back(pos_con_msg);
 
  191     constraint_msgs.name = 
"use_equality_constraints";
 
  199     SCOPED_TRACE(
"testJacobian");
 
  201     double total_error = 999.9;
 
  206       auto jac_exact = 
constraint_->calcErrorJacobian(q);
 
  210       RCLCPP_DEBUG_STREAM(LOGGER, 
"Analytical jacobian:");
 
  211       RCLCPP_DEBUG_STREAM(LOGGER, jac_exact);
 
  212       RCLCPP_DEBUG_STREAM(LOGGER, 
"Finite difference jacobian:");
 
  213       RCLCPP_DEBUG_STREAM(LOGGER, jac_approx);
 
  215       total_error = (jac_exact - jac_approx).lpNorm<1>();
 
  222     SCOPED_TRACE(
"testOMPLProjectedStateSpaceConstruction");
 
  224     auto state_space = std::make_shared<ompl::base::RealVectorStateSpace>(
num_dofs_);
 
  225     ompl::base::RealVectorBounds bounds(
num_dofs_);
 
  231     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  235       bounds.setHigh(i, 
joint_limits[i]->at(0).max_position_);
 
  238     state_space->setBounds(bounds);
 
  240     auto constrained_state_space = std::make_shared<ompl::base::ProjectedStateSpace>(state_space, 
constraint_);
 
  244     auto constrained_state_space_info =
 
  245         std::make_shared<ompl::base::ConstrainedSpaceInformation>(constrained_state_space);
 
  254       constrained_state_space->sanityChecks();
 
  256     catch (ompl::Exception& ex)
 
  258       RCLCPP_ERROR(LOGGER, 
"Sanity checks did not pass: %s", ex.what());
 
  264     SCOPED_TRACE(
"testEqualityPositionConstraints");
 
  266     EXPECT_NE(
constraint_, 
nullptr) << 
"First call setEqualityPositionConstraints before calling this test.";
 
  277     EXPECT_DOUBLE_EQ(
f[1], 0.0);
 
  278     EXPECT_DOUBLE_EQ(
f[2], 0.0);
 
  284     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  287       EXPECT_DOUBLE_EQ(jac(1, i), 0.0);
 
  288       EXPECT_DOUBLE_EQ(jac(2, i), 0.0);
 
  292     EXPECT_NE(
f[0], 0.0);
 
  293     EXPECT_NE(jac.row(0).squaredNorm(), 0.0);
 
  313   setPositionConstraints();
 
  314   setPositionConstraintsDifferentLink();
 
  319   setPositionConstraints();
 
  323   setPositionConstraintsDifferentLink();
 
  329   setPositionConstraints();
 
  330   testOMPLProjectedStateSpaceConstruction();
 
  334   setPositionConstraintsDifferentLink();
 
  335   testOMPLProjectedStateSpaceConstruction();
 
  340   setEqualityPositionConstraints();
 
  341   testOMPLProjectedStateSpaceConstruction();
 
  342   testEqualityPositionConstraints();
 
  357   setPositionConstraints();
 
  358   setPositionConstraintsDifferentLink();
 
  363   setPositionConstraints();
 
  367   setPositionConstraintsDifferentLink();
 
  373   setPositionConstraints();
 
  374   testOMPLProjectedStateSpaceConstruction();
 
  378   setPositionConstraintsDifferentLink();
 
  379   testOMPLProjectedStateSpaceConstruction();
 
  384   setEqualityPositionConstraints();
 
  385   testOMPLProjectedStateSpaceConstruction();
 
  386   testEqualityPositionConstraints();
 
  402   setPositionConstraints();
 
  403   setPositionConstraintsDifferentLink();
 
  408   setPositionConstraints();
 
  412   setPositionConstraintsDifferentLink();
 
  418   setPositionConstraints();
 
  419   testOMPLProjectedStateSpaceConstruction();
 
  422   setPositionConstraintsDifferentLink();
 
  423   testOMPLProjectedStateSpaceConstruction();
 
  428   setEqualityPositionConstraints();
 
  429   testOMPLProjectedStateSpaceConstruction();
 
  430   testEqualityPositionConstraints();
 
  436 int main(
int argc, 
char** argv)
 
  438   testing::InitGoogleTest(&argc, argv);
 
  439   return RUN_ALL_TESTS();
 
PR2LeftArmConstraintTest()
 
TestOMPLConstraints(const std::string &robot_name, const std::string &group_name)
 
std::shared_ptr< ompl_interface::BaseConstraint > constraint_
 
void setPositionConstraints()
 
Eigen::VectorXd getRandomState()
 
void testOMPLProjectedStateSpaceConstruction()
 
const Eigen::Isometry3d fk(const Eigen::VectorXd &q, const std::string &link_name) const
Robot forward kinematics.
 
Eigen::MatrixXd numericalJacobianPosition(const Eigen::VectorXd &q, const std::string &link_name) const
 
void testEqualityPositionConstraints()
 
void setEqualityPositionConstraints()
 
void setPositionConstraintsDifferentLink()
Test position constraints a link that is not the end-effector.
 
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
 
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
 
Robot independent test class setup.
 
moveit::core::RobotStatePtr robot_state_
 
Eigen::VectorXd getDeterministicState() const
Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number ...
 
moveit::core::RobotModelPtr robot_model_
 
std::string ee_link_name_
 
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
 
const moveit::core::JointModelGroup * joint_model_group_
 
std::string base_link_name_
 
Vec3fX< details::Vec3Data< double > > Vector3d
 
constexpr int NUM_RANDOM_TESTS
Number of times to run a test that uses randomly generated input.
 
TEST_F(PandaConstraintTest, InitPositionConstraint)
 
int main(int argc, char **argv)
 
constexpr unsigned int DIFFERENT_LINK_OFFSET
Select a robot link at (num_dofs - different_link_offset) to test another link than the end-effector.
 
constexpr double JAC_ERROR_TOLERANCE
Allowed error when comparing Jacobian matrix error.
 
moveit_msgs::msg::PositionConstraint createPositionConstraint(std::string &base_link, std::string &ee_link)
Helper function to create a specific position constraint.