Robowflex  v0.1
Making MoveIt Easy
ur5_test.cpp File Reference

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 18 of file ur5_test.cpp.

19 {
20  // Startup ROS
21  ROS ros(argc, argv);
22 
23  // Create the default UR5 robot.
24  auto ur5 = std::make_shared<UR5Robot>();
25  ur5->initialize();
26 
27  // Create an empty scene.
28  auto scene = std::make_shared<Scene>(ur5);
29 
30  // Create the default planner for the UR5.
31  auto default_planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5, "default");
32  default_planner->initialize();
33 
34  // Create the a planner for the UR5, and disable simplification.
35  auto simple_planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5, "simple");
36 
37  OMPL::Settings settings;
38  settings.simplify_solutions = false;
39 
40  simple_planner->initialize(settings);
41 
42  // Run a motion plan for each planner.
43  for (const auto &planner : {default_planner, simple_planner})
44  {
45  // Create a motion planning request with a pose goal.
46  MotionRequestBuilder request(planner, "manipulator");
47  request.setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
48 
49  RobotPose pose = RobotPose::Identity();
50  pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
51  Eigen::Quaterniond orn{0, 0, 1, 0};
52 
53  request.setGoalRegion("ee_link", "world", // links
54  pose, Geometry::makeSphere(0.1), // position
55  orn, {0.01, 0.01, 0.01} // orientation
56  );
57 
58  // Do motion planning!
59  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
60  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
61  return 1;
62  }
63 
64  return 0;
65 }
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline.
bool simplify_solutions
Whether or not planner should simplify solutions.
RAII-pattern for starting up ROS.
Definition: util.h:52
std::shared_ptr< dart::dynamics::SphereShape > makeSphere(double radius)
Create a sphere.
Definition: structure.cpp:385
std::decay< decltype(std::declval< moveit::core::Transforms >().getTransform("")) >::type RobotPose
A pose (point in SE(3)) used in various functions. Defined from what MoveIt! uses.
Definition: adapter.h:24
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_