Robowflex  v0.1
Making MoveIt Easy
fetch_trajopt.cpp
Go to the documentation of this file.
1 /* Author: Carlos Quintero Pena */
2 
11 
12 using namespace robowflex;
13 
14 /* \file fetch_trajopt.cpp
15  * A basic script that demonstrates using Tesseract's TrajOpt planner. The
16  * resulting trajectory is output to a YAML file. This file can be visualized
17  * using Blender. See the corresponding robowflex_visualization readme.
18  */
19 
20 static const std::string GROUP = "arm";
21 
22 int main(int argc, char **argv)
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  // Create an empty scene.
32  auto scene = std::make_shared<Scene>(fetch);
33 
34  // Create a TrajOpt planner for Fetch.
35  auto planner = std::make_shared<TrajOptPlanner>(fetch, GROUP);
36  planner->initialize("torso_lift_link", "gripper_link");
37  planner->options.num_waypoints = 3;
38 
39  // Create a motion planning request with a pose goal.
40  MotionRequestBuilder request(planner, GROUP);
41  fetch->setGroupState(GROUP, {0.201, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
42  request.setStartConfiguration(fetch->getScratchState());
43 
44  fetch->setGroupState(GROUP, {1.301, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
45  request.setGoalConfiguration(fetch->getScratchState());
46 
47  // Do motion planning!
48  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
49  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
50  return 1;
51 
52  // Create a trajectory object for better manipulation.
53  auto trajectory = std::make_shared<Trajectory>(res.trajectory_);
54 
55  // Output path to a file for visualization.
56  trajectory->toYAMLFile("fetch_trajopt_path.yml");
57 
58  return 0;
59 }
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
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_
robot_trajectory::RobotTrajectoryPtr trajectory_
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")