44 #if __has_include(<tf2/LinearMath/Quaternion.hpp>)
45 #include <tf2/LinearMath/Quaternion.hpp>
47 #include <tf2/LinearMath/Quaternion.h>
49 #if __has_include(<tf2/LinearMath/Vector3.hpp>)
50 #include <tf2/LinearMath/Vector3.hpp>
52 #include <tf2/LinearMath/Vector3.h>
55 #include <unordered_map>
61 static const rclcpp::Logger LOGGER =
62 rclcpp::get_logger(
"moveit_cached_ik_kinematics_plugin.cached_ik_kinematics_plugin");
89 Pose(
const geometry_msgs::msg::Pose& pose);
101 using IKEntry = std::pair<std::vector<Pose>, std::vector<double>>;
112 void initializeCache(
const std::string& robot_id,
const std::string& group_name,
const std::string& cache_name,
123 void updateCache(
const IKEntry& nearest,
const std::vector<Pose>& poses,
const std::vector<double>& config)
const;
129 double configDistance2(
const std::vector<double>& config1,
const std::vector<double>& config2)
const;
161 class IKCacheMap :
public std::unordered_map<std::string, IKCache*>
167 IKCacheMap(
const std::string& robot_description,
const std::string& group_name,
unsigned int num_joints);
174 const std::vector<std::string>& active,
175 const std::vector<Pose>& poses)
const;
181 const std::vector<std::string>& active,
const std::vector<Pose>& poses,
182 const std::vector<double>& config);
185 std::string
getKey(
const std::vector<std::string>& fixed,
const std::vector<std::string>& active)
const;
194 template <
typename KinematicsPlugin,
typename =
bool>
199 template <
typename KinematicsPlugin>
200 struct HasRobotModelApi<KinematicsPlugin, decltype(std::declval<KinematicsPlugin&>().initialize(
201 std::declval<const rclcpp::Node::SharedPtr&>(),
202 std::declval<const moveit::core::RobotModel&>(), std::string(),
203 std::string(), std::vector<std::string>(), 0.0))> : std::true_type
207 template <
typename KinematicsPlugin,
typename =
bool>
212 template <
typename KinematicsPlugin>
214 decltype(std::declval<KinematicsPlugin&>().KinematicsPlugin::initialize(
215 std::string(), std::string(), std::string(), std::vector<std::string>(), 0.0))>
221 template <
class KinematicsPlugin>
237 const std::string& group_name,
const std::string& base_frame,
238 const std::vector<std::string>& tip_frames,
double search_discretization)
override
241 return initializeImpl(node, robot_model, group_name, base_frame, tip_frames, search_discretization);
244 bool getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
245 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, std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
252 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
253 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
254 moveit_msgs::msg::MoveItErrorCodes& error_code,
257 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
258 double timeout, std::vector<double>& solution,
const IKCallbackFn& solution_callback,
259 moveit_msgs::msg::MoveItErrorCodes& error_code,
262 bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
263 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
264 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
268 rclcpp::Node::SharedPtr node_;
272 void initCache(
const std::string& robot_id,
const std::string& group_name,
const std::string& cache_name);
277 template <
class T = KinematicsPlugin>
278 typename std::enable_if<HasRobotModelApi<T>::value,
bool>
::type
280 const std::string& group_name,
const std::string& base_frame,
281 const std::vector<std::string>& tip_frames,
double search_discretization)
283 if (tip_frames.size() != 1)
285 RCLCPP_ERROR(LOGGER,
"This solver does not support multiple tip frames");
290 if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
292 initCache(robot_model.
getName(), group_name, base_frame + tip_frames[0]);
296 template <
class T = KinematicsPlugin>
297 typename std::enable_if<!HasRobotModelApi<T>::value,
bool>
::type
299 const std::string& ,
const std::string& ,
300 const std::vector<std::string>& ,
double )
305 template <
class T = KinematicsPlugin>
306 typename std::enable_if<HasRobotDescApi<T>::value,
bool>
::type
307 initializeImpl(
const std::string& robot_description,
const std::string& group_name,
const std::string& base_frame,
308 const std::string& tip_frame,
double search_discretization)
311 if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frame, search_discretization))
313 initCache(robot_description, group_name, base_frame + tip_frame);
317 template <
class T = KinematicsPlugin>
318 typename std::enable_if<!HasRobotDescApi<T>::value,
bool>
::type
319 initializeImpl(
const std::string& ,
const std::string& ,
const std::string& ,
320 const std::string& ,
double )
337 template <
class KinematicsPlugin>
347 const std::string& group_name,
const std::string& base_frame,
348 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
350 bool searchPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
351 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
352 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.
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.