42template <
class KinematicsPlugin>
47template <
class KinematicsPlugin>
52template <
class KinematicsPlugin>
54 const std::string& cache_name)
62 cache_.initializeCache(robot_id, group_name, cache_name, KinematicsPlugin::getJointNames().size(), opts);
70template <
class KinematicsPlugin>
73 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
double search_discretization)
76 if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
79 std::string cache_name = base_frame;
80 std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
82 KinematicsPlugin::getJointNames().size());
86template <
class KinematicsPlugin>
88 const std::vector<double>& ik_seed_state,
89 std::vector<double>& solution,
90 moveit_msgs::msg::MoveItErrorCodes& error_code,
94 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
95 bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code, options) ||
96 KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code, options);
98 cache_.updateCache(nearest, pose, solution);
99 return solution_found;
102template <
class KinematicsPlugin>
104 const std::vector<double>& ik_seed_state,
105 double timeout, std::vector<double>& solution,
106 moveit_msgs::msg::MoveItErrorCodes& error_code,
109 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
111 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
112 bool solution_found =
113 KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code, options);
116 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
118 KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution, error_code, options);
121 cache_.updateCache(nearest, pose, solution);
122 return solution_found;
125template <
class KinematicsPlugin>
127 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
128 const std::vector<double>& consistency_limits, std::vector<double>& solution,
131 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
133 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
134 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
135 solution, error_code, options);
138 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
139 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
140 solution, error_code, options);
143 cache_.updateCache(nearest, pose, solution);
144 return solution_found;
147template <
class KinematicsPlugin>
149 const std::vector<double>& ik_seed_state,
150 double timeout, std::vector<double>& solution,
152 moveit_msgs::msg::MoveItErrorCodes& error_code,
155 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
157 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
158 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution,
159 solution_callback, error_code, options);
162 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
163 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution,
164 solution_callback, error_code, options);
167 cache_.updateCache(nearest, pose, solution);
168 return solution_found;
171template <
class KinematicsPlugin>
173 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
174 const std::vector<double>& consistency_limits, std::vector<double>& solution,
const IKCallbackFn& solution_callback,
177 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
179 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
180 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
181 solution, solution_callback, error_code, options);
184 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
185 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
186 solution, solution_callback, error_code, options);
189 cache_.updateCache(nearest, pose, solution);
190 return solution_found;
193template <
class KinematicsPlugin>
195 const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
double timeout,
196 const std::vector<double>& consistency_limits, std::vector<double>& solution,
const IKCallbackFn& solution_callback,
200 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
201 std::vector<Pose> poses(ik_poses.size());
202 for (
unsigned int i = 0; i < poses.size(); ++i)
203 poses[i] =
Pose(ik_poses[i]);
205 bool solution_found =
206 KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
207 solution_callback, error_code, options, context_state);
210 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
212 KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
213 solution_callback, error_code, options, context_state);
218 return solution_found;
~CachedIKKinematicsPlugin() override
CachedIKKinematicsPlugin()
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
kinematics::KinematicsBase::IKCallbackFn IKCallbackFn
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
bool searchPositionIK(const std::vector< geometry_msgs::msg::Pose > &ik_poses, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const override
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
kinematics::KinematicsBase::IKCallbackFn IKCallbackFn
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
const std::string & getName() const
Get the model name.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
double min_joint_config_distance
std::string cached_ik_path
unsigned int max_cache_size
class to represent end effector pose
A set of options for the kinematics solver.