45 #include <gtest/gtest.h> 
   46 #include <Eigen/Dense> 
   53 #include <moveit_msgs/msg/constraints.hpp> 
   55 #include <ompl/util/Exception.h> 
   56 #include <ompl/base/spaces/RealVectorStateSpace.h> 
   57 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h> 
   61 static const rclcpp::Logger LOGGER =
 
   62     rclcpp::get_logger(
"moveit.ompl_planning.test.test_constrained_planning_state_space");
 
   68   DummyConstraint(
const unsigned int num_dofs) : ompl::base::Constraint(num_dofs, 1)
 
   71   void function(
const Eigen::Ref<const Eigen::VectorXd>& , Eigen::Ref<Eigen::VectorXd> out) 
const override 
  100     moveit_state_space_ = std::make_shared<ompl_interface::ConstrainedPlanningStateSpace>(space_spec);
 
  107     auto con = std::make_shared<DummyConstraint>(
num_dofs_);
 
  113     SCOPED_TRACE(
"testGetValueAddressAtIndex");
 
  117     auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
 
  119     EXPECT_FALSE(out_joint_positions == 
nullptr);
 
  121     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  123       *(out_joint_positions + i) = joint_positions[i];
 
  130     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  138     SCOPED_TRACE(
"testCopyToRobotState");
 
  146     auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
 
  148     EXPECT_FALSE(out_joint_positions == 
nullptr);
 
  150     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  152       *(out_joint_positions + i) = joint_positions[i];
 
  161     Eigen::VectorXd out_joint_position(
num_dofs_);
 
  164     EXPECT_EQ(joint_positions.size(), out_joint_position.size());
 
  166     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  168       EXPECT_EQ(joint_positions[i], out_joint_position[i]);
 
  174     SCOPED_TRACE(
"testCopyToOMPLState");
 
  188     auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
 
  190     EXPECT_FALSE(out_joint_positions == 
nullptr);
 
  192     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  194       EXPECT_EQ(joint_positions[i], *(out_joint_positions + i));
 
  200     SCOPED_TRACE(
"testCopyJointToOMPLState");
 
  213     for (std::size_t joint_index = 0; joint_index < 
num_dofs_; ++joint_index)
 
  216       EXPECT_FALSE(joint_model == 
nullptr);
 
  218       RCLCPP_DEBUG_STREAM(LOGGER, 
"Joint model: " << joint_model->
getName() << 
" index: " << joint_index);
 
  219       RCLCPP_DEBUG_STREAM(LOGGER, 
"first index: " << joint_model->
getFirstVariableIndex() * 
sizeof(
double));
 
  220       RCLCPP_DEBUG_STREAM(LOGGER, 
"width: " << joint_model->
getVariableCount() * 
sizeof(
double));
 
  222       moveit_state_space_->copyJointToOMPLState(ompl_state.get(), moveit_state, joint_model, joint_index);
 
  226     auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
 
  228     EXPECT_FALSE(out_joint_positions == 
nullptr);
 
  230     for (std::size_t i = 0; i < 
num_dofs_; ++i)
 
  232       EXPECT_EQ(joint_positions[i], *(out_joint_positions + i));
 
  254   testGetValueAddressAtIndex();
 
  259   testCopyToRobotState();
 
  264   testCopyToOMPLState();
 
  269   testCopyJointToOMPLState();
 
  285   testGetValueAddressAtIndex();
 
  290   testCopyToRobotState();
 
  295   testCopyToOMPLState();
 
  300   testCopyJointToOMPLState();
 
  316   testGetValueAddressAtIndex();
 
  321   testCopyToRobotState();
 
  326   testCopyToOMPLState();
 
  331   testCopyJointToOMPLState();
 
  337 int main(
int argc, 
char** argv)
 
  339   testing::InitGoogleTest(&argc, argv);
 
  340   return RUN_ALL_TESTS();
 
Dummy constraint for testing, always satisfied. We need this to create and OMPL ConstrainedStateSpace...
 
DummyConstraint(const unsigned int num_dofs)
 
Robot indepentent implementation of the tests.
 
TestConstrainedStateSpace(const std::string &robot_name, const std::string &group_name)
 
ompl_interface::ConstrainedPlanningStateSpacePtr moveit_state_space_
 
void testGetValueAddressAtIndex()
 
ompl::base::ConstrainedStateSpacePtr constrained_state_space_
 
void setupMoveItStateSpace()
 
void testCopyToRobotState()
 
void setupOMPLStateSpace()
 
void testCopyJointToOMPLState()
 
void testCopyToOMPLState()
 
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
 
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
 
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
 
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
 
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
 
const std::string & getName() const
Get the name of the joint.
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
 
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
 
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
 
Robot independent test class setup.
 
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_
 
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
 
const moveit::core::JointModelGroup * joint_model_group_
 
TEST_F(PandaCopyStateTest, testGetValueAddressAtIndex)
 
int main(int argc, char **argv)
 
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)