36 auto fetch = std::make_shared<FetchRobot>();
40 scene->fromYAMLFile(
"package://robowflex_library/yaml/test_fetch.yml");
45 auto fetch_dart = std::make_shared<darts::Robot>(
fetch);
46 auto fetch_name = fetch_dart->getName();
47 auto scene_dart = std::make_shared<darts::Structure>(
"scene",
scene);
50 auto world = std::make_shared<darts::World>();
51 world->addRobot(fetch_dart);
52 world->addStructure(scene_dart);
54 fetch_dart->setJoint(
"r_gripper_finger_joint", 0.05);
55 fetch_dart->setJoint(
"l_gripper_finger_joint", 0.05);
59 const auto &plan_to_pick = [&]() {
61 builder.addGroup(fetch_name,
GROUP);
64 start_spec.
setFrame(fetch_name,
"wrist_roll_link",
"base_link");
65 start_spec.
setPose(-0.2, 0.6, 0.92,
69 start_tsr.useGroup(
GROUP);
70 start_tsr.initialize();
71 start_tsr.solveWorld();
73 builder.setStartConfigurationFromWorld();
77 goal_spec.
setFrame(fetch_name,
"wrist_roll_link",
"base_link");
78 goal_spec.
setPose(0.4, 0.6, 1.32,
81 auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
82 auto goal = builder.getGoalTSR(goal_tsr);
83 builder.setGoal(goal);
85 auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info,
true);
87 builder.ss->setPlanner(rrt);
91 goal->startSampling();
92 ompl::base::PlannerStatus solved = builder.ss->solve(60.0);
99 window.animatePath(builder, builder.getSolutionPath());
105 const auto &plan_to_grasp = [&]() {
107 builder.addGroup(fetch_name,
GROUP);
108 builder.setStartConfigurationFromWorld();
111 constraint_spec.
setFrame(fetch_name,
"wrist_roll_link",
"base_link");
112 constraint_spec.
setPose(0.4, 0.6, 0.92,
113 0.5, -0.5, 0.5, 0.5);
116 auto constraint_tsr = std::make_shared<darts::TSR>(world, constraint_spec);
117 builder.addConstraint(constraint_tsr);
118 builder.initialize();
121 goal_spec.
setFrame(fetch_name,
"wrist_roll_link",
"base_link");
122 goal_spec.
setPose(0.4, 0.6, 0.92,
123 0.5, -0.5, 0.5, 0.5);
125 auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
126 auto goal = builder.getGoalTSR(goal_tsr);
127 builder.setGoal(goal);
129 auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info,
true);
131 builder.ss->setPlanner(rrt);
135 goal->startSampling();
136 ompl::base::PlannerStatus solved = builder.ss->solve(60.0);
137 goal->stopSampling();
143 window.animatePath(builder, builder.getSolutionPath());
149 const auto &plan_to_place = [&]() {
151 builder.addGroup(fetch_name,
GROUP);
152 builder.setStartConfigurationFromWorld();
153 builder.initialize();
156 goal_spec.
setFrame(fetch_name,
"wrist_roll_link",
"base_link");
157 goal_spec.
setPose(-0.2, 0.6, 0.92,
158 0.5, -0.5, 0.5, 0.5);
160 auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
161 auto goal = builder.getGoalTSR(goal_tsr);
162 builder.setGoal(goal);
164 auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info,
true);
166 builder.ss->setPlanner(rrt);
170 goal->startSampling();
171 ompl::base::PlannerStatus solved = builder.ss->solve(60.0);
172 goal->stopSampling();
178 window.animatePath(builder, builder.getSolutionPath());
191 auto *
cube = scene_dart->getFrame(
"Cube3");
192 fetch_dart->reparentFreeFrame(
cube,
"wrist_roll_link");
RAII-pattern for starting up ROS.
A helper class to setup common OMPL structures for planning.
The specification of a TSR.
void setNoZPosTolerance()
Set no position tolerance on the Z-axis.
void setPose(const RobotPose &other)
Set the pose of the TSR.
void setFrame(const std::string &structure, const std::string &target, const std::string &base=magic::ROOT_FRAME)
Set the base and target frame.
A Task Space Region (TSR). TSRs are workspace regions that impose a constraints on a robot....
Open Scene Graph GUI for DART visualization.
static const std::string GROUP
#define RBX_WARN(fmt,...)
Output a warning logging message.
#define RBX_INFO(fmt,...)
Output a info logging message.
Functions for loading and animating scenes in Blender.