43 #include <tf2/LinearMath/Quaternion.h>
44 #include <tf2/LinearMath/Vector3.h>
46 #include <unordered_map>
49 #include <cached_ik_kinematics_parameters.hpp>
80 Pose(
const geometry_msgs::msg::Pose& pose);
92 using IKEntry = std::pair<std::vector<Pose>, std::vector<double>>;
103 void initializeCache(
const std::string& robot_id,
const std::string& group_name,
const std::string& cache_name,
114 void updateCache(
const IKEntry& nearest,
const std::vector<Pose>& poses,
const std::vector<double>& config)
const;
120 double configDistance2(
const std::vector<double>& config1,
const std::vector<double>& config2)
const;
152 class 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;
185 template <
typename KinematicsPlugin,
typename =
bool>
190 template <
typename KinematicsPlugin>
191 struct 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
198 template <
typename KinematicsPlugin,
typename =
bool>
203 template <
typename KinematicsPlugin>
205 decltype(std::declval<KinematicsPlugin&>().KinematicsPlugin::initialize(
206 std::string(), std::string(), std::string(), std::vector<std::string>(), 0.0))>
212 template <
class KinematicsPlugin>
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 )
336 template <
class KinematicsPlugin>
346 const std::string& group_name,
const std::string& base_frame,
347 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
349 bool searchPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
350 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
351 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
~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
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::KinematicsQueryOptions KinematicsQueryOptions
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::KinematicsQueryOptions KinematicsQueryOptions
const IKEntry & getBestApproximateIKSolution(const std::vector< std::string > &fixed, const std::vector< std::string > &active, const std::vector< Pose > &poses) const
std::string getKey(const std::vector< std::string > &fixed, const std::vector< std::string > &active) const
std::string robot_description_
void updateCache(const IKEntry &nearest, const std::vector< std::string > &fixed, const std::vector< std::string > &active, const std::vector< Pose > &poses, const std::vector< double > &config)
IKCacheMap(const std::string &robot_description, const std::string &group_name, unsigned int num_joints)
A cache of inverse kinematic solutions.
double min_pose_distance_
unsigned int max_cache_size_
const IKEntry & getBestApproximateIKSolution(const Pose &pose) const
std::pair< std::vector< Pose >, std::vector< double > > IKEntry
unsigned int last_saved_cache_size_
void verifyCache(kdl_kinematics_plugin::KDLKinematicsPlugin &fk) const
NearestNeighborsGNAT< IKEntry * > ik_nn_
double configDistance2(const std::vector< double > &config1, const std::vector< double > &config2) const
std::filesystem::path cache_file_name_
void initializeCache(const std::string &robot_id, const std::string &group_name, const std::string &cache_name, const unsigned int num_joints, const Options &opts=Options())
double min_config_distance2_
void updateCache(const IKEntry &nearest, const Pose &pose, const std::vector< double > &config) const
IKCache(const IKCache &)=delete
std::vector< IKEntry > ik_cache_
Specific implementation of kinematics using KDL. This version supports any kinematic chain,...
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
double min_joint_config_distance
std::string cached_ik_path
unsigned int max_cache_size
class to represent end effector pose
double distance(const Pose &pose) const
tf2::Quaternion orientation
A set of options for the kinematics solver.