152class IKCacheMap :
public std::unordered_map<std::string, IKCache*>
158 IKCacheMap(
const std::string& robot_description,
const std::string& group_name,
unsigned int num_joints);
165 const std::vector<std::string>& active,
166 const std::vector<Pose>& poses)
const;
172 const std::vector<std::string>& active,
const std::vector<Pose>& poses,
173 const std::vector<double>& config);
176 std::string
getKey(
const std::vector<std::string>& fixed,
const std::vector<std::string>& active)
const;
191struct HasRobotModelApi<KinematicsPlugin, decltype(std::declval<KinematicsPlugin&>().initialize(
192 std::declval<const rclcpp::Node::SharedPtr&>(),
193 std::declval<const moveit::core::RobotModel&>(), std::string(),
194 std::string(), std::vector<std::string>(), 0.0))> : std::true_type
228 const std::string& group_name,
const std::string& base_frame,
229 const std::vector<std::string>& tip_frames,
double search_discretization)
override
233 std::string kinematics_param_prefix =
"robot_description_kinematics." + group_name;
234 param_listener_ = std::make_shared<cached_ik_kinematics::ParamListener>(node, kinematics_param_prefix);
235 params_ = param_listener_->get_params();
237 return initializeImpl(node, robot_model, group_name, base_frame, tip_frames, search_discretization);
240 bool getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
241 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
244 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
245 double timeout, std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
248 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
249 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
250 moveit_msgs::msg::MoveItErrorCodes& error_code,
253 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
254 double timeout, std::vector<double>& solution,
const IKCallbackFn& solution_callback,
255 moveit_msgs::msg::MoveItErrorCodes& error_code,
258 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
259 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
260 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
264 rclcpp::Node::SharedPtr node_;
265 std::shared_ptr<cached_ik_kinematics::ParamListener> param_listener_;
266 cached_ik_kinematics::Params params_;
270 void initCache(
const std::string& robot_id,
const std::string& group_name,
const std::string& cache_name);
275 template <
class T = KinematicsPlugin>
276 typename std::enable_if<HasRobotModelApi<T>::value,
bool>::type
278 const std::string& group_name,
const std::string& base_frame,
279 const std::vector<std::string>& tip_frames,
double search_discretization)
281 if (tip_frames.size() != 1)
284 "This solver does not support multiple tip frames");
289 if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
291 initCache(robot_model.
getName(), group_name, base_frame + tip_frames[0]);
295 template <
class T = KinematicsPlugin>
296 typename std::enable_if<!HasRobotModelApi<T>::value,
bool>::type
298 const std::string& ,
const std::string& ,
299 const std::vector<std::string>& ,
double )
304 template <
class T = KinematicsPlugin>
305 typename std::enable_if<HasRobotDescApi<T>::value,
bool>::type
306 initializeImpl(
const std::string& robot_description,
const std::string& group_name,
const std::string& base_frame,
307 const std::string& tip_frame,
double search_discretization)
310 if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frame, search_discretization))
312 initCache(robot_description, group_name, base_frame + tip_frame);
316 template <
class T = KinematicsPlugin>
317 typename std::enable_if<!HasRobotDescApi<T>::value,
bool>::type
318 initializeImpl(
const std::string& ,
const std::string& ,
const std::string& ,
319 const std::string& ,
double )
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