Robowflex  v0.1
Making MoveIt Easy
fetch_robowflex_planner.cpp
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
10 #include <robowflex_library/util.h>
11 
12 #include <robowflex_dart/planner.h>
13 
14 using namespace robowflex;
15 
16 static const std::string GROUP = "arm_with_torso";
17 
18 int main(int argc, char **argv)
19 {
20  // Startup ROS
21  ROS ros(argc, argv);
22 
23  // Create the default Fetch robot.
24  auto fetch = std::make_shared<FetchRobot>();
25  fetch->initialize();
26 
27  // Create an RViz visualization helper
28  IO::RVIZHelper rviz(fetch);
29  RBX_INFO("RViz Initialized! Press enter to continue (after your RViz is setup)...");
30  std::cin.get();
31 
32  // Create an empty scene.
33  auto scene = std::make_shared<Scene>(fetch);
34 
35  // Create the default planner for the Fetch.
36  auto planner = std::make_shared<darts::DARTPlanner>(fetch);
37 
38  // Create a motion planning request with a pose goal.
39  MotionRequestBuilder request(planner, GROUP);
40  fetch->setGroupState(GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0}); // Stow
41  request.setStartConfiguration(fetch->getScratchState());
42 
43  fetch->setGroupState(GROUP, {0.265, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007}); // Unfurl
44  request.setGoalConfiguration(fetch->getScratchState());
45 
46  request.setConfig("rrt::RRTConnect");
47 
48  // Do motion planning!
49  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
50  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
51  return 1;
52 
53  // Publish the trajectory to a topic to display in RViz
54  rviz.updateTrajectory(res);
55 
56  return 0;
57 }
RVIZ visualization helper. See Live Visualization with RViz for more information.
Definition: visualization.h:38
void updateTrajectory(const planning_interface::MotionPlanResponse &response)
Updates the trajectory being visualized.
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)
static const std::string GROUP
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
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_