non_constraint_aware_ik_adapter.cpp
Go to the documentation of this file.
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: 09.01.2011
00022  *      Author: Martin Günther <mguenthe@uos.de>
00023  */
00024 
00040 #include <ros/ros.h>
00041 
00042 #include <kinematics_msgs/GetConstraintAwarePositionIK.h>
00043 #include <kinematics_msgs/GetPositionIK.h>
00044 
00045 
00046 ros::ServiceClient client_;
00047 
00048 bool getConstraintAwareIk(kinematics_msgs::GetConstraintAwarePositionIK::Request &req,
00049                           kinematics_msgs::GetConstraintAwarePositionIK::Response &resp) {
00050 
00051   kinematics_msgs::GetPositionIK srv;
00052   srv.request.ik_request = req.ik_request;
00053   srv.request.timeout = req.timeout;
00054 
00055   client_.call(srv);
00056 
00057   ROS_DEBUG("non_constraint_aware_ik_adapter: get'ConstraintAware'Ik is called");
00058   resp.error_code = srv.response.error_code;
00059   resp.solution = srv.response.solution;
00060 
00061   return true;
00062 }
00063 
00064 
00065 int main(int argc, char** argv)
00066 {
00067   ros::init(argc, argv, "non_constraint_aware_ik_adapter");
00068   ros::NodeHandle n;
00069 
00070   ros::NodeHandle pn("~");
00071   std::string ik_service;
00072   pn.param<std::string>("ik_service", ik_service, "get_ik");
00073 
00074   client_ = n.serviceClient<kinematics_msgs::GetPositionIK>(ik_service);
00075 
00076   ros::ServiceServer service = pn.advertiseService("get_constraint_aware_ik", getConstraintAwareIk);
00077 
00078   ros::spin();
00079 
00080   return 0;
00081 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


katana_kinematics_constraint_aware
Author(s): Henning Deeken, Martin Günther
autogenerated on Tue Mar 5 2013 15:20:34