43 #include <gtest/gtest.h>
50 #include <ompl/geometric/SimpleSetup.h>
51 #include <ompl/base/Constraint.h>
52 #include <ompl/base/ConstrainedSpaceInformation.h>
53 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
58 static const rclcpp::Logger LOGGER =
59 rclcpp::get_logger(
"moveit.ompl_planning.test.test_constrained_state_validity_checker");
62 std::ostream&
operator<<(std::ostream& os,
const std::vector<double>& v)
75 DummyConstraint(
const unsigned int num_dofs) : ompl::base::Constraint(num_dofs, 1)
78 void function(
const Eigen::Ref<const Eigen::VectorXd>& , Eigen::Ref<Eigen::VectorXd> out)
const override
97 SCOPED_TRACE(
"testEqualityPositionConstraints");
103 SCOPED_TRACE(
"testJointLimits");
106 auto checker = std::make_shared<ompl_interface::ConstrainedPlanningStateValidityChecker>(
planning_context_.get());
115 auto state = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()
119 RCLCPP_DEBUG_STREAM(LOGGER,
124 bool result = checker->isValid(ompl_state.get());
129 result = checker->isValid(ompl_state.get(),
distance);
131 RCLCPP_DEBUG(LOGGER,
"Distance from the isValid function '%f': ",
distance);
136 state->values[0] = std::numeric_limits<double>::max();
137 state->clearKnownInformation();
139 RCLCPP_DEBUG_STREAM(LOGGER,
142 bool result_2 = checker->isValid(ompl_state.get());
143 EXPECT_FALSE(result_2);
146 double distance_2 = 0.0;
147 result_2 = checker->isValid(ompl_state.get(), distance_2);
148 EXPECT_FALSE(result_2);
150 EXPECT_EQ(distance_2, 0.0);
155 SCOPED_TRACE(
"testSelfCollision");
158 auto checker = std::make_shared<ompl_interface::ConstrainedPlanningStateValidityChecker>(
planning_context_.get());
169 auto state = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()
175 RCLCPP_DEBUG_STREAM(LOGGER,
179 bool result = checker->isValid(ompl_state.get());
180 EXPECT_FALSE(result);
184 result = checker->isValid(ompl_state.get(),
distance);
185 EXPECT_FALSE(result);
189 EXPECT_TRUE(result_2);
212 state_space_ = std::make_shared<ompl_interface::ConstrainedPlanningStateSpace>(space_spec);
215 auto dummy_constraint = std::make_shared<DummyConstraint>(
num_dofs_);
221 ASSERT_NE(
state_space_,
nullptr) <<
"Initialize state space before creating the planning context.";
231 auto si_constrained =
dynamic_cast<ompl::base::ConstrainedSpaceInformation*
>(si.get());
232 ASSERT_NE(si_constrained,
nullptr);
241 RCLCPP_DEBUG(LOGGER,
"Planning context with name '%s' is ready (but not configured).",
275 testJointLimits({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 });
282 testSelfCollision({ 2.31827, -0.169668, 2.5225, -2.98568, -0.36355, 0.808339, 0.0843406 });
304 testJointLimits({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
311 testSelfCollision({ -2.95993, -0.682185, -2.43873, -0.939784, 3.0544, 0.882294 });
319 int main(
int argc,
char** argv)
321 testing::InitGoogleTest(&argc, argv);
322 return RUN_ALL_TESTS();
Dummy constraint for testing, always satisfied. We need this to create and OMPL ConstrainedStateSpace...
DummyConstraint(const unsigned int num_dofs)
FanucTestStateValidityChecker()
PandaValidityCheckerTests()
Generic implementation of the tests that can be executed on different robots.
moveit::core::RobotStatePtr initial_robot_state_
void setupPlanningContext()
ompl_interface::ModelBasedStateSpacePtr state_space_
void testJointLimits(const std::vector< double > &position_in_limits)
void testSelfCollision(const std::vector< double > &position_in_self_collision)
planning_scene::PlanningScenePtr planning_scene_
ompl::base::ConstrainedStateSpacePtr constrained_state_space_
ompl_interface::ModelBasedPlanningContextSpecification planning_context_spec_
ompl_interface::ModelBasedPlanningContextPtr planning_context_
TestStateValidityChecker(const std::string &robot_name, const std::string &group_name)
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
moveit::core::RobotModelPtr robot_model_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
double distance(const urdf::Pose &transform)
ModelBasedStateSpacePtr state_space_
og::SimpleSetupPtr ompl_simple_setup_
int main(int argc, char **argv)
std::ostream & operator<<(std::ostream &os, const std::vector< double > &v)
Pretty print std:vectors.
constexpr bool VERBOSE
This flag sets the verbosity level for the state validity checker.
TEST_F(PandaValidityCheckerTests, testConstructor)
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)