Hekateros  3.4.3
RoadNarrows Robotics Robot Arm Project
hekCalib.h
Go to the documentation of this file.
1 ////////////////////////////////////////////////////////////////////////////////
2 //
3 // Package: Hekateros
4 //
5 // Library: libhekateros
6 //
7 // File: hekCalib.h
8 //
9 /*! \file
10  *
11  * $LastChangedDate: 2014-11-18 14:31:49 -0700 (Tue, 18 Nov 2014) $
12  * $Rev: 3810 $
13  *
14  * \brief HekCalib - Hekateros calibration abstract base class interface.
15  *
16  * \author Robin Knight (robin.knight@roadnarrows.com)
17  *
18  * \copyright
19  * \h_copy 2013-2018. RoadNarrows LLC.\n
20  * http://www.roadnarrows.com\n
21  * All Rights Reserved
22  */
23 /*
24  * @EulaBegin@
25  *
26  * Unless otherwise stated explicitly, all materials contained are copyrighted
27  * and may not be used without RoadNarrows LLC's written consent,
28  * except as provided in these terms and conditions or in the copyright
29  * notice (documents and software) or other proprietary notice provided with
30  * the relevant materials.
31  *
32  * IN NO EVENT SHALL THE AUTHOR, ROADNARROWS LLC, OR ANY
33  * MEMBERS/EMPLOYEES/CONTRACTORS OF ROADNARROWS OR DISTRIBUTORS OF THIS SOFTWARE
34  * BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR
35  * CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS
36  * DOCUMENTATION, EVEN IF THE AUTHORS OR ANY OF THE ABOVE PARTIES HAVE BEEN
37  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
38  *
39  * THE AUTHORS AND ROADNARROWS LLC SPECIFICALLY DISCLAIM ANY WARRANTIES,
40  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
41  * FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS ON AN
42  * "AS IS" BASIS, AND THE AUTHORS AND DISTRIBUTORS HAVE NO OBLIGATION TO
43  * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
44  *
45  * @EulaEnd@
46  */
47 ////////////////////////////////////////////////////////////////////////////////
48 
49 #ifndef _HEK_CALIB_H
50 #define _HEK_CALIB_H
51 
52 #include <string>
53 
54 #include "rnr/rnrconfig.h"
55 
56 #include "Dynamixel/Dynamixel.h"
57 #include "Dynamixel/DynaServo.h"
58 
59 #include "Hekateros/hekateros.h"
60 
61 namespace hekateros
62 {
63  //
64  // Forward declaraions.
65  //
66  class HekRobot;
67 
68  /*!
69  * \brief Hekateros robotic manipulator calibration abstract base class.
70  *
71  * \param robot Instance of \h_hek robot.
72  */
73  class HekCalib
74  {
75  public:
76 
77  /*!
78  * \breif Default initialization constructor.
79  *
80  * \param robot Instance of \h_hek robot.
81  */
82  HekCalib(HekRobot &robot) : m_robot(robot)
83  {
84  }
85 
86  /*!
87  * \breif Destructor.
88  */
89  virtual ~HekCalib()
90  {
91  }
92 
93  /*!
94  * \brief Calibrate the \h_hek's robotic arm.
95  *
96  * \copydoc doc_return_std
97  */
98  virtual int calibrate() = 0;
99 
100  /*!
101  * \brief Move joint to position.
102  *
103  * This call blocks until move is complete.
104  *
105  * \param strJointName Joint name.
106  * \param fJointGoalPos Joint goal position (radians).
107  * \param fJointGoalVel Joint goal velocity (radians/second).
108  *
109  * \return New joint position (radians).
110  */
111  virtual double moveWait(const std::string &strJointName,
112  const double fJointGoalPos,
113  const double fJointGoalVel);
114 
115  /*!
116  * \brief Move joint until torque limit is reached.
117  *
118  * This call blocks until move is complete.
119  *
120  * \param strJointName Joint name.
121  * \param fJointGoalPos Joint goal position (radians).
122  * \param fJointGoalVel Joint goal velocity (radians/second).
123  *
124  * \return New joint position (radians) at over torque condition.
125  */
126  virtual double moveToTorqueLimit(const std::string &strJointName,
127  const double fJointGoalPos,
128  const double fJointGoalVel);
129 
130  /*!
131  * \brief Move joint until unoccluded optical limit position is detected.
132  *
133  * This call blocks until move is complete.
134  *
135  * \param strJointName Joint name.
136  * \param fJointGoalPos Joint goal position (radians).
137  * \param fJointGoalVel Joint goal velocity (radians/second).
138  * \param byMask Mask of limits to check.
139  *
140  * \return New joint position (radians) at first light.
141  */
142  virtual double moveToLight(const std::string &strJointName,
143  const double fJointGoalPos,
144  const double fJointGoalVel,
145  byte_t byMask);
146 
147  /*!
148  * \brief Move joint until occluded optical limit position is detected.
149  *
150  * This call blocks until move is complete.
151  *
152  * \param strJointName Joint name.
153  * \param fJointGoalPos Joint goal position (radians).
154  * \param fJointGoalVel Joint goal velocity (radians/second).
155  * \param byMask Mask of limits to check.
156  *
157  * \return New joint position (radians) at first dark.
158  */
159  virtual double moveToDark(const std::string &strJointName,
160  const double fJointGoalPos,
161  const double fJointGoalVel,
162  byte_t byMask);
163 
164  protected:
165  HekRobot &m_robot; ///< robot instance
166  };
167 
168 } // namespace hekaeros
169 
170 #endif // _HEK_CALIB_H
virtual int calibrate()=0
Calibrate the <b><i>Hekateros</i></b>&#39;s robotic arm.
virtual double moveToTorqueLimit(const std::string &strJointName, const double fJointGoalPos, const double fJointGoalVel)
Move joint until torque limit is reached.
Definition: hekCalib.cxx:110
HekRobot & m_robot
robot instance
Definition: hekCalib.h:165
virtual double moveToLight(const std::string &strJointName, const double fJointGoalPos, const double fJointGoalVel, byte_t byMask)
Move joint until unoccluded optical limit position is detected.
Definition: hekCalib.cxx:164
virtual double moveWait(const std::string &strJointName, const double fJointGoalPos, const double fJointGoalVel)
Move joint to position.
Definition: hekCalib.cxx:65
virtual double moveToDark(const std::string &strJointName, const double fJointGoalPos, const double fJointGoalVel, byte_t byMask)
Move joint until occluded optical limit position is detected.
Definition: hekCalib.cxx:241
Hekateros robotic manipulator calibration abstract base class.
Definition: hekCalib.h:73
Top-level package include file.
virtual ~HekCalib()
Definition: hekCalib.h:89
Hekateros robotic manipulator plus accesories class.
Definition: hekRobot.h:88
HekCalib(HekRobot &robot)
Definition: hekCalib.h:82
The <b><i>Hekateros</i></b> namespace encapsulates all <b><i>Hekateros</i></b> related constructs...
Definition: hekateros.h:56