Katana300.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) 2011 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  * Katana300.h
20  *
21  * Created on: Dec 13, 2011
22  * Authors:
23  * Hannes Raudies <h.raudies@hs-mannheim.de>
24  * Martin Günther <mguenthe@uos.de>
25  */
26 
27 #ifndef KATANA300_H_
28 #define KATANA300_H_
29 
30 #include <ros/ros.h>
31 #include <boost/thread/recursive_mutex.hpp>
32 #include <boost/thread.hpp>
33 
34 #include <kniBase.h>
35 
37 #include <katana/AbstractKatana.h>
38 #include <katana/KNIConverter.h>
39 #include <katana/Katana.h>
40 
41 namespace katana
42 {
43 
44 class Katana300 : public Katana
45 {
46 public:
47  Katana300();
48  virtual ~Katana300();
49 
50  virtual void setLimits();
51 
53  boost::function<bool()> isPreemptRequested);
54 
55  virtual void freezeRobot();
56  virtual bool moveJoint(int jointIndex, double turningAngle);
57 
58  virtual void refreshMotorStatus();
59  virtual bool allJointsReady();
60  virtual bool allMotorsReady();
61 
62  virtual void testSpeed();
63 
64  const double JOINTS_STOPPED_POS_TOLERANCE = 0.01;
65  const double JOINTS_STOPPED_VEL_TOLERANCE = 0.01;
66 
67 private:
68  std::vector<double> desired_angles_;
69 
70 };
71 
72 }
73 
74 #endif /* KATANA300_H_ */
const double JOINTS_STOPPED_POS_TOLERANCE
Definition: Katana300.h:64
virtual void testSpeed()
Definition: Katana300.cpp:140
const double JOINTS_STOPPED_VEL_TOLERANCE
Definition: Katana300.h:65
virtual void freezeRobot()
Definition: Katana300.cpp:72
virtual ~Katana300()
Definition: Katana300.cpp:40
virtual void setLimits()
Definition: Katana300.cpp:44
virtual bool moveJoint(int jointIndex, double turningAngle)
Definition: Katana300.cpp:81
virtual void refreshMotorStatus()
Definition: Katana300.cpp:93
virtual bool allMotorsReady()
Definition: Katana300.cpp:124
Wrapper class around the KNI (Katana Native Library).
Definition: Katana.h:48
virtual bool allJointsReady()
Definition: Katana300.cpp:103
std::vector< double > desired_angles_
Definition: Katana300.h:68
virtual bool executeTrajectory(boost::shared_ptr< SpecifiedTrajectory > traj, boost::function< bool()> isPreemptRequested)
Definition: Katana300.cpp:223


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