Robowflex  v0.1
Making MoveIt Easy
fetch_chomp.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 20 of file fetch_chomp.cpp.

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
RAII-pattern for starting up ROS.
Definition: util.h:52
static const std::string GROUP
Definition: fetch_chomp.cpp:18
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 18 of file fetch_chomp.cpp.