41 #include <tf2_eigen/tf2_eigen.hpp>
46 static const rclcpp::Logger
LOGGER =
47 rclcpp::get_logger(
"moveit_move_group_default_capabilities.kinematics_service_capability");
55 fk_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionFK>(
56 FK_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& req_header,
57 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
58 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res) {
59 return computeFKService(req_header, req, res);
61 ik_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionIK>(
62 IK_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& req_header,
63 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
64 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res) {
65 return computeIKService(req_header, req, res);
74 const double* ik_solution)
83 void MoveGroupKinematicsService::computeIK(moveit_msgs::msg::PositionIKRequest& req,
84 moveit_msgs::msg::RobotState& solution,
95 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
97 if (req.pose_stamped_vector.empty() || req.pose_stamped_vector.size() == 1)
99 geometry_msgs::msg::PoseStamped req_pose =
100 req.pose_stamped_vector.empty() ? req.pose_stamped : req.pose_stamped_vector[0];
101 std::string ik_link = (!req.pose_stamped_vector.empty()) ?
102 (req.ik_link_names.empty() ?
"" : req.ik_link_names[0]) :
107 bool result_ik =
false;
109 result_ik = rs.
setFromIK(jmg, req_pose.pose, req.timeout.sec, constraint);
111 result_ik = rs.
setFromIK(jmg, req_pose.pose, ik_link, req.timeout.sec, constraint);
116 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
119 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
122 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
126 if (req.pose_stamped_vector.size() != req.ik_link_names.size())
127 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
131 EigenSTL::vector_Isometry3d req_poses(req.pose_stamped_vector.size());
132 for (std::size_t k = 0; k < req.pose_stamped_vector.size(); ++k)
134 geometry_msgs::msg::PoseStamped msg = req.pose_stamped_vector[k];
136 tf2::fromMsg(msg.pose, req_poses[k]);
139 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
146 if (rs.
setFromIK(jmg, req_poses, req.ik_link_names, req.timeout.sec, constraint))
149 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
152 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
158 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
161 bool MoveGroupKinematicsService::computeIKService(
const std::shared_ptr<rmw_request_id_t>& ,
162 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
163 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res)
165 context_->planning_scene_monitor_->updateFrameTransforms();
173 kset.add(req->ik_request.constraints, ls->getTransforms());
174 computeIK(req->ik_request, res->solution, res->error_code, rs,
175 [
scene = req->ik_request.avoid_collisions ?
176 static_cast<const planning_scene::PlanningSceneConstPtr&
>(ls).get() :
180 const double* joint_group_variable_values) {
181 return isIKSolutionValid(scene, kset_ptr, robot_state, joint_group, joint_group_variable_values);
189 computeIK(req->ik_request, res->solution, res->error_code, rs);
195 bool MoveGroupKinematicsService::computeFKService(
const std::shared_ptr<rmw_request_id_t>& ,
196 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
197 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res)
199 if (req->fk_link_names.empty())
201 RCLCPP_ERROR(LOGGER,
"No links specified for FK request");
202 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
206 context_->planning_scene_monitor_->updateFrameTransforms();
208 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
209 bool do_transform = !req->header.frame_id.empty() &&
211 context_->planning_scene_monitor_->getTFClient();
212 bool tf_problem =
false;
217 for (std::size_t i = 0; i < req->fk_link_names.size(); ++i)
220 res->pose_stamped.resize(res->pose_stamped.size() + 1);
222 res->pose_stamped.back().header.frame_id = default_frame;
223 res->pose_stamped.back().header.stamp =
context_->moveit_cpp_->getNode()->get_clock()->now();
227 res->fk_link_names.push_back(req->fk_link_names[i]);
230 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
231 else if (res->fk_link_names.size() == req->fk_link_names.size())
232 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
234 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
239 #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.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
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 RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
void update(bool force=false)
Update all transforms.
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.
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
bool satisfied
Whether or not the constraint or constraints were satisfied.