AbstractKatana.h
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  * AbstractKatana.h
00020  *
00021  *  Created on: 20.12.2010
00022  *      Author: Martin Günther <mguenthe@uos.de>
00023  */
00024 
00025 #ifndef ABSTRACTKATANA_H_
00026 #define ABSTRACTKATANA_H_
00027 
00028 #include <ros/ros.h>
00029 #include <urdf/model.h>
00030 #include <urdf_model/joint.h>
00031 
00032 #include <katana/SpecifiedTrajectory.h>
00033 #include <katana/katana_constants.h>
00034 
00035 #include <moveit_msgs/JointLimits.h>
00036 
00037 namespace katana
00038 {
00039 
00040 class AbstractKatana
00041 {
00042 public:
00043   AbstractKatana();
00044   virtual ~AbstractKatana();
00045 
00046   virtual void refreshEncoders() = 0;
00047   virtual bool executeTrajectory(boost::shared_ptr<SpecifiedTrajectory> traj,
00048                                  boost::function<bool()> isPreemptRequested) = 0;
00049   virtual void freezeRobot();
00050 
00059   virtual bool moveJoint(int jointIndex, double turningAngle) = 0;
00060 
00061   virtual int getJointIndex(std::string joint_name);
00062 
00063   virtual std::vector<std::string> getJointNames();
00064   virtual std::vector<int> getJointTypes();
00065 
00066   virtual std::vector<std::string> getGripperJointNames();
00067   virtual std::vector<int> getGripperJointTypes();
00068 
00069   virtual std::vector<double> getMotorAngles();
00070   virtual std::vector<double> getMotorVelocities();
00071 
00072   virtual std::vector<moveit_msgs::JointLimits> getMotorLimits();
00073   virtual double getMotorLimitMax(std::string joint_name);
00074   virtual double getMotorLimitMin(std::string joint_name);
00075 
00076   virtual void refreshMotorStatus();
00077   virtual bool someMotorCrashed() = 0;
00078   virtual bool allJointsReady() = 0;
00079   virtual bool allMotorsReady() = 0;
00080 
00081 
00082 protected:
00083   // only the 5 "real" joints:
00084   std::vector<std::string> joint_names_;
00085   std::vector<int> joint_types_;
00086 
00087   // the two "finger" joints of the gripper:
00088   std::vector<std::string> gripper_joint_names_;
00089   std::vector<int> gripper_joint_types_;
00090 
00091   // all motors (the 5 "real" joints plus the gripper)
00092 
00093   std::vector<double> motor_angles_;
00094   std::vector<double> motor_velocities_;
00095 
00096   // the motor limits of the 6 motors
00097 
00098   std::vector<moveit_msgs::JointLimits> motor_limits_;
00099 };
00100 
00101 }
00102 
00103 #endif /* ABSTRACTKATANA_H_ */


katana
Author(s): Martin Günther
autogenerated on Mon Aug 14 2017 02:45:49