43 #include <gtest/gtest.h> 
   49 #include <geometry_msgs/PointStamped.h> 
   53 class MoveItCppTest : 
public ::testing::Test
 
   97   auto robot_model = moveit_cpp_ptr->getRobotModel();
 
   98   auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
 
   99   EXPECT_TRUE(moveit_cpp_ptr->getCurrentState(robot_state, 0.0));
 
  101   std::vector<double> joints_vals;
 
  102   robot_state->copyJointGroupPositions(PLANNING_GROUP, joints_vals);
 
  113 TEST_F(MoveItCppTest, NameOfPlanningGroupTest)
 
  115   EXPECT_STREQ(planning_component_ptr->getPlanningGroupName().c_str(), 
"panda_arm");
 
  119 TEST_F(MoveItCppTest, TestSetStartStateToCurrentState)
 
  121   planning_component_ptr->setStartStateToCurrentState();
 
  122   planning_component_ptr->setGoal(target_pose1, 
"panda_link8");
 
  124   ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
 
  129 TEST_F(MoveItCppTest, TestSetGoalFromPoseStamped)
 
  131   planning_component_ptr->setGoal(target_pose1, 
"panda_link8");
 
  133   ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
 
  137 TEST_F(MoveItCppTest, TestSetStartStateFromRobotState)
 
  139   auto start_state = *(moveit_cpp_ptr->getCurrentState());
 
  140   start_state.setFromIK(jmg_ptr, start_pose);
 
  142   planning_component_ptr->setStartState(start_state);
 
  143   planning_component_ptr->setGoal(target_pose1, 
"panda_link8");
 
  145   ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
 
  151   auto target_state = *(moveit_cpp_ptr->getCurrentState());
 
  153   target_state.setFromIK(jmg_ptr, target_pose2);
 
  155   planning_component_ptr->setGoal(target_state);
 
  157   ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
 
  161 int main(
int argc, 
char** argv)
 
  163   testing::InitGoogleTest(&argc, argv);
 
  164   ros::init(argc, argv, 
"moveit_cpp_test");
 
  169   int result = RUN_ALL_TESTS();