Robowflex  v0.1
Making MoveIt Easy
builder.cpp
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
3 #include <moveit/constraint_samplers/constraint_sampler.h>
4 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
5 #include <moveit/constraint_samplers/default_constraint_samplers.h>
6 #include <moveit/kinematic_constraints/utils.h>
7 #include <moveit/robot_state/conversions.h>
8 
13 #include <robowflex_library/io.h>
15 #include <robowflex_library/log.h>
19 #include <robowflex_library/tf.h>
20 #include <robowflex_library/util.h>
21 
22 using namespace robowflex;
23 
24 // Typical name for RRTConnect configuration in MoveIt
25 const std::string MotionRequestBuilder::DEFAULT_CONFIG = "RRTConnectkConfigDefault";
26 
28 {
29  initialize();
30 
31  robot_state::RobotState start_state(robot_->getModelConst());
32  start_state.setToDefaultValues();
33 
34  moveit::core::robotStateToRobotStateMsg(start_state, request_.start_state);
35 }
36 
38  const std::string &planner_config)
40 {
41  setPlanningGroup(group_name);
42 
43  if (not planner_config.empty())
44  setConfig(planner_config);
45 }
46 
48  const std::string &planner_config)
49  : MotionRequestBuilder(planner->getRobot())
50 {
51  setPlanningGroup(group_name);
52  setPlanner(planner);
53 
54  if (not planner_config.empty())
55  setConfig(planner_config);
56 }
57 
59  : MotionRequestBuilder(other.getRobot())
60 {
61  request_ = other.getRequestConst();
62 
63  const auto &planner = other.getPlanner();
64  if (planner)
65  setPlanner(planner);
66 }
67 
69 {
70  return std::make_shared<MotionRequestBuilder>(*this);
71 }
72 
74 {
76 
77  setWorkspaceBounds(Eigen::Vector3d::Constant(-constants::default_workspace_bound),
78  Eigen::Vector3d::Constant(constants::default_workspace_bound));
79  request_.allowed_planning_time = constants::default_allowed_planning_time;
80 }
81 
83 {
84  const auto &rname = robot_->getName();
85  const auto &pname = planner->getRobot()->getName();
86 
87  if (rname != pname)
88  {
89  RBX_ERROR("Conflicting robots `%s` and `%s` in request builder!", rname, pname);
90  throw Exception(1, "Invalid planner!");
91  }
92 
93  planner_ = planner;
94 }
95 
97 {
98  const auto &model = robot_->getModelConst();
99 
100  if (model->hasJointModelGroup(group_name))
101  {
102  group_name_ = group_name;
103  jmg_ = robot_->getModelConst()->getJointModelGroup(group_name_);
104 
105  request_.group_name = group_name_;
106  }
107  else
108  {
109  RBX_ERROR("Joint group `%s` does not exist in robot!", group_name);
110  throw Exception(1, "Invalid joint group name!");
111  }
112 }
113 
114 bool MotionRequestBuilder::setConfig(const std::string &requested_config)
115 {
116  if (not planner_)
117  {
118  RBX_INFO("No planner set! Using requested config `%s`", requested_config);
119  request_.planner_id = requested_config;
120  return true;
121  }
122 
123  const auto &configs = planner_->getPlannerConfigs();
124 
126  for (const auto &config : configs)
127  {
128  if (config.find(requested_config) != std::string::npos)
129  matches.emplace_back(config);
130  }
131 
132  if (matches.empty())
133  return false;
134 
135  const auto &found =
136  std::min_element(matches.begin(), matches.end(),
137  [](const std::string &a, const std::string &b) { return a.size() < b.size(); });
138 
140 
141  request_.planner_id = *found;
142  RBX_INFO("Requested Config: `%s`: Using planning config `%s`", requested_config, request_.planner_id);
143  return true;
144 }
145 
146 void MotionRequestBuilder::setWorkspaceBounds(const moveit_msgs::WorkspaceParameters &wp)
147 {
149  request_.workspace_parameters = wp;
150 }
151 
152 void MotionRequestBuilder::setWorkspaceBounds(const Eigen::Ref<const Eigen::VectorXd> &min,
153  const Eigen::Ref<const Eigen::VectorXd> &max)
154 {
155  moveit_msgs::WorkspaceParameters wp;
156  wp.min_corner.x = min[0];
157  wp.min_corner.y = min[1];
158  wp.min_corner.z = min[2];
159  wp.max_corner.x = max[0];
160  wp.max_corner.y = max[1];
161  wp.max_corner.z = max[2];
162 
163  setWorkspaceBounds(wp);
164 }
165 
167 {
168  if (request_.goal_constraints.size() != 1)
169  {
170  RBX_ERROR("Multiple goal constraints exist, cannot swap start with goal");
171  return false;
172  }
173 
174  if (request_.goal_constraints[0].joint_constraints.empty())
175  {
176  RBX_ERROR("No joint goal is specified, cannot swap start with goal");
177  return false;
178  }
179 
180  const auto &start = getStartConfiguration();
181  const auto &goal = getGoalConfiguration();
182  clearGoals();
183 
184  setStartConfiguration(goal);
185  setGoalConfiguration(start);
186  return true;
187 }
188 
190 {
191  if (not jmg_)
192  {
193  RBX_ERROR("No planning group set!");
194  throw Exception(1, "No planning group set!");
195  }
196 
198  robot_->setStateMsgGroupState(request_.start_state, request_.group_name, joints);
199 }
200 
201 void MotionRequestBuilder::setStartConfiguration(const robot_state::RobotState &state)
202 {
205 }
206 
207 void MotionRequestBuilder::setStartConfiguration(const robot_state::RobotStatePtr &state)
208 {
209  setStartConfiguration(*state);
210 }
211 
213 {
214  setStartConfiguration(scene->getCurrentStateConst());
215 }
216 
218 {
219  // Attach object to current start configuration.
220  const auto &start = getStartConfiguration();
221  if (not scene->attachObject(*start, object))
222  return false;
223 
225  return true;
226 }
227 
229 {
230  auto copy = scene->deepCopy();
231  return attachObjectToStart(copy, object);
232 }
233 
235 {
236  if (not jmg_)
237  {
238  RBX_ERROR("No planning group set!");
239  throw Exception(1, "No planning group set!");
240  }
241 
243 
244  robot_state::RobotStatePtr state;
245  state.reset(new robot_state::RobotState(robot_->getModelConst()));
246  state->setJointGroupPositions(jmg_, joints);
247 
248  addGoalConfiguration(state);
249 }
250 
251 void MotionRequestBuilder::addGoalConfiguration(const robot_state::RobotStatePtr &state)
252 {
253  addGoalConfiguration(*state);
254 }
255 
256 void MotionRequestBuilder::addGoalConfiguration(const robot_state::RobotState &state)
257 {
258  if (not jmg_)
259  {
260  RBX_ERROR("No planning group set!");
261  throw Exception(1, "No planning group set!");
262  }
263 
265  request_.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(state, jmg_));
266 }
267 
269 {
270  if (not jmg_)
271  {
272  RBX_ERROR("No planning group set!");
273  throw Exception(1, "No planning group set!");
274  }
275 
276  if (group_name_ != query.group)
277  {
278  RBX_ERROR("Planning group in IK query `%1%` not the same as request `%2%`", query.group, group_name_);
279  throw Exception(1, "Mismatched query groups!");
280  }
281 
282  if (query.regions.size() > 1)
283  {
284  RBX_ERROR("Cannot set goal request from IK query with multiple targets!");
285  throw Exception(1, "Tried to set goal from multi-target request!");
286  }
287 
288  std::string tip_to_use = query.tips[0];
289  if (tip_to_use.empty())
290  {
291  const auto &tips = robot_->getSolverTipFrames(group_name_);
292  if (tips.empty() or tips.size() > 1)
293  {
294  RBX_ERROR("Unable to find tip frame for request.");
295  throw Exception(1, "Unable to find tip frame for request.");
296  }
297 
298  tip_to_use = tips[0];
299  }
300 
301  const std::string &base = robot_->getSolverBaseFrame(group_name_);
302  if (base.empty())
303  {
304  RBX_ERROR("Failed to get base frame for request.");
305  throw Exception(1, "Unable to find base frame for request.");
306  }
307 
308  addGoalRegion(tip_to_use, base, query.region_poses[0], query.regions[0], query.orientations[0],
309  query.tolerances[0]);
310 }
311 
312 void MotionRequestBuilder::addGoalPose(const std::string &ee_name, const std::string &base_name,
313  const RobotPose &pose, double tolerance)
314 {
315  auto copy = pose;
316  Eigen::Quaterniond orientation(pose.rotation());
317  copy.linear() = Eigen::Matrix3d::Identity();
318  addGoalRegion(ee_name, base_name, //
319  copy, Geometry::makeSphere(tolerance), //
320  orientation, {tolerance, tolerance, tolerance});
321 }
322 
323 void MotionRequestBuilder::addGoalRegion(const std::string &ee_name, const std::string &base_name,
324  const RobotPose &pose, const GeometryConstPtr &geometry,
325  const Eigen::Quaterniond &orientation,
326  const Eigen::Vector3d &tolerances)
327 {
329 
330  moveit_msgs::Constraints constraints;
331 
332  constraints.position_constraints.push_back(TF::getPositionConstraint(ee_name, base_name, pose, geometry));
333  constraints.orientation_constraints.push_back(
334  TF::getOrientationConstraint(ee_name, base_name, orientation, tolerances));
335 
336  request_.goal_constraints.push_back(constraints);
337 }
338 
340  const RobotPose &pose, const GeometryConstPtr &geometry,
341  const Eigen::Quaterniond &orientation,
342  const Eigen::Vector3d &tolerances, const RobotPose &offset,
343  const Eigen::Vector3d &axis, unsigned int n)
344 {
345  for (double angle = 0; angle < constants::two_pi; angle += constants::two_pi / n)
346  {
347  Eigen::Quaterniond rotation(Eigen::AngleAxisd(angle, axis));
348  RobotPose new_pose = pose * rotation * offset;
349  Eigen::Quaterniond new_orientation(rotation * orientation);
350 
351  addGoalRegion(ee_name, base_name, new_pose, geometry, new_orientation, tolerances);
352  }
353 }
354 
356  const RobotPose &pose, const GeometryConstPtr &cylinder,
357  double distance, double depth, unsigned int n)
358 {
359  // Grasping region to tile
360  auto box = Geometry::makeBox(depth, depth, cylinder->getDimensions()[1]);
361  RobotPose offset(Eigen::Translation3d(cylinder->getDimensions()[0] + distance, 0, 0));
362 
363  Eigen::Quaterniond orientation = Eigen::AngleAxisd(-constants::pi, Eigen::Vector3d::UnitX()) //
364  * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY()) //
365  * Eigen::AngleAxisd(constants::pi, Eigen::Vector3d::UnitZ());
366 
367  addGoalRotaryTile(ee_name, base_name, //
368  pose, box, orientation, {0.01, 0.01, 0.01}, //
369  offset, Eigen::Vector3d::UnitZ(), n);
370 }
371 
373 {
374  clearGoals();
375  addGoalConfiguration(joints);
376 }
377 
378 void MotionRequestBuilder::setGoalConfiguration(const robot_state::RobotStatePtr &state)
379 {
380  clearGoals();
381  addGoalConfiguration(state);
382 }
383 
384 void MotionRequestBuilder::setGoalConfiguration(const robot_state::RobotState &state)
385 {
386  clearGoals();
387  addGoalConfiguration(state);
388 }
389 
391 {
392  clearGoals();
393  addGoalFromIKQuery(query);
394 }
395 
396 void MotionRequestBuilder::setGoalPose(const std::string &ee_name, const std::string &base_name,
397  const RobotPose &pose, double tolerance)
398 {
399  clearGoals();
400  addGoalPose(ee_name, base_name, pose, tolerance);
401 }
402 
403 void MotionRequestBuilder::setGoalRegion(const std::string &ee_name, const std::string &base_name,
404  const RobotPose &pose, const GeometryConstPtr &geometry,
405  const Eigen::Quaterniond &orientation,
406  const Eigen::Vector3d &tolerances)
407 {
408  clearGoals();
409  addGoalRegion(ee_name, base_name, pose, geometry, orientation, tolerances);
410 }
411 
414 {
415  // Allocate samplers for each region
418  for (const auto &goal : request_.goal_constraints)
419  {
420  samplers.emplace_back(manager.selectSampler(scene->getSceneConst(), group_name_, goal));
421  samplers.back()->setGroupStateValidityCallback(scene->getGSVCF(false));
422  }
423 
424  clearGoals();
425 
426  // Clone start
427  robot_state::RobotState state = *robot_->getScratchStateConst();
428 
429  // Sample n_samples to add to new request
430  std::size_t n = n_samples;
431  while (n)
432  {
433  auto sampler = RNG::uniformSample(samplers);
434  if (sampler->sample(state) and (not callback or callback(state)))
435  {
436  addGoalConfiguration(state);
437  n--;
438  }
439  }
440 }
441 
443 {
445  request_.goal_constraints.clear();
446 }
447 
448 void MotionRequestBuilder::setAllowedPlanningTime(double allowed_planning_time)
449 {
451  request_.allowed_planning_time = allowed_planning_time;
452 }
453 
454 void MotionRequestBuilder::setNumPlanningAttempts(unsigned int num_planning_attempts)
455 {
457  request_.num_planning_attempts = num_planning_attempts;
458 }
459 
461  const RobotPose &pose, const GeometryConstPtr &geometry,
462  const Eigen::Quaterniond &orientation,
463  const Eigen::Vector3d &tolerances)
464 {
465  addPathPositionConstraint(ee_name, base_name, pose, geometry);
466  addPathOrientationConstraint(ee_name, base_name, orientation, tolerances);
467 }
468 
470  const RobotPose &pose, const GeometryConstPtr &geometry)
471 {
473  request_.path_constraints.position_constraints.push_back(
474  TF::getPositionConstraint(ee_name, base_name, pose, geometry));
475 }
476 
478  const std::string &base_name,
479  const Eigen::Quaterniond &orientation,
480  const Eigen::Vector3d &tolerances)
481 {
483  request_.path_constraints.orientation_constraints.push_back(
484  TF::getOrientationConstraint(ee_name, base_name, orientation, tolerances));
485 }
486 
487 moveit_msgs::Constraints &MotionRequestBuilder::getPathConstraints()
488 {
490  return request_.path_constraints;
491 }
492 
494 {
496  return request_;
497 }
498 
499 robot_state::RobotStatePtr MotionRequestBuilder::getStartConfiguration() const
500 {
501  auto start_state = robot_->allocState();
502 
503  moveit::core::robotStateMsgToRobotState(request_.start_state, *start_state);
504  start_state->update(true);
505 
506  return start_state;
507 }
508 
509 robot_state::RobotStatePtr MotionRequestBuilder::getGoalConfiguration() const
510 {
511  auto goal_state = robot_->allocState();
512 
513  if (request_.goal_constraints.size() != 1)
514  {
515  RBX_ERROR("Ambiguous goal, %lu goal goal_constraints exist, returning default goal",
516  request_.goal_constraints.size());
517  return goal_state;
518  }
519 
520  if (request_.goal_constraints[0].joint_constraints.empty())
521  {
522  RBX_ERROR("No joint constraints specified, returning default goal");
523  return goal_state;
524  }
525 
526  std::map<std::string, double> variable_map;
527  for (const auto &joint : request_.goal_constraints[0].joint_constraints)
528  variable_map[joint.joint_name] = joint.position;
529 
530  // Start state includes attached objects and values for the non-group links.
531  moveit::core::robotStateMsgToRobotState(request_.start_state, *goal_state);
532  goal_state->setVariablePositions(variable_map);
533  goal_state->update(true);
534 
535  return goal_state;
536 }
537 
539 {
540  return request_;
541 }
542 
544 {
545  return IO::YAMLToFile(IO::toNode(request_), file);
546 }
547 
549 {
551 
552  bool success = IO::fromYAMLFile(request_, file);
553  setPlanningGroup(request_.group_name);
554  return success;
555 }
556 
558 {
559  return robot_;
560 }
561 
563 {
564  return planner_;
565 }
566 
568 {
569  return group_name_;
570 }
571 
573 {
574  return request_.planner_id;
575 }
T back(T... args)
T begin(T... args)
ConstraintSamplerPtr selectSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr) const
Exception that contains a message and an error code.
Definition: util.h:15
A const shared pointer wrapper for robowflex::Geometry.
static GeometryPtr makeSphere(double radius)
Create a sphere.
Definition: geometry.cpp:43
static GeometryPtr makeBox(double x, double y, double z)
Create a box.
Definition: geometry.cpp:48
void incrementVersion()
Increment the version number of this object.
Definition: id.cpp:42
A shared pointer wrapper for robowflex::MotionRequestBuilder.
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
void addGoalPose(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, double tolerance=0.001)
Add a goal pose for the end-effector ee_name. Generates a sphere with radius tolerance as well as ori...
Definition: builder.cpp:312
bool swapStartWithGoal()
Swap the start and goal configurations. This is only possible when a single joint goal is specified,...
Definition: builder.cpp:166
void useSceneStateAsStart(const SceneConstPtr &scene)
Use the current scene state for the starting configuration.
Definition: builder.cpp:212
bool toYAMLFile(const std::string &file) const
Serialize the motion planning request to a YAML file file.
Definition: builder.cpp:543
planning_interface::MotionPlanRequest request_
The build request.
Definition: builder.h:444
void addGoalFromIKQuery(const Robot::IKQuery &query)
Add an IK query as a goal pose.
Definition: builder.cpp:268
void setAllowedPlanningTime(double allowed_planning_time)
Set the allowed planning time in the request.
Definition: builder.cpp:448
void clearGoals()
Clears all goals.
Definition: builder.cpp:442
robot_model::JointModelGroup * jmg_
Definition: builder.h:441
void addCylinderSideGrasp(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &cylinder, double distance, double depth, unsigned int n)
Adds a set of regions to grasp a cylinder from the side. This function assumes the X-axis of the end-...
Definition: builder.cpp:355
moveit_msgs::Constraints & getPathConstraints()
Get a reference to the current path constraints on the motion planning request.
Definition: builder.cpp:487
void setNumPlanningAttempts(unsigned int num_planning_attempts)
Set the number of planning attemps in the request.
Definition: builder.cpp:454
PlannerConstPtr planner_
The planner to build the request for.
Definition: builder.h:439
const RobotConstPtr robot_
The robot to build the request for.
Definition: builder.h:437
MotionRequestBuilderPtr clone() const
Clone this request.
Definition: builder.cpp:68
void addPathOrientationConstraint(const std::string &ee_name, const std::string &base_name, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Set an orientation constraint on the path. Sets the orientation constraint from orientation and XYZ E...
Definition: builder.cpp:477
void addPathPoseConstraint(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Set a pose constraint on the path. Sets the position constraint from geometry at a pose pose,...
Definition: builder.cpp:460
std::string group_name_
The group to plan for.
Definition: builder.h:440
bool attachObjectToStart(ScenePtr scene, const std::string &object)
Attach an object to the current request start state. Uses object from scene, and modifies the underly...
Definition: builder.cpp:217
static const std::string DEFAULT_CONFIG
Default planner configuration to use.
Definition: builder.h:446
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
const std::string & getPlannerConfig() const
Get the planner config.
Definition: builder.cpp:572
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
robot_state::RobotStatePtr getStartConfiguration() const
Get the start state of the request as a robot state.
Definition: builder.cpp:499
void setGoalPose(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, double tolerance=0.001)
Set a goal pose for the end-effector ee_name. Generates a sphere with radius tolerance as well as ori...
Definition: builder.cpp:396
bool fromYAMLFile(const std::string &file)
Load a planning request from a YAML file file.
Definition: builder.cpp:548
const RobotConstPtr & getRobot() const
Get the robot for this request.
Definition: builder.cpp:557
const PlannerConstPtr & getPlanner() const
Get the planner for this request.
Definition: builder.cpp:562
const std::string & getPlanningGroup() const
Get the planning group.
Definition: builder.cpp:567
void precomputeGoalConfigurations(std::size_t n_samples, const ScenePtr &scene, const ConfigurationValidityCallback &callback={})
Override the goals of this motion request with precomputed goal configurations (from the specified re...
Definition: builder.cpp:412
bool attachObjectToStartConst(const SceneConstPtr &scene, const std::string &object)
Attach an object to the current request start state. Uses object from scene, but does not modify the ...
Definition: builder.cpp:228
void addGoalConfiguration(const std::vector< double > &joints)
Add a goal configuration from a vector joints. All joints are assumed to be specified and in the defa...
Definition: builder.cpp:234
void setWorkspaceBounds(const moveit_msgs::WorkspaceParameters &wp)
Sets workspace bounds of the planning request.
Definition: builder.cpp:146
void initialize()
Sets defaults.
Definition: builder.cpp:73
void setPlanningGroup(const std::string &group_name)
Set the planning group to use for this request builder.
Definition: builder.cpp:96
planning_interface::MotionPlanRequest & getRequest()
Get a reference to the currently built motion planning request.
Definition: builder.cpp:493
void addGoalRegion(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Add a goal region for an end-effector ee_name. Sets the position constraint from geometry at a pose p...
Definition: builder.cpp:323
void addGoalRotaryTile(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances, const RobotPose &offset, const Eigen::Vector3d &axis, unsigned int n)
Tiles some geometry around a pose in base_name for the end-effector ee_name. The geometry is placed a...
Definition: builder.cpp:339
void setPlanner(const PlannerConstPtr &planner)
Set the Robowflex planner to use.
Definition: builder.cpp:82
void setGoalRegion(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Set a goal region for an end-effector ee_name. Sets the position constraint from geometry at a pose p...
Definition: builder.cpp:403
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
void setGoalFromIKQuery(const Robot::IKQuery &query)
Set the goal pose from an IK query.
Definition: builder.cpp:390
const planning_interface::MotionPlanRequest & getRequestConst() const
Get a const reference to the currently built motion planning request.
Definition: builder.cpp:538
MotionRequestBuilder(const RobotConstPtr &robot)
Constructor.
Definition: builder.cpp:27
void addPathPositionConstraint(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry)
Set a position constraint on the path. Sets the position constraint from geometry at a pose pose.
Definition: builder.cpp:469
robot_state::RobotStatePtr getGoalConfiguration() const
Get the goal state of the request as a robot state.
Definition: builder.cpp:509
A const shared pointer wrapper for robowflex::Planner.
A const shared pointer wrapper for robowflex::Robot.
A const shared pointer wrapper for robowflex::Scene.
A shared pointer wrapper for robowflex::Scene.
T emplace_back(T... args)
T empty(T... args)
T end(T... args)
#define RBX_ERROR(fmt,...)
Output a error logging message.
Definition: log.h:102
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
T min_element(T... args)
moveit_msgs::Constraints constructGoalConstraints(const robot_state::RobotState &state, const robot_model::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
moveit_msgs::MotionPlanRequest MotionPlanRequest
Functions for loading and animating robots in Blender.
bool YAMLToFile(const YAML::Node &node, const std::string &file)
Write the contents of a YAML node out to a potentially new file.
bool fromYAMLFile(moveit_msgs::PlanningScene &msg, const std::string &file)
Loads a planning scene from a YAML file.
Definition: yaml.cpp:1914
YAML::Node toNode(const geometry_msgs::Pose &msg)
Converts a pose message to YAML.
Definition: yaml.cpp:1874
Iter uniformSample(Iter start, Iter end)
Choose a random element between start and end.
Definition: random.h:121
moveit_msgs::OrientationConstraint getOrientationConstraint(const std::string &ee_name, const std::string &base_name, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Get an orientation constraint message.
Definition: tf.cpp:189
moveit_msgs::PositionConstraint getPositionConstraint(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry)
Get a position constraint message.
Definition: tf.cpp:169
static const double two_pi
Definition: constants.h:24
static const double default_workspace_bound
Definition: constants.h:36
static const double pi
Definition: constants.h:21
static const double default_allowed_planning_time
Definition: constants.h:37
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25
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.
const std::vector< std::string > tips
T size(T... args)
Robot IK Query options. IK queries in Robowflex consist of: a) A position specified by some geometric...
std::string group
Target joint group to do IK for.
EigenSTL::vector_Vector3d tolerances
XYZ Euler orientation tolerances.
std::vector< Eigen::Quaterniond > orientations
Target orientations.
std::vector< std::string > tips
List of end-effectors.
std::vector< GeometryConstPtr > regions
Regions to sample target positions from.
void callback(movegroup::MoveGroupHelper::Action &action)
Definition: tapedeck.cpp:20