41 #include <planning_models/kinematic_state.h>
43 #include <urdf_interface/model.h>
44 #include <urdf/model.h>
45 #include <srdf/model.h>
53 const std::string& kinematics_solver_name,
const std::string& group_name,
54 const std::string& base_frame,
const std::string& tip_frame,
double search_discretization)
57 std::make_shared<pluginlib::ClassLoader<kinematics::KinematicsBase>>(
"kinematics_base",
"kinematics::"
62 kinematics_solver_ = kinematics_loader_->createClassInstance(kinematics_solver_name);
64 catch (pluginlib::PluginlibException& ex)
66 ROS_ERROR(
"The plugin failed to load. Error: %s", ex.what());
70 if (!kinematics_solver_->
initialize(group_name, base_frame, tip_frame, search_discretization))
72 ROS_ERROR(
"Could not initialize solver");
77 const srdf::ModelSharedPtr& srdf =
rdf_loader.getSRDF();
78 const urdf::ModelInterfaceSharedPtr& urdf_model =
rdf_loader.getURDF();
79 kinematic_model_ = std::make_shared<planning_models::RobotModel>(urdf_model, srdf);
81 if (!
initialize((kinematics::KinematicsBaseConstPtr&)kinematics_solver_,
82 (planning_models::RobotModelConstPtr&)kinematic_model_,
opt))
virtual 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)
Initialization function for the kinematics, for use with kinematic chain IK solvers.
bool initialize(kinematics::KinematicsBaseConstPtr &solver, const planning_models::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt)
Initialize the cache class.
bool init(const kinematics_cache::KinematicsCache::Options &opt, const std::string &kinematics_solver_name, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Initialization function.