37 #include <moveit_msgs/srv/get_position_ik.hpp> 
   39 #include <class_loader/class_loader.hpp> 
   45 #include <Eigen/Geometry> 
   52 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_srv_kinematics_plugin.srv_kinematics_plugin");
 
   59                                      const std::string& group_name, 
const std::string& base_frame,
 
   60                                      const std::vector<std::string>& tip_frames, 
double search_discretization)
 
   65   RCLCPP_INFO(
LOGGER, 
"SrvKinematicsPlugin initializing");
 
   67   storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
 
   68   joint_model_group_ = 
robot_model_->getJointModelGroup(group_name);
 
   69   if (!joint_model_group_)
 
   74     std::cout << 
"Joint Model Variable Names: ------------------------------------------- \n ";
 
   75     const std::vector<std::string> jm_names = joint_model_group_->
getVariableNames();
 
   76     std::copy(jm_names.begin(), jm_names.end(), std::ostream_iterator<std::string>(std::cout, 
"\n"));
 
   82   RCLCPP_INFO_STREAM(
LOGGER, 
"Dimension planning group '" 
   83                                  << group_name << 
"': " << dimension_
 
   88   for (std::size_t i = 0; i < joint_model_group_->
getJointModels().size(); ++i)
 
   95     RCLCPP_ERROR(
LOGGER, 
"tip links available:");
 
  104       RCLCPP_ERROR(
LOGGER, 
"Could not find tip name '%s' in joint group '%s'", tip_frame.c_str(), group_name.c_str());
 
  107     ik_group_info_.link_names.push_back(tip_frame);
 
  111   RCLCPP_DEBUG(
LOGGER, 
"Looking for ROS service name on rosparam server with param: " 
  112                        "/kinematics_solver_service_name");
 
  113   std::string ik_service_name;
 
  114   lookupParam(node_, 
"kinematics_solver_service_name", ik_service_name, std::string(
"solve_ik"));
 
  117   robot_state_ = std::make_shared<moveit::core::RobotState>(
robot_model_);
 
  118   robot_state_->setToDefaultValues();
 
  121   ik_service_client_ = node_->create_client<moveit_msgs::srv::GetPositionIK>(ik_service_name);
 
  123   if (!ik_service_client_->wait_for_service(std::chrono::seconds(1)))  
 
  124     RCLCPP_WARN_STREAM(
LOGGER,
 
  125                        "Unable to connect to ROS service client with name: " << ik_service_client_->get_service_name());
 
  127     RCLCPP_INFO_STREAM(
LOGGER,
 
  128                        "Service client started with ROS service name: " << ik_service_client_->get_service_name());
 
  131   RCLCPP_DEBUG(
LOGGER, 
"ROS service-based kinematics solver initialized");
 
  137   if (num_possible_redundant_joints_ < 0)
 
  139     RCLCPP_ERROR(
LOGGER, 
"This group cannot have redundant joints");
 
  142   if (
int(redundant_joints.size()) > num_possible_redundant_joints_)
 
  144     RCLCPP_ERROR(
LOGGER, 
"This group can only have %d redundant joints", num_possible_redundant_joints_);
 
  151 bool SrvKinematicsPlugin::isRedundantJoint(
unsigned int index)
 const 
  154     if (redundant_joint_indice == index)
 
  159 int SrvKinematicsPlugin::getJointIndex(
const std::string& 
name)
 const 
  161   for (
unsigned int i = 0; i < ik_group_info_.joint_names.size(); ++i)
 
  163     if (ik_group_info_.joint_names[i] == 
name)
 
  169 bool SrvKinematicsPlugin::timedOut(
const rclcpp::Time& start_time, 
double duration)
 const 
  171   return ((node_->now() - start_time).seconds() >= duration);
 
  175                                         const std::vector<double>& ik_seed_state, std::vector<double>& solution,
 
  176                                         moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  179   std::vector<double> consistency_limits;
 
  186                                            const std::vector<double>& ik_seed_state, 
double timeout,
 
  187                                            std::vector<double>& solution,
 
  188                                            moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  191   std::vector<double> consistency_limits;
 
  198                                            const std::vector<double>& ik_seed_state, 
double timeout,
 
  199                                            const std::vector<double>& consistency_limits, std::vector<double>& solution,
 
  200                                            moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  208                                            const std::vector<double>& ik_seed_state, 
double timeout,
 
  209                                            std::vector<double>& solution, 
const IKCallbackFn& solution_callback,
 
  210                                            moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  213   std::vector<double> consistency_limits;
 
  214   return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
 
  219                                            const std::vector<double>& ik_seed_state, 
double timeout,
 
  220                                            const std::vector<double>& consistency_limits, std::vector<double>& solution,
 
  222                                            moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  226   std::vector<geometry_msgs::msg::Pose> ik_poses;
 
  227   ik_poses.push_back(ik_pose);
 
  229   return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
 
  234                                            const std::vector<double>& ik_seed_state, 
double ,
 
  235                                            const std::vector<double>& ,
 
  236                                            std::vector<double>& solution, 
const IKCallbackFn& solution_callback,
 
  237                                            moveit_msgs::msg::MoveItErrorCodes& error_code,
 
  244     RCLCPP_ERROR(
LOGGER, 
"kinematics not active");
 
  245     error_code.val = error_code.NO_IK_SOLUTION;
 
  250   if (ik_seed_state.size() != dimension_)
 
  252     RCLCPP_ERROR_STREAM(
LOGGER,
 
  253                         "Seed state must have size " << dimension_ << 
" instead of size " << ik_seed_state.size());
 
  254     error_code.val = error_code.NO_IK_SOLUTION;
 
  261     RCLCPP_ERROR_STREAM(
LOGGER, 
"Mismatched number of pose requests (" << ik_poses.size() << 
") to tip frames (" 
  263                                                                        << 
") in searchPositionIK");
 
  264     error_code.val = error_code.NO_IK_SOLUTION;
 
  269   auto ik_srv = std::make_shared<moveit_msgs::srv::GetPositionIK::Request>();
 
  270   ik_srv->ik_request.avoid_collisions = 
true;
 
  274   robot_state_->setJointGroupPositions(joint_model_group_, ik_seed_state);
 
  278   geometry_msgs::msg::PoseStamped ik_pose_st;
 
  283     for (std::size_t i = 0; i < 
tip_frames_.size(); ++i)
 
  285       ik_pose_st.pose = ik_poses[i];
 
  286       ik_srv->ik_request.pose_stamped_vector.push_back(ik_pose_st);
 
  287       ik_srv->ik_request.ik_link_names.push_back(
tip_frames_[i]);
 
  292     ik_pose_st.pose = ik_poses[0];
 
  295     ik_srv->ik_request.pose_stamped = ik_pose_st;
 
  299   RCLCPP_DEBUG(
LOGGER, 
"Calling service: %s", ik_service_client_->get_service_name());
 
  300   auto result_future = ik_service_client_->async_send_request(ik_srv);
 
  301   const auto& response = result_future.get();
 
  302   if (rclcpp::spin_until_future_complete(node_, result_future) == rclcpp::FutureReturnCode::SUCCESS)
 
  305     error_code.val = response->error_code.val;
 
  306     if (error_code.val != error_code.SUCCESS)
 
  313       switch (error_code.val)
 
  315         case moveit_msgs::msg::MoveItErrorCodes::FAILURE:
 
  316           RCLCPP_ERROR(
LOGGER, 
"Service failed with with error code: FAILURE");
 
  318         case moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION:
 
  319           RCLCPP_DEBUG(
LOGGER, 
"Service failed with with error code: NO IK SOLUTION");
 
  322           RCLCPP_DEBUG_STREAM(
LOGGER, 
"Service failed with with error code: " << error_code.val);
 
  329     RCLCPP_DEBUG_STREAM(
LOGGER, 
"Service call failed to connect to service: " << ik_service_client_->get_service_name());
 
  330     error_code.val = error_code.FAILURE;
 
  336     RCLCPP_ERROR(
LOGGER, 
"An error occurred converting received robot state message into internal robot state.");
 
  337     error_code.val = error_code.FAILURE;
 
  342   robot_state_->copyJointGroupPositions(joint_model_group_, solution);
 
  345   if (solution_callback)
 
  347     RCLCPP_DEBUG(
LOGGER, 
"Calling solution callback on IK solution");
 
  350     solution_callback(ik_poses[0], solution, error_code);
 
  352     if (error_code.val != error_code.SUCCESS)
 
  354       switch (error_code.val)
 
  356         case moveit_msgs::msg::MoveItErrorCodes::FAILURE:
 
  357           RCLCPP_ERROR(
LOGGER, 
"IK solution callback failed with with error code: FAILURE");
 
  359         case moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION:
 
  360           RCLCPP_ERROR(
LOGGER, 
"IK solution callback failed with with error code: " 
  364           RCLCPP_ERROR_STREAM(
LOGGER, 
"IK solution callback failed with with error code: " << error_code.val);
 
  370   RCLCPP_INFO(
LOGGER, 
"IK Solver Succeeded!");
 
  375                                         const std::vector<double>& joint_angles,
 
  376                                         std::vector<geometry_msgs::msg::Pose>& poses)
 const 
  380     RCLCPP_ERROR(
LOGGER, 
"kinematics not active");
 
  383   poses.resize(link_names.size());
 
  384   if (joint_angles.size() != dimension_)
 
  386     RCLCPP_ERROR(
LOGGER, 
"Joint angles vector must have size: %d", dimension_);
 
  390   RCLCPP_ERROR(
LOGGER, 
"Forward kinematics not implemented");
 
  397   return ik_group_info_.joint_names;
 
  402   return ik_group_info_.link_names;
 
Provides an interface for kinematics solvers.
 
void storeValues(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)
 
std::vector< unsigned int > redundant_joint_indices_
 
static const rclcpp::Logger LOGGER
 
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...
 
virtual const std::vector< std::string > & getTipFrames() const
Return the names of the tip frames of the kinematic tree on which the solver is operating....
 
std::vector< std::string > tip_frames_
 
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.
 
moveit::core::RobotModelConstPtr robot_model_
 
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
 
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
 
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
 
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
 
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
 
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
 
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
 
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
 
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
 
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
 
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
 
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 kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
 
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 kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, compute the joint angles to reach it.
 
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
 
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
 
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
 
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics, for use with kinematic chain IK solvers.
 
SrvKinematicsPlugin()
Default constructor.
 
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
 
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
 
A set of options for the kinematics solver.
 
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)