42 #include <Eigen/Geometry.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
49 const std::string& group_name)
51 if (!kinematic_model->hasJointModelGroup(group_name))
53 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"The group %s does not exist", group_name.c_str());
54 joint_model_group_ =
nullptr;
57 kinematic_model_ = kinematic_model;
58 group_name_ = group_name;
59 joint_model_group_ = kinematic_model_->getJointModelGroup(group_name);
62 has_sub_groups_ =
false;
63 sub_groups_names_.push_back(group_name_);
67 ROS_DEBUG_NAMED(
"kinematics_constraint_aware",
"No kinematics solver instance defined for group %s",
69 bool is_solvable_group =
true;
72 const std::vector<std::string> sub_groups_names = joint_model_group_->
getSubgroupNames();
73 for (std::size_t i = 0; i < sub_groups_names.size(); ++i)
75 if (!kinematic_model_->getJointModelGroup(sub_groups_names[i])->getSolverInstance())
77 is_solvable_group =
false;
81 if (is_solvable_group)
83 ROS_DEBUG_NAMED(
"kinematics_constraint_aware",
"Group %s is a group for which we can solve IK",
84 joint_model_group_->
getName().c_str());
85 sub_groups_names_ = sub_groups_names;
89 joint_model_group_ =
nullptr;
95 joint_model_group_ =
nullptr;
96 ROS_INFO_NAMED(
"kinematics_constraint_aware",
"No solver allocated for group %s", group_name.c_str());
98 has_sub_groups_ =
true;
107 if (!joint_model_group_)
109 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"This solver has not been constructed properly");
115 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"Planning scene must be allocated");
124 ros::WallTime start_time = ros::WallTime::now();
142 if (!kinematic_model_->getJointModelGroup(sub_groups_names_[i])->hasLinkModel(request.
ik_link_names_[i]) &&
143 kinematic_model_->getJointModelGroup(sub_groups_names_[i])->isLinkUpdated(request.
ik_link_names_[i]))
148 kinematic_model_->getJointModelGroup(sub_groups_names_[i])->getSolverInstance()->getTipFrame();
150 else if (!kinematic_model_->getJointModelGroup(sub_groups_names_[i])->canSetStateFromIK(request.
ik_link_names_[i]))
152 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"Could not find IK solver for link %s for group %s",
160 EigenSTL::vector_Isometry3d goals =
163 moveit::core::StateValidityCallbackFn constraint_callback_fn = [
this, &
planning_scene, &request,
164 &response](moveit::core::JointStateGroup* jsg,
165 const std::vector<double>& jg_values) {
166 validityCallbackFn(
planning_scene, request, response, jsg, jg_values);
172 result = kinematic_state.getJointStateGroup(group_name_)
173 ->
setFromIK(goals, ik_link_names, ik_attempts_, request.
timeout_.toSec(), constraint_callback_fn);
178 ik_link_names.empty() ?
179 kinematic_state.getJointStateGroup(group_name_)
180 ->
setFromIK(goals[0], ik_attempts_, request.
timeout_.toSec(), constraint_callback_fn) :
181 kinematic_state.getJointStateGroup(group_name_)
182 ->
setFromIK(goals[0], ik_link_names[0], ik_attempts_, request.
timeout_.toSec(), constraint_callback_fn);
187 std::vector<double> solution_values;
188 kinematic_state.getJointStateGroup(group_name_)->getVariableValues(solution_values);
189 response.
solution_->getJointStateGroup(group_name_)->setVariableValues(solution_values);
200 bool KinematicsConstraintAware::validityCallbackFn(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
203 moveit::core::JointStateGroup* joint_state_group,
204 const std::vector<double>& joint_group_variable_values)
const
206 joint_state_group->setVariableValues(joint_group_variable_values);
214 planning_scene->checkCollision(collision_request, collision_result, *joint_state_group->getRobotState());
217 ROS_DEBUG_NAMED(
"kinematics_constraint_aware",
"IK solution is in collision");
231 ROS_DEBUG_NAMED(
"kinematics_constraint_aware",
"IK solution violates constraints");
242 ROS_DEBUG_NAMED(
"kinematics_constraint_aware",
"IK solution violates user specified constraints");
252 const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
253 moveit_msgs::msg::GetConstraintAwarePositionIK::Response& response)
const
255 if (!joint_model_group_)
257 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"This solver has not been constructed properly");
263 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"Planning scene must be allocated");
270 if (!convertServiceRequest(
planning_scene, request, kinematics_request, kinematics_response))
272 response.error_code = kinematics_response.
error_code_;
277 response.error_code = kinematics_response.
error_code_;
278 kinematics_response.
solution_->getStateValues(response.solution.joint_state);
282 bool KinematicsConstraintAware::convertServiceRequest(
284 const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
288 if (request.ik_request.group_name != group_name_)
290 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
"This kinematics solver does not support requests for group: %s",
291 request.ik_request.group_name.c_str());
296 if (!request.ik_request.pose_stamped_vector.empty() &&
297 request.ik_request.pose_stamped_vector.size() != sub_groups_names_.size())
299 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
300 "Number of poses in request: %d must match number of sub groups %d in this group",
301 request.ik_request.pose_stamped_vector.size(), sub_groups_names_.size());
306 if (!request.ik_request.ik_link_names.empty() && request.ik_request.ik_link_names.size() != sub_groups_names_.size())
308 ROS_ERROR_NAMED(
"kinematics_constraint_aware",
309 "Number of ik_link_names in request: "
310 "%d must match number of sub groups %d in this group or must be zero",
311 request.ik_request.ik_link_names.size(), sub_groups_names_.size());
316 if (request.ik_request.ik_link_names.empty() && request.ik_request.ik_link_name !=
"")
317 kinematics_request.
ik_link_names_.push_back(request.ik_request.ik_link_name);
319 kinematics_request.
ik_link_names_ = request.ik_request.ik_link_names;
321 if (request.ik_request.pose_stamped_vector.empty())
327 kinematics_request.
robot_state_->setStateValues(request.ik_request.robot_state.joint_state);
328 kinematics_request.
constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(
330 kinematics_request.
constraints_->add(request.constraints);
331 kinematics_request.
timeout_ = request.ik_request.timeout;
332 kinematics_request.
group_name_ = request.ik_request.group_name;
340 EigenSTL::vector_Isometry3d KinematicsConstraintAware::transformPoses(
342 const std::vector<geometry_msgs::PoseStamped>& poses,
const std::string& target_frame)
const
344 Eigen::Isometry3d eigen_pose, eigen_pose_2;
345 EigenSTL::vector_Isometry3d result(poses.size());
346 bool target_frame_is_root_frame = (target_frame == kinematic_state.
getRobotModel()->getModelFrame());
347 for (std::size_t i = 0; i < poses.size(); ++i)
349 geometry_msgs::Pose pose = poses[i].pose;
350 tf2::fromMsg(pose, eigen_pose_2);
351 planning_scene->getTransforms()->transformPose(kinematic_state, poses[i].header.frame_id, eigen_pose_2, eigen_pose);
352 if (!target_frame_is_root_frame)
354 eigen_pose_2 =
planning_scene->getTransforms()->getTransform(kinematic_state, target_frame);
355 eigen_pose = eigen_pose_2.inverse() * eigen_pose;
357 result[i] = eigen_pose;
362 geometry_msgs::Pose KinematicsConstraintAware::getTipFramePose(
364 const geometry_msgs::Pose& pose,
const std::string& link_name,
unsigned int sub_group_index)
const
366 geometry_msgs::Pose result;
367 Eigen::Isometry3d eigen_pose_in, eigen_pose_link, eigen_pose_tip;
368 std::string tip_name =
369 kinematic_model_->getJointModelGroup(sub_groups_names_[sub_group_index])->getSolverInstance()->getTipFrame();
370 tf2::fromMsg(pose, eigen_pose_in);
371 eigen_pose_link =
planning_scene->getTransforms()->getTransform(kinematic_state, link_name);
372 eigen_pose_tip =
planning_scene->getTransforms()->getTransform(kinematic_state, tip_name);
373 eigen_pose_in = eigen_pose_in * (eigen_pose_link.inverse() * eigen_pose_tip);
374 result = tf2::toMsg(eigen_pose_in, result);
KinematicsConstraintAware(const moveit::core::RobotModelConstPtr &kinematic_model, const std::string &group_name)
Default constructor.
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
Solve the planning problem.
moveit::core::RobotStatePtr robot_state_
kinematic_constraints::KinematicConstraintSetPtr constraints_
bool check_for_collisions_
std::vector< std::string > ik_link_names_
moveit::core::StateValidityCallbackFn constraint_callback_
std::vector< geometry_msgs::PoseStamped > pose_stamped_vector_
moveit::core::RobotStatePtr solution_
std::vector< kinematic_constraints::ConstraintEvaluationResult > constraint_eval_results_
moveit_msgs::msg::MoveItErrorCodes error_code_
const std::string & getName() const
Get the name of the joint group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
const std::vector< std::string > & getSubgroupNames() const
Get the names of the groups that are subsets of this one (in terms of joints set)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
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 namespace includes the central class for representing planning contexts.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Struct for containing the results of constraint evaluation.
bool satisfied
Whether or not the constraint or constraints were satisfied.