Robowflex  v0.1
Making MoveIt Easy
fetch_test.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_with_torso"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 19 of file fetch_test.cpp.

20 {
21  // Startup ROS
22  ROS ros(argc, argv);
23 
24  // Create the default Fetch robot.
25  auto fetch = std::make_shared<FetchRobot>();
26  fetch->initialize();
27 
28  // Create an empty scene.
29  auto scene = std::make_shared<Scene>(fetch);
30 
31  // Create the default planner for the Fetch.
32  auto planner = std::make_shared<OMPL::FetchOMPLPipelinePlanner>(fetch, "default");
33  planner->initialize();
34 
35  // Sets the Fetch's base pose.
36  fetch->setBasePose(1, 1, 0.5);
37 
38  // Sets the Fetch's head pose to look at a point.
39  fetch->pointHead({2, 1, 1.5});
40 
41  // Create a motion planning request with a pose goal.
42  MotionRequestBuilder request(planner, GROUP);
43  fetch->setGroupState(GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0}); // Stow
44  request.setStartConfiguration(fetch->getScratchState());
45 
46  fetch->setGroupState(GROUP, {0.265, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007}); // Unfurl
47  request.setGoalConfiguration(fetch->getScratchState());
48 
49  request.setConfig("RRTConnect");
50 
51  // Do motion planning!
52  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
53  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
54  return 1;
55 
56  // Create a trajectory object for better manipulation.
57  auto trajectory = std::make_shared<Trajectory>(res.trajectory_);
58 
59  // Output path to a file for visualization.
60  trajectory->toYAMLFile("fetch_path.yml");
61 
62  return 0;
63 }
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
RAII-pattern for starting up ROS.
Definition: util.h:52
static const std::string GROUP
Definition: fetch_test.cpp:17
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_
robot_trajectory::RobotTrajectoryPtr trajectory_
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")

Variable Documentation

◆ GROUP

const std::string GROUP = "arm_with_torso"
static

Definition at line 17 of file fetch_test.cpp.