22 auto world = std::make_shared<darts::World>();
25 "package://fetch_description/robots/fetch.urdf",
26 "package://fetch_moveit_config/config/fetch.srdf");
28 world->addRobot(fetch1);
32 nfetch =
atoi(argv[1]);
36 auto fetch2 = fetch1->cloneRobot(
"fetch2");
37 fetch2->setDof(2, -1.57);
38 fetch2->setDof(3, 0.525);
39 fetch2->setDof(4, 0.525);
40 world->addRobot(fetch2);
45 auto fetch3 = fetch1->cloneRobot(
"fetch3");
46 fetch3->setDof(2, 1.57);
47 fetch3->setDof(3, 0.525);
48 fetch3->setDof(4, -0.525);
49 world->addRobot(fetch3);
54 auto fetch4 = fetch1->cloneRobot(
"fetch4");
55 fetch4->setDof(2, 3.14);
56 fetch4->setDof(3, 1.05);
57 world->addRobot(fetch4);
63 builder.addGroup(
"fetch1",
"arm_with_torso");
65 builder.addGroup(
"fetch2",
"arm_with_torso");
67 builder.addGroup(
"fetch3",
"arm_with_torso");
69 builder.addGroup(
"fetch4",
"arm_with_torso");
71 builder.setStartConfiguration({
72 0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
73 0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
74 0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
75 0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
80 auto goal = builder.getGoalConfiguration({
81 0.0, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007,
82 0.13, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007,
83 0.38, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007,
84 0.26, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007,
86 builder.setGoal(goal);
88 auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info,
true);
90 builder.ss->setPlanner(rrt);
95 ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
100 window.animatePath(builder, builder.getSolutionPath());
A helper class to setup common OMPL structures for planning.
Open Scene Graph GUI for DART visualization.
#define RBX_WARN(fmt,...)
Output a warning logging message.
#define RBX_INFO(fmt,...)
Output a info logging message.
RobotPtr loadMoveItRobot(const std::string &name, const std::string &urdf, const std::string &srdf)
Load a robot from a URDF and SRDF (i.e., a MoveIt enabled robot).