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>
31 robot_state::RobotState start_state(
robot_->getModelConst());
32 start_state.setToDefaultValues();
43 if (not planner_config.
empty())
54 if (not planner_config.
empty())
70 return std::make_shared<MotionRequestBuilder>(*
this);
84 const auto &rname =
robot_->getName();
85 const auto &pname = planner->getRobot()->getName();
89 RBX_ERROR(
"Conflicting robots `%s` and `%s` in request builder!", rname, pname);
98 const auto &model =
robot_->getModelConst();
100 if (model->hasJointModelGroup(group_name))
109 RBX_ERROR(
"Joint group `%s` does not exist in robot!", group_name);
110 throw Exception(1,
"Invalid joint group name!");
118 RBX_INFO(
"No planner set! Using requested config `%s`", requested_config);
119 request_.planner_id = requested_config;
123 const auto &configs =
planner_->getPlannerConfigs();
126 for (
const auto &config : configs)
128 if (config.find(requested_config) != std::string::npos)
142 RBX_INFO(
"Requested Config: `%s`: Using planning config `%s`", requested_config,
request_.planner_id);
153 const Eigen::Ref<const Eigen::VectorXd> &max)
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];
168 if (
request_.goal_constraints.size() != 1)
170 RBX_ERROR(
"Multiple goal constraints exist, cannot swap start with goal");
174 if (
request_.goal_constraints[0].joint_constraints.empty())
176 RBX_ERROR(
"No joint goal is specified, cannot swap start with goal");
194 throw Exception(1,
"No planning group set!");
221 if (not
scene->attachObject(*start,
object))
230 auto copy =
scene->deepCopy();
239 throw Exception(1,
"No planning group set!");
244 robot_state::RobotStatePtr state;
245 state.reset(
new robot_state::RobotState(
robot_->getModelConst()));
246 state->setJointGroupPositions(
jmg_, joints);
261 throw Exception(1,
"No planning group set!");
273 throw Exception(1,
"No planning group set!");
279 throw Exception(1,
"Mismatched query groups!");
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!");
289 if (tip_to_use.
empty())
294 RBX_ERROR(
"Unable to find tip frame for request.");
295 throw Exception(1,
"Unable to find tip frame for request.");
298 tip_to_use =
tips[0];
304 RBX_ERROR(
"Failed to get base frame for request.");
305 throw Exception(1,
"Unable to find base frame for request.");
316 Eigen::Quaterniond orientation(pose.rotation());
317 copy.linear() = Eigen::Matrix3d::Identity();
320 orientation, {tolerance, tolerance, tolerance});
325 const Eigen::Quaterniond &orientation,
326 const Eigen::Vector3d &tolerances)
330 moveit_msgs::Constraints constraints;
333 constraints.orientation_constraints.push_back(
336 request_.goal_constraints.push_back(constraints);
341 const Eigen::Quaterniond &orientation,
342 const Eigen::Vector3d &tolerances,
const RobotPose &offset,
343 const Eigen::Vector3d &axis,
unsigned int n)
347 Eigen::Quaterniond rotation(Eigen::AngleAxisd(angle, axis));
348 RobotPose new_pose = pose * rotation * offset;
349 Eigen::Quaterniond new_orientation(rotation * orientation);
351 addGoalRegion(ee_name, base_name, new_pose, geometry, new_orientation, tolerances);
357 double distance,
double depth,
unsigned int n)
361 RobotPose offset(Eigen::Translation3d(cylinder->getDimensions()[0] + distance, 0, 0));
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());
368 pose, box, orientation, {0.01, 0.01, 0.01},
369 offset, Eigen::Vector3d::UnitZ(), n);
405 const Eigen::Quaterniond &orientation,
406 const Eigen::Vector3d &tolerances)
409 addGoalRegion(ee_name, base_name, pose, geometry, orientation, tolerances);
418 for (
const auto &goal :
request_.goal_constraints)
421 samplers.
back()->setGroupStateValidityCallback(
scene->getGSVCF(
false));
427 robot_state::RobotState state = *
robot_->getScratchStateConst();
451 request_.allowed_planning_time = allowed_planning_time;
457 request_.num_planning_attempts = num_planning_attempts;
462 const Eigen::Quaterniond &orientation,
463 const Eigen::Vector3d &tolerances)
473 request_.path_constraints.position_constraints.push_back(
479 const Eigen::Quaterniond &orientation,
480 const Eigen::Vector3d &tolerances)
483 request_.path_constraints.orientation_constraints.push_back(
501 auto start_state =
robot_->allocState();
504 start_state->update(
true);
511 auto goal_state =
robot_->allocState();
513 if (
request_.goal_constraints.size() != 1)
515 RBX_ERROR(
"Ambiguous goal, %lu goal goal_constraints exist, returning default goal",
520 if (
request_.goal_constraints[0].joint_constraints.empty())
522 RBX_ERROR(
"No joint constraints specified, returning default goal");
527 for (
const auto &joint :
request_.goal_constraints[0].joint_constraints)
528 variable_map[joint.joint_name] = joint.position;
532 goal_state->setVariablePositions(variable_map);
533 goal_state->update(
true);
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.
A const shared pointer wrapper for robowflex::Geometry.
static GeometryPtr makeSphere(double radius)
Create a sphere.
static GeometryPtr makeBox(double x, double y, double z)
Create a box.
void incrementVersion()
Increment the version number of this object.
A shared pointer wrapper for robowflex::MotionRequestBuilder.
A helper class to build motion planning requests for a robowflex::Planner.
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...
bool swapStartWithGoal()
Swap the start and goal configurations. This is only possible when a single joint goal is specified,...
void useSceneStateAsStart(const SceneConstPtr &scene)
Use the current scene state for the starting configuration.
bool toYAMLFile(const std::string &file) const
Serialize the motion planning request to a YAML file file.
planning_interface::MotionPlanRequest request_
The build request.
void addGoalFromIKQuery(const Robot::IKQuery &query)
Add an IK query as a goal pose.
void setAllowedPlanningTime(double allowed_planning_time)
Set the allowed planning time in the request.
void clearGoals()
Clears all goals.
robot_model::JointModelGroup * jmg_
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-...
moveit_msgs::Constraints & getPathConstraints()
Get a reference to the current path constraints on the motion planning request.
void setNumPlanningAttempts(unsigned int num_planning_attempts)
Set the number of planning attemps in the request.
PlannerConstPtr planner_
The planner to build the request for.
const RobotConstPtr robot_
The robot to build the request for.
MotionRequestBuilderPtr clone() const
Clone this request.
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...
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,...
std::string group_name_
The group to plan for.
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...
static const std::string DEFAULT_CONFIG
Default planner configuration to use.
bool setConfig(const std::string &requested_config)
Set the planning configuration to use for the motion planning request. Attempts to match requested_co...
const std::string & getPlannerConfig() const
Get the planner config.
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...
robot_state::RobotStatePtr getStartConfiguration() const
Get the start state of the request as a robot state.
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...
bool fromYAMLFile(const std::string &file)
Load a planning request from a YAML file file.
const RobotConstPtr & getRobot() const
Get the robot for this request.
const PlannerConstPtr & getPlanner() const
Get the planner for this request.
const std::string & getPlanningGroup() const
Get the planning group.
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...
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 ...
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...
void setWorkspaceBounds(const moveit_msgs::WorkspaceParameters &wp)
Sets workspace bounds of the planning request.
void initialize()
Sets defaults.
void setPlanningGroup(const std::string &group_name)
Set the planning group to use for this request builder.
planning_interface::MotionPlanRequest & getRequest()
Get a reference to the currently built motion planning request.
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...
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...
void setPlanner(const PlannerConstPtr &planner)
Set the Robowflex planner to use.
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...
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...
void setGoalFromIKQuery(const Robot::IKQuery &query)
Set the goal pose from an IK query.
const planning_interface::MotionPlanRequest & getRequestConst() const
Get a const reference to the currently built motion planning request.
MotionRequestBuilder(const RobotConstPtr &robot)
Constructor.
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.
robot_state::RobotStatePtr getGoalConfiguration() const
Get the goal state of the request as a robot state.
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)
#define RBX_ERROR(fmt,...)
Output a error logging message.
#define RBX_INFO(fmt,...)
Output a info logging message.
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.
YAML::Node toNode(const geometry_msgs::Pose &msg)
Converts a pose message to YAML.
Iter uniformSample(Iter start, Iter end)
Choose a random element between start and end.
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.
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.
static const double two_pi
static const double default_workspace_bound
static const double default_allowed_planning_time
Main namespace. Contains all library classes and functions.
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.
Functions for loading and animating scenes in Blender.
const std::vector< std::string > tips
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.
RobotPoseVector region_poses
Poses of regions.
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)