42 template <
class KinematicsPlugin>
47 template <
class KinematicsPlugin>
52 template <
class KinematicsPlugin>
54 const std::string& cache_name)
63 kinematics::KinematicsBase::lookupParam<std::string>(node_,
"cached_ik_path", opts.
cached_ik_path,
"");
65 cache_.initializeCache(robot_id, group_name, cache_name, KinematicsPlugin::getJointNames().size(), opts);
73 template <
class KinematicsPlugin>
76 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
double search_discretization)
79 if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
82 std::string cache_name = base_frame;
83 std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
85 KinematicsPlugin::getJointNames().size());
89 template <
class KinematicsPlugin>
91 const std::vector<double>& ik_seed_state,
92 std::vector<double>& solution,
93 moveit_msgs::msg::MoveItErrorCodes& error_code,
97 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
98 bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code,
options) ||
99 KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code,
options);
101 cache_.updateCache(nearest, pose, solution);
102 return solution_found;
105 template <
class KinematicsPlugin>
107 const std::vector<double>& ik_seed_state,
108 double timeout, std::vector<double>& solution,
109 moveit_msgs::msg::MoveItErrorCodes& error_code,
112 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
114 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
115 bool solution_found =
116 KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code,
options);
119 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
121 KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution, error_code,
options);
124 cache_.updateCache(nearest, pose, solution);
125 return solution_found;
128 template <
class KinematicsPlugin>
130 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
131 const std::vector<double>& consistency_limits, std::vector<double>& solution,
134 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
136 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
137 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
138 solution, error_code,
options);
141 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
142 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
143 solution, error_code,
options);
146 cache_.updateCache(nearest, pose, solution);
147 return solution_found;
150 template <
class KinematicsPlugin>
152 const std::vector<double>& ik_seed_state,
153 double timeout, std::vector<double>& solution,
155 moveit_msgs::msg::MoveItErrorCodes& error_code,
158 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
160 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
161 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution,
162 solution_callback, error_code,
options);
165 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
166 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution,
167 solution_callback, error_code,
options);
170 cache_.updateCache(nearest, pose, solution);
171 return solution_found;
174 template <
class KinematicsPlugin>
176 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
177 const std::vector<double>& consistency_limits, std::vector<double>& solution,
const IKCallbackFn& solution_callback,
180 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
182 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
183 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
184 solution, solution_callback, error_code,
options);
187 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
188 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
189 solution, solution_callback, error_code,
options);
192 cache_.updateCache(nearest, pose, solution);
193 return solution_found;
196 template <
class KinematicsPlugin>
198 const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
double timeout,
199 const std::vector<double>& consistency_limits, std::vector<double>& solution,
const IKCallbackFn& solution_callback,
203 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
204 std::vector<Pose> poses(ik_poses.size());
205 for (
unsigned int i = 0; i < poses.size(); ++i)
206 poses[i] =
Pose(ik_poses[i]);
208 bool solution_found =
209 KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
210 solution_callback, error_code,
options, context_state);
213 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
215 KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
216 solution_callback, error_code,
options, context_state);
221 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
bool lookupParam(const rclcpp::Node::SharedPtr &node, const std::string ¶m, T &val, const T &default_val) const
Enables kinematics plugins access to parameters that are defined for the private namespace and inside...
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.