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 * joint_trajectory_action_controller.h 00020 * 00021 * Created on: 14.04.2011 00022 * Author: Henning Deeken <hdeeken@uos.de> 00023 */ 00024 00025 #ifndef JOINT_MOVEMENT_ACTION_CONTROLLER_H__ 00026 #define JOINT_MOVEMENT_ACTION_CONTROLLER_H__ 00027 00028 #include <vector> 00029 00030 #include <ros/node_handle.h> 00031 00032 #include <actionlib/server/simple_action_server.h> 00033 #include <actionlib/client/simple_action_client.h> 00034 00035 #include <katana/AbstractKatana.h> 00036 #include <sensor_msgs/JointState.h> 00037 #include <katana_msgs/JointMovementAction.h> 00038 00039 #include <moveit_msgs/JointLimits.h> 00040 00041 namespace katana 00042 { 00043 00044 class JointMovementActionController 00045 { 00046 typedef actionlib::SimpleActionServer<katana_msgs::JointMovementAction> JMAS; 00047 typedef actionlib::SimpleActionClient<katana_msgs::JointMovementAction> JMAC; 00048 00049 public: 00050 JointMovementActionController(boost::shared_ptr<AbstractKatana> katana); 00051 virtual ~JointMovementActionController(); 00052 00053 private: 00054 // robot and joint state 00055 std::vector<std::string> joints_; // controlled joints, same order as expected by the KNI (index 0 = first motor, ...) 00056 std::vector<std::string> gripper_joints_; 00057 boost::shared_ptr<AbstractKatana> katana_; 00058 00059 sensor_msgs::JointState movement_goal_; 00060 00061 // action server 00062 void executeCB(const JMAS::GoalConstPtr &goal); 00063 JMAS action_server_; 00064 00065 bool suitableJointGoal(const std::vector<std::string>& jointGoalNames); 00066 00067 sensor_msgs::JointState adjustJointGoalPositionsToMotorLimits(const sensor_msgs::JointState &jointGoal); 00068 00069 }; 00070 } 00071 00072 #endif /* JOINT_MOVEMENT_ACTION_CONTROLLER_H_ */