$search
00001 /* 00002 * UOS-ROS packages - Robot Operating System code by the University of Osnabrück 00003 * Copyright (C) 2011 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 * katana_teleop_cyborgevo.h 00020 * 00021 * Created on: 03.06.2011 00022 * Author: Henning Deeken <hdeeken@uos.de> 00023 */ 00024 00025 #ifndef KATANA_TELEOP_CYBORGEVO_H__ 00026 #define KATANA_TELEOP_CYBORGEVO_H__ 00027 00028 #include <ros/ros.h> 00029 #include <joy/Joy.h> 00030 #include <sensor_msgs/JointState.h> 00031 #include <geometry_msgs/PoseStamped.h> 00032 #include <kinematics_msgs/GetPositionFK.h> 00033 #include <kinematics_msgs/GetConstraintAwarePositionIK.h> 00034 #include <kinematics_msgs/GetKinematicSolverInfo.h> 00035 00036 #include <katana_msgs/JointMovementAction.h> 00037 #include <actionlib/server/simple_action_server.h> 00038 #include <actionlib/client/simple_action_client.h> 00039 00040 typedef actionlib::SimpleActionClient<katana_msgs::JointMovementAction> JMAC; 00041 00042 namespace katana{ 00043 00044 class KatanaTeleopCyborgEvo 00045 { 00046 public: 00047 00048 KatanaTeleopCyborgEvo(); 00049 00050 bool matchJointGoalRequest(); 00051 void addGripperGoalPosition(std::string name, float increment); 00052 bool getCurrentJointPosition(sensor_msgs::JointState &joint_state, std::string &name, float &position); 00053 00054 void jointStateCallback(const sensor_msgs::JointState::ConstPtr& js); 00055 void cyborgevoCallback(const joy::Joy::ConstPtr& joy); 00056 00057 void loop(); 00058 00059 ~KatanaTeleopCyborgEvo(){} 00060 00061 private: 00062 00063 bool active, initial; 00064 00065 std::vector<double> current_RPY_Orientation,initial_RPY_Orientation, saved_RPY_Orientation; 00066 katana_msgs::JointMovementGoal goal; 00067 sensor_msgs::JointState currentState, savedState, initialState; 00068 geometry_msgs::PoseStamped currentPose, goalPose; 00069 00070 std::string ik_service, fk_service, ik_solver_info; 00071 ros::ServiceClient info_client, fk_client, ik_client; 00072 00073 ros::Subscriber js_sub_, cyborgevo_sub; 00074 00075 JMAC action_client; 00076 00077 }; 00078 00079 } // end namespace katana 00080 #endif /* KATANA_TELEOP_CYBORGEVO_H__ */ 00081