Robowflex  v0.1
Making MoveIt Easy
fetch_chomp.cpp
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
9 
10 using namespace robowflex;
11 
12 /* \file fetch_chomp.cpp
13  * A basic script that demonstrates using MoveIt's built-in CHOMP planner. The
14  * resulting trajectory is output to a YAML file. This file can be visualized
15  * using Blender. See the corresponding robowflex_visualization readme.
16  */
17 
18 static const std::string GROUP = "arm_with_torso";
19 
20 int main(int argc, char **argv)
21 {
22  // Startup ROS
23  ROS ros(argc, argv);
24 
25  // Create the default Fetch robot.
26  auto fetch = std::make_shared<FetchRobot>();
27  fetch->initialize();
28 
29  // Create an empty scene.
30  auto scene = std::make_shared<Scene>(fetch);
31 
32  // Create a CHOMP planner for Fetch.
33  auto planner = std::make_shared<opt::CHOMPPipelinePlanner>(fetch);
34  planner->initialize();
35 
36  // Create a motion planning request with a pose goal.
37  MotionRequestBuilder request(planner, GROUP);
38  fetch->setGroupState(GROUP, {0.265, 0.201, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
39  request.setStartConfiguration(fetch->getScratchState());
40 
41  fetch->setGroupState(GROUP, {0.265, 1.301, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
42  request.setGoalConfiguration(fetch->getScratchState());
43 
44  request.setConfig("RRTConnect");
45 
46  // Do motion planning!
47  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
48  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
49  return 1;
50 
51  // Create a trajectory object for better manipulation.
52  auto trajectory = std::make_shared<Trajectory>(res.trajectory_);
53 
54  // Output path to a file for visualization.
55  trajectory->toYAMLFile("fetch_chomp_path.yml");
56 
57  return 0;
58 }
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)
Definition: fetch_chomp.cpp:20
static const std::string GROUP
Definition: fetch_chomp.cpp:18
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")