AbstractKatana.h
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2010 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * AbstractKatana.h
20  *
21  * Created on: 20.12.2010
22  * Author: Martin Günther <mguenthe@uos.de>
23  */
24 
25 #ifndef ABSTRACTKATANA_H_
26 #define ABSTRACTKATANA_H_
27 
28 #include <ros/ros.h>
29 #include <urdf/model.h>
30 #include <urdf_model/joint.h>
31 
34 
35 #include <moveit_msgs/JointLimits.h>
36 
37 namespace katana
38 {
39 
41 {
42 public:
44  virtual ~AbstractKatana();
45 
46  virtual void refreshEncoders() = 0;
48  boost::function<bool()> isPreemptRequested) = 0;
49  virtual void freezeRobot();
50 
59  virtual bool moveJoint(int jointIndex, double turningAngle) = 0;
60 
61  virtual int getJointIndex(std::string joint_name);
62 
63  virtual std::vector<std::string> getJointNames();
64  virtual std::vector<int> getJointTypes();
65 
66  virtual std::vector<std::string> getGripperJointNames();
67  virtual std::vector<int> getGripperJointTypes();
68 
69  virtual std::vector<double> getMotorAngles();
70  virtual std::vector<double> getMotorVelocities();
71 
72  virtual std::vector<moveit_msgs::JointLimits> getMotorLimits();
73  virtual double getMotorLimitMax(std::string joint_name);
74  virtual double getMotorLimitMin(std::string joint_name);
75 
76  virtual void refreshMotorStatus();
77  virtual bool someMotorCrashed() = 0;
78  virtual bool allJointsReady() = 0;
79  virtual bool allMotorsReady() = 0;
80 
81 
82 protected:
83  // only the 5 "real" joints:
84  std::vector<std::string> joint_names_;
85  std::vector<int> joint_types_;
86 
87  // the two "finger" joints of the gripper:
88  std::vector<std::string> gripper_joint_names_;
89  std::vector<int> gripper_joint_types_;
90 
91  // all motors (the 5 "real" joints plus the gripper)
92 
93  std::vector<double> motor_angles_;
94  std::vector<double> motor_velocities_;
95 
96  // the motor limits of the 6 motors
97 
98  std::vector<moveit_msgs::JointLimits> motor_limits_;
99 };
100 
101 }
102 
103 #endif /* ABSTRACTKATANA_H_ */
virtual std::vector< std::string > getJointNames()
virtual int getJointIndex(std::string joint_name)
virtual bool executeTrajectory(boost::shared_ptr< SpecifiedTrajectory > traj, boost::function< bool()> isPreemptRequested)=0
virtual double getMotorLimitMin(std::string joint_name)
std::vector< double > motor_angles_
std::vector< int > joint_types_
virtual bool allJointsReady()=0
std::vector< int > gripper_joint_types_
virtual std::vector< int > getGripperJointTypes()
std::vector< double > motor_velocities_
std::vector< std::string > joint_names_
virtual bool someMotorCrashed()=0
virtual bool allMotorsReady()=0
virtual bool moveJoint(int jointIndex, double turningAngle)=0
std::vector< moveit_msgs::JointLimits > motor_limits_
virtual std::vector< std::string > getGripperJointNames()
virtual std::vector< double > getMotorVelocities()
virtual std::vector< double > getMotorAngles()
virtual void refreshEncoders()=0
virtual void freezeRobot()
std::vector< std::string > gripper_joint_names_
virtual std::vector< int > getJointTypes()
virtual void refreshMotorStatus()
virtual double getMotorLimitMax(std::string joint_name)
virtual std::vector< moveit_msgs::JointLimits > getMotorLimits()


katana
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:58