00001
00002
00003 #include <string>
00004 #include <exception>
00005 #include <math.h>
00006
00007 #include <ros/ros.h>
00008 #include <tf/transform_listener.h>
00009 #include <tf_conversions/tf_kdl.h>
00010 #include <tf/transform_datatypes.h>
00011 #include <kdl_parser/kdl_parser.hpp>
00012 #include <kdl/jntarray.hpp>
00013 #include <kdl/chainiksolverpos_nr_jl.hpp>
00014 #include <kdl/chainiksolvervel_wdls.hpp>
00015 #include <kdl/chainfksolverpos_recursive.hpp>
00016 #include <kinematics_msgs/GetPositionFK.h>
00017 #include <kinematics_msgs/GetPositionIK.h>
00018 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00019 #include <kinematics_msgs/KinematicSolverInfo.h>
00020 #include <kdl_arm_kinematics/GetWeightedIK.h>
00021
00022 using std::string;
00023
00024 class Kinematics
00025 {
00026 public:
00027 class InitFailed : public std::runtime_error
00028 {
00029 public:
00030 InitFailed(const string &what)
00031 : std::runtime_error(what) {}
00032 };
00033
00034 Kinematics();
00035
00036 private:
00037 ros::NodeHandle nh, nh_private;
00038 std::string root_name, tip_name;
00039 KDL::JntArray joint_min, joint_max;
00040 KDL::Chain chain;
00041 unsigned int num_joints;
00042 int max_iterations;
00043 double epsilon;
00044 Eigen::MatrixXd default_weight_ts;
00045 Eigen::MatrixXd default_weight_js;
00046 double default_lambda;
00047
00048 ros::ServiceServer ik_service,ik_solver_info_service;
00049 ros::ServiceServer fk_service,fk_solver_info_service;
00050 ros::ServiceServer weighted_ik_service;
00051
00052 tf::TransformListener tf_listener;
00053
00054 kinematics_msgs::KinematicSolverInfo info;
00055
00056 void parseWeightParams(ros::NodeHandle &nh);
00057 bool loadModel(const std::string xml);
00058 bool readJoints(urdf::Model &robot_model);
00059 int getJointIndex(const std::string &name);
00060 int getKDLSegmentIndex(const std::string &name);
00061 bool solveCartToJnt(const KDL::JntArray &q_init, const KDL::Frame &q_in, KDL::JntArray &q_out,
00062 const KDL::Frame &tool_frame = KDL::Frame::Identity());
00063 bool solveCartToJnt(const KDL::JntArray &q_init, const KDL::Frame &q_in, KDL::JntArray &q_out,
00064 const KDL::Frame &tool_frame, const Eigen::MatrixXd &weight_ts,
00065 const Eigen::MatrixXd &weight_js, const double lambda);
00066 double calculateEps(const KDL::Frame &f, const KDL::Frame &ref,
00067 const Eigen::MatrixXd &weight=Eigen::MatrixXd::Identity(6,6));
00068 void initializeWeights(const kdl_arm_kinematics::KDLWeights &msg,
00069 Eigen::MatrixXd &weight_ts, Eigen::MatrixXd &weight_js, double &lambda);
00070
00076 bool getPositionIK(kinematics_msgs::GetPositionIK::Request &request,
00077 kinematics_msgs::GetPositionIK::Response &response);
00078
00084 bool getIKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request,
00085 kinematics_msgs::GetKinematicSolverInfo::Response &response);
00086
00092 bool getFKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request,
00093 kinematics_msgs::GetKinematicSolverInfo::Response &response);
00094
00100 bool getPositionFK(kinematics_msgs::GetPositionFK::Request &request,
00101 kinematics_msgs::GetPositionFK::Response &response);
00102
00103 bool getWeightedIK(kdl_arm_kinematics::GetWeightedIK::Request &request,
00104 kdl_arm_kinematics::GetWeightedIK::Response &response);
00105 };
00106
00107
00108
00109 Kinematics::Kinematics()
00110 : nh(),
00111 nh_private ("~"),
00112 default_weight_ts(Eigen::MatrixXd::Identity(6,6)),
00113 default_lambda(0.1)
00114 {
00115
00116 std::string urdf_xml, full_urdf_xml;
00117 nh_private.param("robot_description_name",urdf_xml,std::string("robot_description"));
00118 nh.searchParam(urdf_xml,full_urdf_xml);
00119 ROS_DEBUG("Reading xml file from parameter server");
00120 std::string result;
00121 if (!nh.getParam(full_urdf_xml, result))
00122 throw Kinematics::InitFailed("Could not load the xml from parameter server: " + urdf_xml);
00123
00124
00125 if (!nh_private.getParam("root_name", root_name))
00126 throw Kinematics::InitFailed("GenericIK: No root name found on parameter server");
00127
00128 if (!nh_private.getParam("tip_name", tip_name))
00129 throw Kinematics::InitFailed("GenericIK: No tip name found on parameter server");
00130
00131
00132 if (!loadModel(result))
00133 throw Kinematics::InitFailed("Could not load models!");
00134
00135 default_weight_js = Eigen::MatrixXd::Identity(chain.getNrOfJoints(), chain.getNrOfJoints());
00136 parseWeightParams(nh_private);
00137
00138 nh_private.param("maxIterations", max_iterations, 100);
00139 nh_private.param("epsilon", epsilon, 1e-2);
00140
00141 ROS_INFO("Advertising services");
00142 fk_service = nh_private.advertiseService("get_fk", &Kinematics::getPositionFK,this);
00143 ik_service = nh_private.advertiseService("get_ik", &Kinematics::getPositionIK,this);
00144 ik_solver_info_service = nh_private.advertiseService("get_ik_solver_info", &Kinematics::getIKSolverInfo,this);
00145 fk_solver_info_service = nh_private.advertiseService("get_fk_solver_info", &Kinematics::getFKSolverInfo,this);
00146 weighted_ik_service = nh_private.advertiseService("get_weighted_ik", &Kinematics::getWeightedIK, this);
00147 }
00148
00149 void Kinematics::parseWeightParams(ros::NodeHandle &nh)
00150 {
00151 ros::NodeHandle weights_nh(nh, "weights");
00152
00153 if(weights_nh.hasParam("lambda"))
00154 {
00155 weights_nh.getParam("lambda", default_lambda);
00156 ROS_INFO("Setting lambda to %lf", default_lambda);
00157 }
00158
00159 if(weights_nh.hasParam("weight_ts"))
00160 {
00161 ros::NodeHandle weight_ts_nh(weights_nh, "weight_ts");
00162 double value;
00163
00164 if(weight_ts_nh.getParam("x", value))
00165 {
00166 ROS_INFO("Reading weight_ts/x: %lf", value);
00167 default_weight_ts(0,0) = value;
00168 }
00169
00170 if(weight_ts_nh.getParam("y", value))
00171 {
00172 ROS_INFO("Reading weight_ts/y: %lf", value);
00173 default_weight_ts(1,1) = value;
00174 }
00175
00176 if(weight_ts_nh.getParam("z", value))
00177 {
00178 ROS_INFO("Reading weight_ts/z: %lf", value);
00179 default_weight_ts(2,2) = value;
00180 }
00181
00182 if(weight_ts_nh.getParam("roll", value))
00183 {
00184 ROS_INFO("Reading weight_ts/roll: %lf", value);
00185 default_weight_ts(3,3) = value;
00186 }
00187
00188 if(weight_ts_nh.getParam("pitch", value))
00189 {
00190 ROS_INFO("Reading weight_ts/pitch: %lf", value);
00191 default_weight_ts(4,4) = value;
00192 }
00193
00194 if(weight_ts_nh.getParam("yaw", value))
00195 {
00196 ROS_INFO("Reading weight_ts/yaw: %lf", value);
00197 default_weight_ts(5,5) = value;
00198 }
00199 }
00200
00201 if(weights_nh.hasParam("weight_js"))
00202 {
00203 ros::NodeHandle weight_js_nh(weights_nh, "weight_js");
00204 double value;
00205
00206 for (unsigned int i=0; i < info.joint_names.size(); i++)
00207 {
00208 if(weight_js_nh.getParam(info.joint_names[i], value))
00209 {
00210 ROS_INFO("Setting weight for joint '%s' to %lf", info.joint_names[i].c_str(), value);
00211 default_weight_js(i, i) = value;
00212 }
00213 }
00214 }
00215 }
00216
00217 bool Kinematics::loadModel(const std::string xml) {
00218 urdf::Model robot_model;
00219 KDL::Tree tree;
00220
00221 if (!robot_model.initString(xml)) {
00222 ROS_FATAL("Could not initialize robot model");
00223 return -1;
00224 }
00225 if (!kdl_parser::treeFromString(xml, tree)) {
00226 ROS_ERROR("Could not initialize tree object");
00227 return false;
00228 }
00229 if (!tree.getChain(root_name, tip_name, chain)) {
00230 ROS_ERROR("Could not initialize chain object");
00231 return false;
00232 }
00233
00234 if (!readJoints(robot_model)) {
00235 ROS_FATAL("Could not read information about the joints");
00236 return false;
00237 }
00238
00239 return true;
00240 }
00241
00242 bool Kinematics::readJoints(urdf::Model &robot_model) {
00243 num_joints = 0;
00244
00245 boost::shared_ptr<const urdf::Link> link = robot_model.getLink(tip_name);
00246 boost::shared_ptr<const urdf::Joint> joint;
00247
00248 while (link && link->name != root_name) {
00249 joint = robot_model.getJoint(link->parent_joint->name);
00250 if (!joint) {
00251 ROS_ERROR("Could not find joint: %s",link->parent_joint->name.c_str());
00252 return false;
00253 }
00254 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) {
00255 ROS_INFO( "adding joint: [%s]", joint->name.c_str() );
00256 num_joints++;
00257 }
00258 link = robot_model.getLink(link->getParent()->name);
00259 }
00260
00261 joint_min.resize(num_joints);
00262 joint_max.resize(num_joints);
00263 info.joint_names.resize(num_joints);
00264 info.link_names.clear();
00265 info.limits.resize(num_joints);
00266
00267 link = robot_model.getLink(tip_name);
00268 unsigned int i = 0;
00269 while (link && i < num_joints) {
00270 joint = robot_model.getJoint(link->parent_joint->name);
00271 info.link_names.push_back(link->name);
00272 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) {
00273 ROS_INFO( "getting bounds for joint: [%s]", joint->name.c_str() );
00274
00275 float lower, upper;
00276 int hasLimits;
00277 if ( joint->type != urdf::Joint::CONTINUOUS ) {
00278 lower = joint->limits->lower;
00279 upper = joint->limits->upper;
00280 hasLimits = 1;
00281 } else {
00282 lower = -M_PI;
00283 upper = M_PI;
00284 hasLimits = 0;
00285 }
00286 int index = num_joints - i -1;
00287
00288 joint_min.data[index] = lower;
00289 joint_max.data[index] = upper;
00290 info.joint_names[index] = joint->name;
00291 info.limits[index].joint_name = joint->name;
00292 info.limits[index].has_position_limits = hasLimits;
00293 info.limits[index].min_position = lower;
00294 info.limits[index].max_position = upper;
00295 i++;
00296 }
00297 link = robot_model.getLink(link->getParent()->name);
00298 }
00299 return true;
00300 }
00301
00302
00303 int Kinematics::getJointIndex(const std::string &name) {
00304 for (unsigned int i=0; i < info.joint_names.size(); i++) {
00305 if (info.joint_names[i] == name)
00306 return i;
00307 }
00308 return -1;
00309 }
00310
00311 int Kinematics::getKDLSegmentIndex(const std::string &name) {
00312 int i=0;
00313 while (i < (int)chain.getNrOfSegments()) {
00314 if (chain.getSegment(i).getName() == name) {
00315 return i+1;
00316 }
00317 i++;
00318 }
00319 return -1;
00320 }
00321
00322 bool Kinematics::solveCartToJnt(const KDL::JntArray &q_init, const KDL::Frame &q_in, KDL::JntArray &q_out,
00323 const KDL::Frame &tool_frame)
00324 {
00325 return solveCartToJnt(q_init, q_in, q_out, tool_frame,
00326 default_weight_ts, default_weight_js, default_lambda);
00327 }
00328
00329 bool Kinematics::solveCartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out,
00330 const KDL::Frame &tool_frame, const Eigen::MatrixXd &weight_ts, const Eigen::MatrixXd &weight_js,
00331 const double lambda)
00332 {
00333 KDL::Frame f;
00334 KDL::JntArray delta_q;
00335 KDL::Twist delta_twist;
00336 int i;
00337 double err;
00338
00339 KDL::Chain chain_with_tool(chain);
00340 chain_with_tool.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::None), tool_frame));
00341
00342 KDL::ChainFkSolverPos_recursive fk_solver(chain_with_tool);
00343 KDL::ChainIkSolverVel_wdls ik_solver(chain_with_tool);
00344
00345 ik_solver.setWeightTS(weight_ts);
00346 ik_solver.setWeightJS(weight_js);
00347 ik_solver.setLambda(lambda);
00348
00349 q_out = q_init;
00350
00351 for(i=0;i<max_iterations;i++)
00352 {
00353 fk_solver.JntToCart(q_out, f);
00354
00355 err = calculateEps(f, p_in, weight_ts);
00356
00357 if(isnan(err))
00358 {
00359 ROS_WARN("NaN in IK");
00360 return false;
00361 }
00362
00363 if( err < epsilon )
00364 break;
00365
00366 delta_twist = diff(f, p_in);
00367 ik_solver.CartToJnt(q_out, delta_twist, delta_q);
00368 KDL::Add(q_out, delta_q, q_out);
00369
00370 for(unsigned int j=0; j<joint_min.rows(); j++)
00371 {
00372 if(q_out(j) < joint_min(j))
00373 q_out(j) = joint_min(j);
00374 }
00375
00376 for(unsigned int j=0; j<joint_max.rows(); j++)
00377 {
00378 if(q_out(j) > joint_max(j))
00379 q_out(j) = joint_max(j);
00380 }
00381 }
00382
00383 ROS_INFO("IK terminating after %d iterations and error %lf", i, err);
00384
00385 if(i < max_iterations)
00386 return true;
00387 return false;
00388 }
00389
00390 double Kinematics::calculateEps(const KDL::Frame &f, const KDL::Frame &ref, const Eigen::MatrixXd &weight)
00391 {
00392 double f_roll, f_pitch, f_yaw;
00393 double ref_roll, ref_pitch, ref_yaw;
00394 f.M.GetRPY(f_roll, f_pitch, f_yaw);
00395 ref.M.GetRPY(ref_roll, ref_pitch, ref_yaw);
00396
00397 double x_diff = f.p.x() - ref.p.x();
00398 double y_diff = f.p.y() - ref.p.y();
00399 double z_diff = f.p.z() - ref.p.z();
00400 double roll_diff = f_roll - ref_roll;
00401 double pitch_diff = f_pitch - ref_pitch;
00402 double yaw_diff = f_yaw - ref_yaw;
00403
00404 return (x_diff * x_diff * weight(0, 0)) +
00405 (y_diff * y_diff * weight(1, 1)) +
00406 (z_diff * z_diff * weight(2, 2)) +
00407 (roll_diff * roll_diff * weight(3, 3)) +
00408 (pitch_diff * pitch_diff * weight(4, 4)) +
00409 (yaw_diff * yaw_diff * weight(5, 5));
00410 }
00411
00412 void Kinematics::initializeWeights(const kdl_arm_kinematics::KDLWeights &msg,
00413 Eigen::MatrixXd &weight_ts, Eigen::MatrixXd &weight_js, double &lambda)
00414 {
00415 if(msg.mode == kdl_arm_kinematics::KDLWeights::INVALID_MODE)
00416 {
00417 return;
00418 }
00419 if(msg.mode & kdl_arm_kinematics::KDLWeights::SET_TS)
00420 {
00421 for(int i=0, a=0; i<6; i++)
00422 {
00423 for(int j=0; j<6; j++, a++)
00424 weight_ts(i, j) = msg.weight_ts[a];
00425 }
00426 }
00427 if(msg.mode & kdl_arm_kinematics::KDLWeights::SET_JS)
00428 {
00429 int dim = sqrt(msg.weight_js.size());
00430 weight_js = Eigen::MatrixXd(dim, dim);
00431 for(int i=0, a=0; i<dim; i++)
00432 {
00433 for(int j=0; j<dim; j++, a++)
00434 weight_js(i, j) = msg.weight_js[a];
00435 }
00436 }
00437 if(msg.mode & kdl_arm_kinematics::KDLWeights::SET_LAMBDA)
00438 lambda = msg.lambda;
00439 }
00440
00441 bool Kinematics::getPositionIK(kinematics_msgs::GetPositionIK::Request &request,
00442 kinematics_msgs::GetPositionIK::Response &response) {
00443
00444 geometry_msgs::PoseStamped pose_msg_in = request.ik_request.pose_stamped;
00445 tf::Stamped<tf::Pose> transform;
00446 tf::Stamped<tf::Pose> transform_root;
00447 tf::poseStampedMsgToTF( pose_msg_in, transform );
00448
00449
00450 KDL::JntArray jnt_pos_in;
00451 KDL::JntArray jnt_pos_out;
00452 jnt_pos_in.resize(num_joints);
00453
00454 if(request.ik_request.ik_seed_state.joint_state.name.size() < num_joints ||
00455 request.ik_request.ik_seed_state.joint_state.position.size() < num_joints)
00456 {
00457 ROS_ERROR("Invalid seed state. It must contain states for all joints used by the IK solver.");
00458 return false;
00459 }
00460 for (unsigned int i=0; i < num_joints; i++) {
00461 int tmp_index = getJointIndex(request.ik_request.ik_seed_state.joint_state.name[i]);
00462 if (tmp_index >=0) {
00463 jnt_pos_in(tmp_index) = request.ik_request.ik_seed_state.joint_state.position[i];
00464 } else {
00465 ROS_ERROR("i: %d, No joint index for %s",i,request.ik_request.ik_seed_state.joint_state.name[i].c_str());
00466 return false;
00467 }
00468 }
00469
00470
00471 try {
00472 tf_listener.transformPose(root_name, transform, transform_root);
00473 } catch (...) {
00474 ROS_ERROR("Could not transform IK pose to frame: %s", root_name.c_str());
00475 response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
00476 return false;
00477 }
00478
00479 KDL::Frame F_dest;
00480 tf::TransformTFToKDL(transform_root, F_dest);
00481
00482 if (solveCartToJnt(jnt_pos_in, F_dest, jnt_pos_out))
00483 {
00484 response.solution.joint_state.name = info.joint_names;
00485 response.solution.joint_state.position.resize(num_joints);
00486 for (unsigned int i=0; i < num_joints; i++)
00487 {
00488 response.solution.joint_state.position[i] = jnt_pos_out(i);
00489 ROS_INFO("IK Solution: %s %d: %f",response.solution.joint_state.name[i].c_str(),i,jnt_pos_out(i));
00490 }
00491 response.error_code.val = response.error_code.SUCCESS;
00492 return true;
00493 } else {
00494 ROS_INFO("An IK solution could not be found");
00495 response.error_code.val = response.error_code.NO_IK_SOLUTION;
00496 return true;
00497 }
00498 }
00499
00500 bool Kinematics::getIKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request,
00501 kinematics_msgs::GetKinematicSolverInfo::Response &response) {
00502 response.kinematic_solver_info = info;
00503 return true;
00504 }
00505
00506 bool Kinematics::getFKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request,
00507 kinematics_msgs::GetKinematicSolverInfo::Response &response) {
00508 response.kinematic_solver_info = info;
00509 return true;
00510 }
00511
00512 bool Kinematics::getPositionFK(kinematics_msgs::GetPositionFK::Request &request,
00513 kinematics_msgs::GetPositionFK::Response &response) {
00514 KDL::Frame p_out;
00515 KDL::JntArray jnt_pos_in;
00516 geometry_msgs::PoseStamped pose;
00517 tf::Stamped<tf::Pose> tf_pose;
00518
00519 KDL::ChainFkSolverPos_recursive fk_solver(chain);
00520
00521 jnt_pos_in.resize(num_joints);
00522 for (unsigned int i=0; i < num_joints; i++) {
00523 int tmp_index = getJointIndex(request.robot_state.joint_state.name[i]);
00524 if (tmp_index >=0)
00525 jnt_pos_in(tmp_index) = request.robot_state.joint_state.position[i];
00526 }
00527
00528 response.pose_stamped.resize(request.fk_link_names.size());
00529 response.fk_link_names.resize(request.fk_link_names.size());
00530
00531 for (unsigned int i=0; i < request.fk_link_names.size(); i++) {
00532 int segmentIndex = getKDLSegmentIndex(request.fk_link_names[i]);
00533 ROS_DEBUG("End effector index: %d",segmentIndex);
00534 ROS_DEBUG("Chain indices: %d",chain.getNrOfSegments());
00535 if (fk_solver.JntToCart(jnt_pos_in,p_out,segmentIndex) >=0) {
00536 tf_pose.frame_id_ = root_name;
00537 tf_pose.stamp_ = ros::Time();
00538 tf::PoseKDLToTF(p_out,tf_pose);
00539 try {
00540 tf_listener.transformPose(request.header.frame_id,tf_pose,tf_pose);
00541 } catch (...) {
00542 ROS_ERROR("Could not transform FK pose to frame: %s",request.header.frame_id.c_str());
00543 response.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::FRAME_TRANSFORM_FAILURE;
00544 return false;
00545 }
00546 tf::poseStampedTFToMsg(tf_pose,pose);
00547 response.pose_stamped[i] = pose;
00548 response.fk_link_names[i] = request.fk_link_names[i];
00549 response.error_code.val = response.error_code.SUCCESS;
00550 } else {
00551 ROS_ERROR("Could not compute FK for %s",request.fk_link_names[i].c_str());
00552 response.error_code.val = arm_navigation_msgs::ArmNavigationErrorCodes::NO_FK_SOLUTION;
00553 }
00554 }
00555 return true;
00556 }
00557
00558 bool Kinematics::getWeightedIK(kdl_arm_kinematics::GetWeightedIK::Request &request,
00559 kdl_arm_kinematics::GetWeightedIK::Response &response)
00560 {
00561 geometry_msgs::PoseStamped pose_msg_in = request.pose;
00562 tf::Stamped<tf::Pose> transform;
00563 tf::Stamped<tf::Pose> transform_root;
00564 tf::poseStampedMsgToTF( pose_msg_in, transform );
00565
00566
00567 KDL::JntArray jnt_pos_in;
00568 KDL::JntArray jnt_pos_out;
00569 jnt_pos_in.resize(num_joints);
00570
00571 if(request.ik_seed.name.size() < num_joints ||
00572 request.ik_seed.position.size() < num_joints)
00573 {
00574 ROS_ERROR("Invalid seed state. It must contain states for all joints used by the IK solver.");
00575 return false;
00576 }
00577 for (unsigned int i=0; i < num_joints; i++)
00578 {
00579 int tmp_index = getJointIndex(request.ik_seed.name[i]);
00580 if (tmp_index >=0)
00581 jnt_pos_in(tmp_index) = request.ik_seed.position[i];
00582 else
00583 {
00584 ROS_ERROR("i: %d, No joint index for %s",i,request.ik_seed.name[i].c_str());
00585 return false;
00586 }
00587 }
00588
00589
00590 try
00591 {
00592 tf_listener.transformPose(root_name, transform, transform_root);
00593 }
00594 catch (...)
00595 {
00596 ROS_ERROR("Could not transform IK pose to frame: %s", root_name.c_str());
00597 response.error_code.val = response.error_code.FRAME_TRANSFORM_FAILURE;
00598 return false;
00599 }
00600
00601 KDL::Frame F_dest;
00602 tf::TransformTFToKDL(transform_root, F_dest);
00603
00604 KDL::Frame tool;
00605 tf::PoseMsgToKDL(request.tool_frame, tool);
00606
00608 Eigen::MatrixXd weight_ts(default_weight_ts);
00609 Eigen::MatrixXd weight_js(default_weight_js);
00610 double lambda = default_lambda;
00611
00612 initializeWeights(request.weights, weight_ts, weight_js, lambda);
00613
00614 if (solveCartToJnt(jnt_pos_in, F_dest, jnt_pos_out, tool, weight_ts, weight_js, lambda))
00615 {
00616 response.solution.name = info.joint_names;
00617 response.solution.position.resize(num_joints);
00618 for (unsigned int i=0; i < num_joints; i++)
00619 {
00620 response.solution.position[i] = jnt_pos_out(i);
00621 ROS_INFO("IK Solution: %s %d: %f",response.solution.name[i].c_str(),i,jnt_pos_out(i));
00622 }
00623 response.error_code.val = response.error_code.SUCCESS;
00624 return true;
00625 } else {
00626 ROS_INFO("An IK solution could not be found");
00627 response.error_code.val = response.error_code.NO_IK_SOLUTION;
00628 return true;
00629 }
00630 }
00631
00632 int main(int argc, char **argv) {
00633 ros::init(argc, argv, "arm_kinematics");
00634 try
00635 {
00636 Kinematics k;
00637 ros::spin();
00638 }
00639 catch(Kinematics::InitFailed &e)
00640 {
00641 ROS_ERROR("Could not initialize kinematics node: %s", e.what());
00642 return -1;
00643 }
00644
00645 return 0;
00646 }
00647