Robowflex  v0.1
Making MoveIt Easy
fetch_tabletop_planning_time.cpp File Reference

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Variables

static const std::string GROUP = "arm"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 22 of file fetch_tabletop_planning_time.cpp.

23 {
24  // Startup ROS
25  ROS ros(argc, argv);
26 
27  // Create the default Fetch robot.
28  auto fetch = std::make_shared<FetchRobot>();
29  fetch->initialize(false);
30 
31  // Load tabletop scene.
32  auto scene = std::make_shared<Scene>(fetch);
33  scene->fromYAMLFile("package://robowflex_tesseract/scenes/table/scene.yaml");
34 
35  // Attach object to end effector.
36  scene->attachObject(*fetch->getScratchState(), "Can1");
37 
38  // Create a TrajOpt planner for Fetch.
39  auto planner = std::make_shared<TrajOptPlanner>(fetch, GROUP);
40  planner->initialize("torso_lift_link", "gripper_link");
41 
42  // Set planner parameters.
43  planner->options.num_waypoints = 8; // Select number of waypoints in trajectory.
44  planner->setInitType(trajopt::InitInfo::Type::JOINT_INTERPOLATED); // Initialize using a straight-line
45  // between start and goal in C-Space.
46 
47  // Load request.
48  const auto &request = std::make_shared<MotionRequestBuilder>(fetch);
49  request->fromYAMLFile("package://robowflex_tesseract/scenes/table/request.yaml");
50 
51  // RVIZ helper.
52  const auto &rviz = std::make_shared<IO::RVIZHelper>(fetch);
53  rviz->updateScene(scene);
54  rviz->visualizeState(request->getStartConfiguration());
55 
56  RBX_INFO("Visualizing start state");
57  RBX_INFO("Press Enter to run the planner and returning its first solution");
58  std::cin.ignore();
59 
60  // Run the planner just once.
61  planner->options.return_first_sol = true;
62 
63  // Do motion planning.
64  auto res = planner->plan(scene, request->getRequest());
65  if (res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
66  rviz->updateTrajectory(res);
67 
68  rviz->visualizeState(request->getGoalConfiguration());
69 
70  RBX_INFO("Visualizing goal state");
71  RBX_INFO("Press Enter to run the planner with a time bound but returning as soon as it finds the first "
72  "feasible solution");
73  std::cin.ignore();
74 
75  // Run the planner potentially more than once and make it return when it finds a feasible solution or when
76  // it runs out of time. Each time the planner runs, it starts with a perturbed version of the initial
77  // trajectory.
78  planner->options.return_first_sol = false;
79  planner->options.return_after_timeout = false;
80 
81  // The time budget is taken from the planning request.
82  request->getRequest().allowed_planning_time = 3.0;
83 
84  // Do motion planning.
85  res = planner->plan(scene, request->getRequest());
86  if (res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
87  rviz->updateTrajectory(res);
88 
89  rviz->visualizeState(request->getGoalConfiguration());
90 
91  RBX_INFO("Visualizing goal state");
92  RBX_INFO("Press Enter to run the planner for the whole time budget");
93  std::cin.ignore();
94 
95  // Run the planner for the whole time budget.
96  planner->options.return_first_sol = false;
97  planner->options.return_after_timeout = true;
98 
99  // The time budget is taken from the planning request.
100  request->getRequest().allowed_planning_time = 3.0;
101 
102  // Do motion planning.
103  res = planner->plan(scene, request->getRequest());
104  if (res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
105  rviz->updateTrajectory(res);
106 
107  rviz->visualizeState(request->getGoalConfiguration());
108 
109  RBX_INFO("Visualizing goal state");
110  RBX_INFO("Press Enter to finish");
111  std::cin.ignore();
112 
113  return 0;
114 }
RAII-pattern for starting up ROS.
Definition: util.h:52
static const std::string GROUP
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
Functions for loading and animating scenes in Blender.

Variable Documentation

◆ GROUP

const std::string GROUP = "arm"
static

Definition at line 20 of file fetch_tabletop_planning_time.cpp.