Robowflex  v0.1
Making MoveIt Easy
fetch_ompl_interface.cpp
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
9 
11 
12 using namespace robowflex;
13 
14 static const std::string GROUP = "arm_with_torso";
15 
16 int main(int argc, char **argv)
17 {
18  // Startup ROS
19  ROS ros(argc, argv);
20 
21  // Create the default Fetch robot.
22  auto fetch = std::make_shared<FetchRobot>();
23  fetch->initialize();
24 
25  // Create an empty scene.
26  auto scene = std::make_shared<Scene>(fetch);
27 
28  // Create the default planner for the Fetch.
29  auto planner = std::make_shared<OMPL::OMPLInterfacePlanner>(fetch, "default");
30  planner->initialize("package://robowflex_resources/fetch/config/ompl_planning.yaml");
31 
32  // Sets the Fetch's base pose.
33  fetch->setBasePose(1, 1, 0.5);
34 
35  // Sets the Fetch's head pose to look at a point.
36  fetch->pointHead({2, 1, 1.5});
37 
38  // Create a motion planning request with a pose goal.
39  MotionRequestBuilder request(planner, GROUP);
40  fetch->setGroupState(GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0}); // Stow
41  request.setStartConfiguration(fetch->getScratchState());
42 
43  fetch->setGroupState(GROUP, {0.265, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007}); // Unfurl
44  request.setGoalConfiguration(fetch->getScratchState());
45 
46  request.setConfig("PRM");
47 
48  // Do motion planning!
49  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
50  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
51  return 1;
52 
53  return 0;
54 }
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
bool setConfig(const std::string &requested_config)
Set the planning configuration to use for the motion planning request. Attempts to match requested_co...
Definition: builder.cpp:114
void setStartConfiguration(const std::vector< double > &joints)
Set the start configuration from a vector joints. All joints are assumed to be specified and in the d...
Definition: builder.cpp:189
planning_interface::MotionPlanRequest & getRequest()
Get a reference to the currently built motion planning request.
Definition: builder.cpp:493
void setGoalConfiguration(const std::vector< double > &joints)
Set the goal configuration from a vector joints. All joints are assumed to be specified and in the de...
Definition: builder.cpp:372
RAII-pattern for starting up ROS.
Definition: util.h:52
int main(int argc, char **argv)
static const std::string GROUP
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_