22 auto fetch = std::make_shared<FetchRobot>();
29 auto planner = std::make_shared<OMPL::OMPLInterfacePlanner>(
fetch,
"default");
30 planner->initialize(
"package://robowflex_resources/fetch/config/ompl_planning.yaml");
33 fetch->setBasePose(1, 1, 0.5);
36 fetch->pointHead({2, 1, 1.5});
40 fetch->setGroupState(
GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0});
41 request.setStartConfiguration(
fetch->getScratchState());
43 fetch->setGroupState(
GROUP, {0.265, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
44 request.setGoalConfiguration(
fetch->getScratchState());
46 request.setConfig(
"PRM");
50 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
A helper class to build motion planning requests for a robowflex::Planner.
RAII-pattern for starting up ROS.
static const std::string GROUP
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_