Robowflex  v0.1
Making MoveIt Easy
fetch_tabletop_goalstate.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_goalstate.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 continue");
58  std::cin.ignore();
59 
60  // Do motion planning.
61  const auto &res = planner->plan(scene, request->getRequest());
62  if (res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
63  rviz->updateTrajectory(res);
64 
65  rviz->visualizeState(request->getGoalConfiguration());
66 
67  RBX_INFO("Visualizing goal state");
68  RBX_INFO("Press Enter to exit");
69  std::cin.ignore();
70 
71  return 0;
72 }
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_goalstate.cpp.