$search
00001 /* 00002 * UOS-ROS packages - Robot Operating System code by the University of Osnabrück 00003 * Copyright (C) 2010 University of Osnabrück 00004 * 00005 * This program is free software; you can redistribute it and/or 00006 * modify it under the terms of the GNU General Public License 00007 * as published by the Free Software Foundation; either version 2 00008 * of the License, or (at your option) any later version. 00009 * 00010 * This program is distributed in the hope that it will be useful, 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 * GNU General Public License for more details. 00014 * 00015 * You should have received a copy of the GNU General Public License 00016 * along with this program; if not, write to the Free Software 00017 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 00018 * 00019 * non_constraint_aware_ik_adapter.cpp 00020 * 00021 * Created on: 19.5.2011 00022 * Author: Henning Deeken <hdeeken@uos.de> 00023 */ 00024 00039 #include <ros/ros.h> 00040 00041 #include <urdf/joint.h> 00042 #include <urdf/model.h> 00043 #include <kinematics_msgs/GetConstraintAwarePositionIK.h> 00044 #include <kinematics_msgs/GetPositionIK.h> 00045 #include <kinematics_msgs/GetKinematicSolverInfo.h> 00046 #include <arm_navigation_msgs/JointLimits.h> 00047 #include <orrosplanning/IK.h> 00048 00049 ros::ServiceClient client_; 00050 std::vector<std::string> joint_names_; 00051 std::vector<arm_navigation_msgs::JointLimits> joint_limits_; 00052 00053 ros::ServiceServer ikService; 00054 ros::ServiceServer infoService; 00055 00056 bool getOpenRaveIK(kinematics_msgs::GetConstraintAwarePositionIK::Request &req, 00057 kinematics_msgs::GetConstraintAwarePositionIK::Response &resp) 00058 { 00059 00060 orrosplanning::IK srv; 00061 00062 // converting the GetConstraintAwarePositionIK::Request to an proper orrosplanning::IK::Request 00063 00064 srv.request.joint_state = req.ik_request.robot_state.joint_state; 00065 srv.request.pose_stamped = req.ik_request.pose_stamped; 00066 srv.request.iktype = "Translation3D"; 00067 srv.request.filteroptions = 0; 00068 client_.call(srv); 00069 00070 resp.solution.joint_state.header = srv.response.solutions.header; 00071 resp.solution.joint_state.name = srv.response.solutions.joint_names; 00072 00073 if (srv.response.solutions.points.size() == 0) 00074 { 00075 ROS_ERROR("OpenRaveIK found no solutions!"); 00076 } 00077 else 00078 { 00079 00080 if (srv.response.solutions.points.size() > 1) 00081 ROS_INFO("OpenRaveIK found more than one solution, we'll take the first one..."); 00082 00083 resp.solution.joint_state.position.resize(srv.response.solutions.points[0].positions.size()); 00084 00085 for (size_t i = 0; 0 < srv.response.solutions.points[0].positions.size(); i++) 00086 resp.solution.joint_state.position[i] = srv.response.solutions.points[0].positions[i]; 00087 00088 } 00089 00090 resp.error_code = srv.response.error_code; 00091 00092 return true; 00093 } 00094 00095 bool get_kinematic_solver_info(kinematics_msgs::GetKinematicSolverInfo::Request &req, 00096 kinematics_msgs::GetKinematicSolverInfo::Response &res) 00097 { 00098 res.kinematic_solver_info.joint_names = joint_names_; 00099 res.kinematic_solver_info.limits = joint_limits_; 00100 00101 return true; 00102 } 00103 00104 int main(int argc, char** argv) 00105 { 00106 ros::init(argc, argv, "katana_openrave_kinematics"); 00107 ros::NodeHandle n; 00108 00109 ros::NodeHandle pn("~"); 00110 std::string ik_service; 00111 00112 pn.param<std::string> ("ik_service", ik_service, "IK"); 00113 00114 client_ = n.serviceClient<orrosplanning::IK> (ik_service); 00115 00116 joint_names_.resize(5); 00117 joint_limits_.resize(5); 00118 00119 std::string robot_desc_string; 00120 00121 if (!n.getParam("robot_description", robot_desc_string)) 00122 { 00123 ROS_FATAL("Couldn't get a robot_description from the param server"); 00124 return 0; 00125 } 00126 00127 urdf::Model model; 00128 model.initString(robot_desc_string); 00129 00130 XmlRpc::XmlRpcValue joint_names; 00131 00132 // Gets all of the joints 00133 if (!n.getParam("katana_joints", joint_names)) 00134 { 00135 ROS_ERROR("No joints given. (namespace: %s)", n.getNamespace().c_str()); 00136 } 00137 if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) 00138 { 00139 ROS_ERROR("Malformed joint specification. (namespace: %s)", n.getNamespace().c_str()); 00140 } 00141 if (joint_names.size() != 5) 00142 { 00143 ROS_ERROR("Wrong number of joints! was: %d, expected: %zu", joint_names.size(), 5); 00144 } 00145 for (size_t i = 0; i < 5; ++i) 00146 { 00147 XmlRpc::XmlRpcValue &name_value = joint_names[i]; 00148 if (name_value.getType() != XmlRpc::XmlRpcValue::TypeString) 00149 { 00150 ROS_ERROR("Array of joint names should contain all strings. (namespace: %s)", 00151 n.getNamespace().c_str()); 00152 } 00153 00154 joint_names_[i] = (std::string)name_value; 00155 joint_limits_[i].joint_name = (std::string)name_value; 00156 joint_limits_[i].min_position = model.getJoint(joint_names_[i])->limits->lower; 00157 joint_limits_[i].max_position = model.getJoint(joint_names_[i])->limits->upper; 00158 } 00159 00160 ikService = pn.advertiseService("get_openrave_ik", getOpenRaveIK); 00161 infoService = pn.advertiseService("get_kinematic_solver_info", get_kinematic_solver_info); 00162 00163 00164 //ros::service::waitForService("get_openrave_ik"); 00165 //ros::service::waitForService("get_kinematic_solver_info"); 00166 00167 ROS_INFO("katana_kinematics_constraint_aware sucessfully established it's services"); 00168 for (size_t i = 0; i < 5; ++i) 00169 ROS_INFO("%s",joint_limits_[i].joint_name.c_str()); 00170 00171 00172 ros::spin(); 00173 00174 return 0; 00175 } 00176 00177