104 ros::Duration(1.0).sleep();
105 auto robot_model = moveit_cpp_ptr->getRobotModel();
106 auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
107 EXPECT_TRUE(moveit_cpp_ptr->getCurrentState(robot_state, 0.0));
109 std::vector<double> joints_vals;
110 robot_state->copyJointGroupPositions(PLANNING_GROUP, joints_vals);
111 EXPECT_NEAR(joints_vals[0], 0.0, 0.001);
112 EXPECT_NEAR(joints_vals[1], -0.785, 0.001);
113 EXPECT_NEAR(joints_vals[2], 0.0, 0.001);
114 EXPECT_NEAR(joints_vals[3], -2.356, 0.001);
115 EXPECT_NEAR(joints_vals[4], 0.0, 0.001);
116 EXPECT_NEAR(joints_vals[5], 1.571, 0.001);
117 EXPECT_NEAR(joints_vals[6], 0.785, 0.001);
147 auto start_state = *(moveit_cpp_ptr->getCurrentState());
148 start_state.setFromIK(jmg_ptr, start_pose);
150 planning_component_ptr->setStartState(start_state);
151 planning_component_ptr->setGoal(target_pose1,
"panda_link8");
153 ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
159 auto target_state = *(moveit_cpp_ptr->getCurrentState());
161 target_state.setFromIK(jmg_ptr, target_pose2);
163 planning_component_ptr->setGoal(target_state);
165 ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));