41#include <tf2_eigen/tf2_eigen.hpp>
54 fk_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionFK>(
55 FK_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& req_header,
56 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
57 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res) {
58 return computeFKService(req_header, req, res);
60 ik_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionIK>(
61 IK_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& req_header,
62 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
63 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res) {
64 return computeIKService(req_header, req, res);
73 const double* ik_solution)
82void MoveGroupKinematicsService::computeIK(moveit_msgs::msg::PositionIKRequest& req,
83 moveit_msgs::msg::RobotState& solution,
94 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
96 if (req.pose_stamped_vector.empty() || req.pose_stamped_vector.size() == 1)
98 geometry_msgs::msg::PoseStamped req_pose =
99 req.pose_stamped_vector.empty() ? req.pose_stamped : req.pose_stamped_vector[0];
100 std::string ik_link = (!req.pose_stamped_vector.empty()) ?
101 (req.ik_link_names.empty() ?
"" : req.ik_link_names[0]) :
106 bool result_ik =
false;
109 result_ik = rs.
setFromIK(jmg, req_pose.pose, req.timeout.sec, constraint);
113 result_ik = rs.
setFromIK(jmg, req_pose.pose, ik_link, req.timeout.sec, constraint);
119 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
122 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
125 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
129 if (req.pose_stamped_vector.size() != req.ik_link_names.size())
131 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
136 EigenSTL::vector_Isometry3d req_poses(req.pose_stamped_vector.size());
137 for (std::size_t k = 0; k < req.pose_stamped_vector.size(); ++k)
139 geometry_msgs::msg::PoseStamped msg = req.pose_stamped_vector[k];
142 tf2::fromMsg(msg.pose, req_poses[k]);
146 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
153 if (rs.
setFromIK(jmg, req_poses, req.ik_link_names, req.timeout.sec, constraint))
156 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
159 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
165 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
168bool MoveGroupKinematicsService::computeIKService(
const std::shared_ptr<rmw_request_id_t>& ,
169 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
170 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res)
172 context_->planning_scene_monitor_->updateFrameTransforms();
180 kset.add(req->ik_request.constraints, ls->getTransforms());
181 computeIK(req->ik_request, res->solution, res->error_code, rs,
182 [scene = req->ik_request.avoid_collisions ?
183 static_cast<const planning_scene::PlanningSceneConstPtr&
>(ls).get() :
185 kset_ptr = kset.empty() ? nullptr : &kset](
moveit::core::RobotState* robot_state,
186 const
moveit::core::JointModelGroup* joint_group,
187 const double* joint_group_variable_values) {
188 return isIKSolutionValid(scene, kset_ptr, robot_state, joint_group, joint_group_variable_values);
196 computeIK(req->ik_request, res->solution, res->error_code, rs);
202bool MoveGroupKinematicsService::computeFKService(
const std::shared_ptr<rmw_request_id_t>& ,
203 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
204 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res)
206 if (req->fk_link_names.empty())
208 RCLCPP_ERROR(
moveit::getLogger(
"moveit.ros.move_group.kinematics_service"),
"No links specified for FK request");
209 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
213 context_->planning_scene_monitor_->updateFrameTransforms();
215 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
216 bool do_transform = !req->header.frame_id.empty() &&
218 context_->planning_scene_monitor_->getTFClient();
219 bool tf_problem =
false;
224 for (std::size_t i = 0; i < req->fk_link_names.size(); ++i)
228 res->pose_stamped.resize(res->pose_stamped.size() + 1);
229 res->pose_stamped.back().pose = tf2::toMsg(rs.
getFrameTransform(req->fk_link_names[i]));
230 res->pose_stamped.back().header.frame_id = default_frame;
231 res->pose_stamped.back().header.stamp =
context_->moveit_cpp_->getNode()->get_clock()->now();
237 res->fk_link_names.push_back(req->fk_link_names[i]);
242 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
244 else if (res->fk_link_names.size() == req->fk_link_names.size())
246 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
250 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
256#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
A class that contains many different constraints, and can check RobotState *versus the full set....
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
MoveGroupContextPtr context_
void initialize() override
MoveGroupKinematicsService()
const std::string & getName() const
Get the name of the joint group.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
This class maintains the representation of the environment as seen by a planning instance....
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
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.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
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.
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
This namespace includes the central class for representing planning contexts.
bool satisfied
Whether or not the constraint or constraints were satisfied.