Dynamixel  2.9.5
RoadNarrows Robotics Dynamixel Package
DynaServoMX28.cxx
Go to the documentation of this file.
1 ////////////////////////////////////////////////////////////////////////////////
2 //
3 // Package: Dynamixel
4 //
5 // Library: libDynamixel
6 //
7 // File: DynaServoMX28.cxx
8 //
9 /*! \file
10  *
11  * $LastChangedDate: 2015-03-13 13:28:02 -0600 (Fri, 13 Mar 2015) $
12  * $Rev: 3890 $
13  *
14  * \brief RoadNarrows MX-28 Dynamixel servo class.
15  *
16  * \author Robin Knight (robin.knight@roadnarrows.com)
17  *
18  * \copyright
19  * \h_copy 2011-2017. 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 #include <stdio.h>
50 #include <stdlib.h>
51 #include <libgen.h>
52 #include <string.h>
53 #include <stdarg.h>
54 
55 #include "rnr/rnrconfig.h"
56 #include "rnr/log.h"
57 #include "rnr/new.h"
58 #include "rnr/units.h"
59 
60 #include "Dynamixel/Dynamixel.h"
61 #include "Dynamixel/MX.h"
62 #include "Dynamixel/DynaError.h"
63 #include "Dynamixel/DynaComm.h"
64 #include "Dynamixel/DynaServo.h"
67 
68 #include "DynaLibInternal.h"
69 
70 
71 // ---------------------------------------------------------------------------
72 // Private Interface
73 // ---------------------------------------------------------------------------
74 
75 /*!
76  * \brief MX-28 Servo EEPROM Control Table Information.
77  */
79 {
80  {0x00, "Model Number", 2, 0xffff, false, NULL},
81  {0x02, "Firmware Version", 1, 0xff, false, "%u"},
82  {0x03, "Servo Id", 1, 0xff, false, "%u"},
83  {0x04, "Baud Rate", 1, 0xff, false, "%u"},
84  {0x05, "Return Delay Time", 1, 0xff, false, "%u"},
85  {0x06, "CW Angle Limit", 2, 0x3ff, false, "%u"},
86  {0x08, "CCW Angle Limit", 2, 0x3ff, false, "%u"},
87  {0x0b, "Highest Temperature Limit", 1, 0xff, false, "%u"},
88  {0x0c, "Lowest Voltage Limit", 1, 0xff, false, "%u"},
89  {0x0d, "Highest Voltage Limit", 1, 0xff, false, "%u"},
90  {0x0e, "Maximum Torque", 2, 0x3ff, false, "%u"},
91  {0x10, "Status Return Level", 1, 0xff, false, "%u"},
92  {0x11, "Alarm LED", 1, 0xff, false, "%u"},
93  {0x12, "Alarm Shutdown", 1, 0xff, false, NULL},
94  {0x14, "Multi Turn Offset", 2, 0xffff, true, "%d"},
95  {0x16, "Resolution Divider", 1, 0xff, false, "%u"}
96 };
97 
98 /*!
99  * \brief MX-28 Servo RAM Control Table Information.
100  */
102 {
103  {0x18, "Torque Enable", 1, 0xff, false, "%u"},
104  {0x19, "LED", 1, 0xff, false, "%u"},
105  {0x1a, "CW Compliance Margin", 1, 0xff, false, "%u"},
106  {0x1b, "CCW Compliance Margin", 1, 0xff, false, "%u"},
107  {0x1c, "CW Compliance Slope", 1, 0xff, false, "%u"},
108  {0x1d, "CCW Compliance Slope", 1, 0xff, false, "%u"},
109  {0x1e, "Goal Position", 2, 0x3ff, false, "%u"},
110  {0x20, "Goal Speed", 2, 0x7ff, true, "%d"},
111  {0x22, "Torque Limit", 2, 0x3ff, false, "%u"},
112  {0x24, "Current Position", 2, 0x3ff, false, "%u"},
113  {0x26, "Current Speed", 2, 0x7ff, true, "%d"},
114  {0x28, "Current Load", 2, 0x7ff, true, "%d"},
115  {0x2a, "Current Voltage", 1, 0xff, false, "%u"},
116  {0x2b, "Current Temperature", 1, 0xff, false, "%u"},
117  {0x2c, "Registered", 1, 0xff, false, "%u"},
118  {0x2e, "Moving", 1, 0xff, false, "%u"},
119  {0x2f, "Lock", 1, 0xff, false, "%u"},
120  {0x30, "Punch", 2, 0x3ff, false, "%u"},
121  {0x49, "Goal Acceleration", 1, 0xff, false, "%u"}
122 };
123 
124 
125 // ---------------------------------------------------------------------------
126 // DynaServoMX28 Class
127 // ---------------------------------------------------------------------------
128 
129 // . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
130 // Constructors and Destructors
131 // . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
132 
134  int nServoId,
135  uint_t uModelNum,
136  uint_t uFwVer) :
137  DynaServoGeneric(comm)
138 {
139  Init(nServoId, uFwVer); // this class
140  SyncData(); // generic
141  CheckData(); // generic
142 }
143 
145 {
146 }
147 
148 
149 // . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
150 // Servo Read/Write Functions
151 // . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
152 
154 {
155  DumpCtlTbl("EEPROM", MX28EEPROMCtlTblInfo, arraysize(MX28EEPROMCtlTblInfo));
156 
157  printf("\n");
158 
159  DumpCtlTbl("RAM", MX28RAMCtlTblInfo, arraysize(MX28RAMCtlTblInfo));
160 }
161 
162 
163 // . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
164 // Protected Interface
165 // . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
166 
167 void DynaServoMX28::Init(int nServoId, uint_t uFwVer)
168 {
169  DynaServo::Init(nServoId, DYNA_MODEL_NUM, uFwVer);
170 
171  InitSpec(); // this class
172  InitCfg(); // generic
173  InitState(); // generic
174 }
175 
177 {
178  //
179  // Fixed servo specification.
180  //
181  if( m_spec.m_sModelName != NULL )
182  {
183  delete[] m_spec.m_sModelName;
184  }
185 
186  // physical and fixed features
187  m_spec.m_sModelName = newstr("MX-28");
205 
206  // raw units
218 }
RoadNarrows Dynamixel Bus Communications Abstract Base Class Interface.
char * newstr(const char *s)
Allocate new duplicated string.
#define DYNA_MX28_SPEC_ANGLE_MIN_DEG
minimum rotation angle in servo mode (deg)
Definition: MX.h:283
#define DYNA_TORQUE_MAX_RAW
maximum raw torque
Definition: Dynamixel.h:282
double m_fMaxSpeed
max no-load speed (rpm) at optimal power
Definition: DynaTypes.h:91
#define DYNA_MX28_SPEC_GEAR_RATIO
gear reduction ratio : 1
Definition: MX.h:275
void DumpCtlTbl(const char *sTblName, const DynaCtlTblEntry_T tblInfo[], size_t uSize)
Dump the servo control tabl values to stdout.
Definition: DynaServo.cxx:422
RoadNarrows MX Series Dynamixel Declarations.
uint_t m_uRawVoltMin
minimum raw voltage value
Definition: DynaTypes.h:110
#define DYNA_MX28_SPEC_HAS_360_POS
servo does provide 360 &deg; position data
Definition: MX.h:292
#define DYNA_TEMP_MIN_RAW
minimum raw temperature
Definition: Dynamixel.h:295
double m_fHeight
height (mm)
Definition: DynaTypes.h:86
uint_t m_uRawPosMin
minimum raw position value (servo mode)
Definition: DynaTypes.h:101
uint_t m_uRawSpeedMax
maximum raw speed magnitude value
Definition: DynaTypes.h:105
#define DYNA_VOLT_MAX_RAW
maximum raw temperature
Definition: Dynamixel.h:309
double m_fVoltMax
maximum operational voltage (V)
Definition: DynaTypes.h:99
uint_t m_uRawSpeedMin
minimum raw speed magnitude value
Definition: DynaTypes.h:104
#define DYNA_MX28_SPEC_WIDTH_MM
width (mm)
Definition: MX.h:270
Generic Dynamixel Servo Base Class Interface.
#define DYNA_SPEED_MIN_RAW
minimum raw value
Definition: Dynamixel.h:265
static const int DYNA_MODEL_NUM
Definition: DynaServoMX28.h:81
double m_fDepth
depth (mm)
Definition: DynaTypes.h:87
void Init()
Initialize servo class instance.
#define DYNA_MX28_SPEC_CTL_METHOD
position control method (see Dynamixel Internal Position Control Methods)
Definition: MX.h:307
uint_t m_uCtlMethodUsed
Dynamixel Internal Position Control Methods
Definition: DynaTypes.h:100
double m_fVoltMin
minimum operational voltage (V)
Definition: DynaTypes.h:98
double m_fAngleMin
min rotation angle in servo mode (deg)
Definition: DynaTypes.h:92
#define DYNA_MX28_POS_MIN_RAW
minimum raw angular position
Definition: MX.h:331
double m_fGearRedectionRatio
gear reduction ratio
Definition: DynaTypes.h:89
double m_fWeight
weight (grams)
Definition: DynaTypes.h:84
uint_t m_uSupportedModes
Dynamixel Operational Modes
Definition: DynaTypes.h:94
uint_t m_uRawPosModulo
raw position modulo
Definition: DynaTypes.h:103
virtual ~DynaServoMX28()
Destructor.
#define DYNA_MX28_SPEC_TEMP_MAX_C
maximum recommended operational temperature (C)
Definition: MX.h:298
#define DYNA_MX28_POS_MODULO
servo position modulo [0-max]
Definition: MX.h:333
Servo Control Table Entry.
Definition: DynaTypes.h:369
double m_fResolution
resolution (degrees)
Definition: DynaTypes.h:88
#define DYNA_TORQUE_MIN_RAW
minimum raw torque
Definition: Dynamixel.h:281
#define DYNA_MX28_SPEC_DEPTH_MM
depth (mm)
Definition: MX.h:272
uint_t m_uRawTorqueMin
minimum raw torque value
Definition: DynaTypes.h:106
#define DYNA_MX28_SPEC_VOLT_MIN_V
minimum operational voltage (V)
Definition: MX.h:301
The libDynamixel internal declarations.
char * m_sModelName
model name
Definition: DynaTypes.h:83
virtual void Dump()
Dump contents of the servo EEPROM and RAM control tables.
static DynaCtlTblEntry_T MX28RAMCtlTblInfo[]
MX-28 Servo RAM Control Table Information.
Generic Dynamixel Servo Base Class.
uint_t m_uRawTempMin
minimum raw temperature value
Definition: DynaTypes.h:108
double m_fTempMin
minimum operational temperature (C)
Definition: DynaTypes.h:96
void InitCfg()
Initialize servo configuration data.
uint_t m_uRawTorqueMax
maximum raw torque value
Definition: DynaTypes.h:107
void InitState()
Initialize servo state data.
#define DYNA_MX28_SPEC_POS_RES_DEG
resolution (degrees)
Definition: MX.h:274
#define DYNA_TEMP_MAX_RAW
maximum raw temperature
Definition: Dynamixel.h:296
#define DYNA_MX28_SPEC_HEIGHT_MM
height (mm)
Definition: MX.h:271
void Init(int nServoId, uint_t uModelNum, uint_t uFwVer)
Initialize servo class instance.
Definition: DynaServo.cxx:406
static DynaCtlTblEntry_T MX28EEPROMCtlTblInfo[]
MX-28 Servo EEPROM Control Table Information.
#define DYNA_MX28_SPEC_VOLT_MAX_V
maximum operational voltage (V)
Definition: MX.h:304
#define DYNA_MX28_SPEC_MODES
supported modes (see Dynamixel Operational Modes)
Definition: MX.h:289
RoadNarrows Dynamixel Archetype Servo Abstract Base Class.
virtual void CheckData()
Check data for consitencies.
#define DYNA_VOLT_MIN_RAW
minimum raw temperature
Definition: Dynamixel.h:308
#define DYNA_MX28_SPEC_ANGLE_MAX_DEG
maximum rotation angle in servo mode (deg)
Definition: MX.h:286
#define DYNA_MX28_SPEC_STALL_TORQUE_KGF
maximum stall torque (kgf) at optimal power
Definition: MX.h:277
double m_fTempMax
maximum operational temperature (C)
Definition: DynaTypes.h:97
virtual int SyncData()
Synchronize the shadowed configuration and state data to the servo control table. ...
RoadNarrows Dynamixel Top-Level Package Header File.
#define DYNA_MX28_POS_MAX_RAW
maximum raw angular position
Definition: MX.h:332
void InitSpec()
Initialize servo fixed specification data.
DynaServoMX28(DynaComm &comm)
Bare-bones initialization constructor.
Definition: DynaServoMX28.h:92
uint_t m_uRawPosMax
maximum raw position value (servo mode)
Definition: DynaTypes.h:102
#define DYNA_MX28_SPEC_TEMP_MIN_C
minimum recommended operational temperature (C)
Definition: MX.h:295
DynaServoSpec_T m_spec
servo specification
Definition: DynaServo.h:837
uint_t m_uRawTempMax
maximum raw temperature value
Definition: DynaTypes.h:109
double m_fStallTorque
max stall torque (kgf) at optimal power
Definition: DynaTypes.h:90
#define DYNA_SPEED_MAX_RAW
maximum raw value
Definition: Dynamixel.h:266
double m_fWidth
width (mm)
Definition: DynaTypes.h:85
double m_fAngleMax
max rotation angle in servo mode (deg)
Definition: DynaTypes.h:93
RoadNarrows MX-28 Dynamixel Servo Class Interface.
#define DYNA_MX28_SPEC_WEIGHT_G
weight (grams)
Definition: MX.h:269
bool m_bHas360Pos
does [not] have full 360 position info
Definition: DynaTypes.h:95
uint_t m_uRawVoltMax
maximum raw voltage value
Definition: DynaTypes.h:111
RoadNarrows Dynamixel Library Error and Logging Routines.
#define DYNA_MX28_SPEC_MAX_SPEED_RPM
maximum no-load speed (rpm) at optimal power
Definition: MX.h:280
Dynamixel Bus Communications Abstract Base Class.
Definition: DynaComm.h:80