00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/srv_kinematics_plugin/srv_kinematics_plugin.h>
00038 #include <class_loader/class_loader.h>
00039
00040
00041 #include <urdf_model/model.h>
00042 #include <srdfdom/model.h>
00043
00044 #include <moveit/robot_state/conversions.h>
00045 #include <moveit/rdf_loader/rdf_loader.h>
00046
00047
00048 #include <Eigen/Core>
00049 #include <Eigen/Geometry>
00050
00051
00052 CLASS_LOADER_REGISTER_CLASS(srv_kinematics_plugin::SrvKinematicsPlugin, kinematics::KinematicsBase)
00053
00054 namespace srv_kinematics_plugin
00055 {
00056 SrvKinematicsPlugin::SrvKinematicsPlugin() : active_(false)
00057 {
00058 }
00059
00060 bool SrvKinematicsPlugin::initialize(const std::string& robot_description, const std::string& group_name,
00061 const std::string& base_frame, const std::vector<std::string>& tip_frames,
00062 double search_discretization)
00063 {
00064 bool debug = false;
00065
00066 ROS_INFO_STREAM_NAMED("srv", "SrvKinematicsPlugin initializing");
00067
00068 setValues(robot_description, group_name, base_frame, tip_frames, search_discretization);
00069
00070 ros::NodeHandle private_handle("~");
00071 rdf_loader::RDFLoader rdf_loader(robot_description_);
00072 const boost::shared_ptr<srdf::Model>& srdf = rdf_loader.getSRDF();
00073 const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader.getURDF();
00074
00075 if (!urdf_model || !srdf)
00076 {
00077 ROS_ERROR_NAMED("srv", "URDF and SRDF must be loaded for SRV kinematics solver to work.");
00078 return false;
00079 }
00080
00081 robot_model_.reset(new robot_model::RobotModel(urdf_model, srdf));
00082
00083 joint_model_group_ = robot_model_->getJointModelGroup(group_name);
00084 if (!joint_model_group_)
00085 return false;
00086
00087 if (debug)
00088 {
00089 std::cout << std::endl << "Joint Model Variable Names: ------------------------------------------- " << std::endl;
00090 const std::vector<std::string> jm_names = joint_model_group_->getVariableNames();
00091 std::copy(jm_names.begin(), jm_names.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
00092 std::cout << std::endl;
00093 }
00094
00095
00096 dimension_ = joint_model_group_->getVariableCount();
00097 ROS_INFO_STREAM_NAMED("srv", "Dimension planning group '"
00098 << group_name << "': " << dimension_
00099 << ". Active Joints Models: " << joint_model_group_->getActiveJointModels().size()
00100 << ". Mimic Joint Models: " << joint_model_group_->getMimicJointModels().size());
00101
00102
00103 for (std::size_t i = 0; i < joint_model_group_->getJointModels().size(); ++i)
00104 {
00105 ik_group_info_.joint_names.push_back(joint_model_group_->getJointModelNames()[i]);
00106 }
00107
00108 if (debug)
00109 {
00110 ROS_ERROR_STREAM_NAMED("temp", "tip links available:");
00111 std::copy(tip_frames_.begin(), tip_frames_.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
00112 }
00113
00114
00115 for (std::size_t i = 0; i < tip_frames_.size(); ++i)
00116 {
00117 if (!joint_model_group_->hasLinkModel(tip_frames_[i]))
00118 {
00119 ROS_ERROR_NAMED("srv", "Could not find tip name '%s' in joint group '%s'", tip_frames_[i].c_str(),
00120 group_name.c_str());
00121 return false;
00122 }
00123 ik_group_info_.link_names.push_back(tip_frames_[i]);
00124 }
00125
00126
00127 ROS_DEBUG_STREAM_NAMED("srv", "Looking for ROS service name on rosparm server at location: "
00128 << private_handle.getNamespace() << "/" << group_name_
00129 << "/kinematics_solver_service_name");
00130 std::string ik_service_name;
00131 private_handle.param(group_name_ + "/kinematics_solver_service_name", ik_service_name, std::string("solve_ik"));
00132
00133
00134 robot_state_.reset(new robot_state::RobotState(robot_model_));
00135 robot_state_->setToDefaultValues();
00136
00137
00138 ros::NodeHandle nonprivate_handle("");
00139 ik_service_client_ = boost::make_shared<ros::ServiceClient>(
00140 nonprivate_handle.serviceClient<moveit_msgs::GetPositionIK>(ik_service_name));
00141 if (!ik_service_client_->waitForExistence(ros::Duration(0.1)))
00142 ROS_WARN_STREAM_NAMED("srv",
00143 "Unable to connect to ROS service client with name: " << ik_service_client_->getService());
00144 else
00145 ROS_INFO_STREAM_NAMED("srv", "Service client started with ROS service name: " << ik_service_client_->getService());
00146
00147 active_ = true;
00148 ROS_DEBUG_NAMED("srv", "ROS service-based kinematics solver initialized");
00149 return true;
00150 }
00151
00152 bool SrvKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joints)
00153 {
00154 if (num_possible_redundant_joints_ < 0)
00155 {
00156 ROS_ERROR_NAMED("srv", "This group cannot have redundant joints");
00157 return false;
00158 }
00159 if (redundant_joints.size() > num_possible_redundant_joints_)
00160 {
00161 ROS_ERROR_NAMED("srv", "This group can only have %d redundant joints", num_possible_redundant_joints_);
00162 return false;
00163 }
00164
00165 return true;
00166 }
00167
00168 bool SrvKinematicsPlugin::isRedundantJoint(unsigned int index) const
00169 {
00170 for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
00171 if (redundant_joint_indices_[j] == index)
00172 return true;
00173 return false;
00174 }
00175
00176 int SrvKinematicsPlugin::getJointIndex(const std::string& name) const
00177 {
00178 for (unsigned int i = 0; i < ik_group_info_.joint_names.size(); i++)
00179 {
00180 if (ik_group_info_.joint_names[i] == name)
00181 return i;
00182 }
00183 return -1;
00184 }
00185
00186 bool SrvKinematicsPlugin::timedOut(const ros::WallTime& start_time, double duration) const
00187 {
00188 return ((ros::WallTime::now() - start_time).toSec() >= duration);
00189 }
00190
00191 bool SrvKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00192 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00193 const kinematics::KinematicsQueryOptions& options) const
00194 {
00195 const IKCallbackFn solution_callback = 0;
00196 std::vector<double> consistency_limits;
00197
00198 return searchPositionIK(ik_pose, ik_seed_state, default_timeout_, solution, solution_callback, error_code,
00199 consistency_limits, options);
00200 }
00201
00202 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00203 double timeout, std::vector<double>& solution,
00204 moveit_msgs::MoveItErrorCodes& error_code,
00205 const kinematics::KinematicsQueryOptions& options) const
00206 {
00207 const IKCallbackFn solution_callback = 0;
00208 std::vector<double> consistency_limits;
00209
00210 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
00211 options);
00212 }
00213
00214 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00215 double timeout, const std::vector<double>& consistency_limits,
00216 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00217 const kinematics::KinematicsQueryOptions& options) const
00218 {
00219 const IKCallbackFn solution_callback = 0;
00220 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
00221 options);
00222 }
00223
00224 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00225 double timeout, std::vector<double>& solution,
00226 const IKCallbackFn& solution_callback,
00227 moveit_msgs::MoveItErrorCodes& error_code,
00228 const kinematics::KinematicsQueryOptions& options) const
00229 {
00230 std::vector<double> consistency_limits;
00231 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
00232 options);
00233 }
00234
00235 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00236 double timeout, const std::vector<double>& consistency_limits,
00237 std::vector<double>& solution, const IKCallbackFn& solution_callback,
00238 moveit_msgs::MoveItErrorCodes& error_code,
00239 const kinematics::KinematicsQueryOptions& options) const
00240 {
00241 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
00242 options);
00243 }
00244
00245 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00246 double timeout, std::vector<double>& solution,
00247 const IKCallbackFn& solution_callback,
00248 moveit_msgs::MoveItErrorCodes& error_code,
00249 const std::vector<double>& consistency_limits,
00250 const kinematics::KinematicsQueryOptions& options) const
00251 {
00252
00253 std::vector<geometry_msgs::Pose> ik_poses;
00254 ik_poses.push_back(ik_pose);
00255
00256 return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
00257 options);
00258 }
00259
00260 bool SrvKinematicsPlugin::searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
00261 const std::vector<double>& ik_seed_state, double timeout,
00262 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00263 const IKCallbackFn& solution_callback,
00264 moveit_msgs::MoveItErrorCodes& error_code,
00265 const kinematics::KinematicsQueryOptions& options) const
00266 {
00267
00268 if (!active_)
00269 {
00270 ROS_ERROR_NAMED("srv", "kinematics not active");
00271 error_code.val = error_code.NO_IK_SOLUTION;
00272 return false;
00273 }
00274
00275
00276 if (ik_seed_state.size() != dimension_)
00277 {
00278 ROS_ERROR_STREAM_NAMED("srv", "Seed state must have size " << dimension_ << " instead of size "
00279 << ik_seed_state.size());
00280 error_code.val = error_code.NO_IK_SOLUTION;
00281 return false;
00282 }
00283
00284
00285 if (tip_frames_.size() != ik_poses.size())
00286 {
00287 ROS_ERROR_STREAM_NAMED("srv", "Mismatched number of pose requests (" << ik_poses.size() << ") to tip frames ("
00288 << tip_frames_.size()
00289 << ") in searchPositionIK");
00290 error_code.val = error_code.NO_IK_SOLUTION;
00291 return false;
00292 }
00293
00294
00295 moveit_msgs::GetPositionIK ik_srv;
00296 ik_srv.request.ik_request.avoid_collisions = true;
00297 ik_srv.request.ik_request.group_name = getGroupName();
00298
00299
00300 robot_state_->setJointGroupPositions(joint_model_group_, ik_seed_state);
00301 moveit::core::robotStateToRobotStateMsg(*robot_state_, ik_srv.request.ik_request.robot_state);
00302
00303
00304 geometry_msgs::PoseStamped ik_pose_st;
00305 ik_pose_st.header.frame_id = base_frame_;
00306 if (tip_frames_.size() > 1)
00307 {
00308
00309 for (std::size_t i = 0; i < tip_frames_.size(); ++i)
00310 {
00311 ik_pose_st.pose = ik_poses[i];
00312 ik_srv.request.ik_request.pose_stamped_vector.push_back(ik_pose_st);
00313 ik_srv.request.ik_request.ik_link_names.push_back(tip_frames_[i]);
00314 }
00315 }
00316 else
00317 {
00318 ik_pose_st.pose = ik_poses[0];
00319
00320
00321 ik_srv.request.ik_request.pose_stamped = ik_pose_st;
00322 ik_srv.request.ik_request.ik_link_name = getTipFrames()[0];
00323 }
00324
00325 ROS_DEBUG_STREAM_NAMED("srv", "Calling service: " << ik_service_client_->getService());
00326 if (ik_service_client_->call(ik_srv))
00327 {
00328
00329 error_code.val = ik_srv.response.error_code.val;
00330 if (error_code.val != error_code.SUCCESS)
00331 {
00332 ROS_DEBUG_NAMED("srv", "An IK that satisifes the constraints and is collision free could not be found.");
00333 switch (error_code.val)
00334 {
00335
00336 ROS_DEBUG_STREAM("Request was: \n" << ik_srv.request.ik_request);
00337 ROS_DEBUG_STREAM("Response was: \n" << ik_srv.response.solution);
00338
00339 case moveit_msgs::MoveItErrorCodes::FAILURE:
00340 ROS_ERROR_STREAM_NAMED("srv", "Service failed with with error code: FAILURE");
00341 break;
00342 case moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION:
00343 ROS_ERROR_STREAM_NAMED("srv", "Service failed with with error code: NO IK SOLUTION");
00344 break;
00345 default:
00346 ROS_ERROR_STREAM_NAMED("srv", "Service failed with with error code: " << error_code.val);
00347 }
00348 return false;
00349 }
00350 }
00351 else
00352 {
00353 ROS_ERROR_STREAM("Service call failed to connect to service: " << ik_service_client_->getService());
00354 error_code.val = error_code.FAILURE;
00355 return false;
00356 }
00357
00358
00359 if (!moveit::core::robotStateMsgToRobotState(ik_srv.response.solution, *robot_state_))
00360 {
00361 ROS_ERROR_STREAM_NAMED("srv", "An error occured converting recieved robot state message into internal robot "
00362 "state.");
00363 error_code.val = error_code.FAILURE;
00364 return false;
00365 }
00366
00367
00368 robot_state_->copyJointGroupPositions(joint_model_group_, solution);
00369
00370
00371 if (!solution_callback.empty())
00372 {
00373 ROS_DEBUG_STREAM_NAMED("srv", "Calling solution callback on IK solution");
00374
00375
00376 solution_callback(ik_poses[0], solution, error_code);
00377
00378 if (error_code.val != error_code.SUCCESS)
00379 {
00380 switch (error_code.val)
00381 {
00382 case moveit_msgs::MoveItErrorCodes::FAILURE:
00383 ROS_ERROR_STREAM_NAMED("srv", "IK solution callback failed with with error code: FAILURE");
00384 break;
00385 case moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION:
00386 ROS_ERROR_STREAM_NAMED("srv", "IK solution callback failed with with error code: NO IK SOLUTION");
00387 break;
00388 default:
00389 ROS_ERROR_STREAM_NAMED("srv", "IK solution callback failed with with error code: " << error_code.val);
00390 }
00391 return false;
00392 }
00393 }
00394
00395 ROS_INFO_STREAM_NAMED("srv", "IK Solver Succeeded!");
00396 return true;
00397 }
00398
00399 bool SrvKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
00400 const std::vector<double>& joint_angles,
00401 std::vector<geometry_msgs::Pose>& poses) const
00402 {
00403 ros::WallTime n1 = ros::WallTime::now();
00404 if (!active_)
00405 {
00406 ROS_ERROR_NAMED("srv", "kinematics not active");
00407 return false;
00408 }
00409 poses.resize(link_names.size());
00410 if (joint_angles.size() != dimension_)
00411 {
00412 ROS_ERROR_NAMED("srv", "Joint angles vector must have size: %d", dimension_);
00413 return false;
00414 }
00415
00416 ROS_ERROR_STREAM_NAMED("srv", "Forward kinematics not implemented");
00417
00418 return false;
00419 }
00420
00421 const std::vector<std::string>& SrvKinematicsPlugin::getJointNames() const
00422 {
00423 return ik_group_info_.joint_names;
00424 }
00425
00426 const std::vector<std::string>& SrvKinematicsPlugin::getLinkNames() const
00427 {
00428 return ik_group_info_.link_names;
00429 }
00430
00431 const std::vector<std::string>& SrvKinematicsPlugin::getVariableNames() const
00432 {
00433 return joint_model_group_->getVariableNames();
00434 }
00435
00436 }