39 #include <moveit/task_constructor/container.h>
40 #include <moveit/task_constructor/cost_queue.h>
41 #include <geometry_msgs/PoseStamped.h>
42 #include <Eigen/Geometry>
46 MOVEIT_CLASS_FORWARD(RobotState);
47 MOVEIT_CLASS_FORWARD(JointModelGroup);
52 namespace task_constructor {
71 ComputeIK(
const std::string& name =
"IK", Stage::pointer&& child = Stage::pointer());
73 void reset()
override;
74 void init(
const core::RobotModelConstPtr& robot_model)
override;
77 bool canCompute()
const override;
79 void compute()
override;
81 void setEndEffector(
const std::string& eef) {
setProperty(
"eef", eef); }
82 void setGroup(
const std::string& group) {
setProperty(
"group", group); }
86 void setIKFrame(
const Eigen::Isometry3d& pose,
const std::string& link);
88 void setIKFrame(
const T& p,
const std::string& link) {
89 Eigen::Isometry3d pose;
101 void setTargetPose(
const Eigen::Isometry3d& pose,
const std::string& frame =
"");
102 template <
typename T>
103 void setTargetPose(
const T& p,
const std::string& frame =
"") {
104 Eigen::Isometry3d pose;
109 void setMaxIKSolutions(uint32_t n) {
setProperty(
"max_ik_solutions", n); }
110 void setIgnoreCollisions(
bool flag) {
setProperty(
"ignore_collisions", flag); }
111 void setMinSolutionDistance(
double distance) {
setProperty(
"min_solution_distance", distance); }
abstract base class for solutions (primitive and sequences)
Definition: storage.h:269
void setProperty(const std::string &name, const boost::any &value)
Set a previously declared property to a new value.
Definition: stage.cpp:443
Definition: container.h:214
Definition: compute_ik.h:69
void onNewSolution(const SolutionBase &s) override
called by a (direct) child when a new solution becomes available
Definition: compute_ik.cpp:219
void setTargetPose(const geometry_msgs::PoseStamped &pose)
Definition: compute_ik.h:100
void setIKFrame(const geometry_msgs::PoseStamped &pose)
setters for IK frame
Definition: compute_ik.h:85
void reset() override
reset stage, clearing all solutions, interfaces, inherited properties.
Definition: compute_ik.cpp:190
ordered<ValueType> provides an adapter for a std::list to allow sorting.
Definition: cost_queue.h:30