Laelaps  2.3.5
RoadNarrows Robotics Small Outdoor Mobile Robot Project
RoboClaw.h
Go to the documentation of this file.
1 ////////////////////////////////////////////////////////////////////////////////
2 //
3 // Package: Laelasp
4 //
5 // Library: liblaelaps
6 //
7 // File: RoboClaw.h
8 //
9 /*! \file
10  *
11  * $LastChangedDate: 2016-02-19 11:48:14 -0700 (Fri, 19 Feb 2016) $
12  * $Rev: 4324 $
13  *
14  * \brief RoboClaw motor controller class interface.
15  *
16  * RoboClaw is from Ion Motion Control.
17  *
18  * \author Robin Knight (robin.knight@roadnarrows.com)
19  *
20  * \par Copyright
21  * \h_copy 2015-2017. RoadNarrows LLC.\n
22  * http://www.roadnarrows.com\n
23  * All Rights Reserved
24  */
25 /*
26  * @EulaBegin@
27  *
28  * Unless otherwise stated explicitly, all materials contained are copyrighted
29  * and may not be used without RoadNarrows LLC's written consent,
30  * except as provided in these terms and conditions or in the copyright
31  * notice (documents and software) or other proprietary notice provided with
32  * the relevant materials.
33  *
34  * IN NO EVENT SHALL THE AUTHOR, ROADNARROWS LLC, OR ANY
35  * MEMBERS/EMPLOYEES/CONTRACTORS OF ROADNARROWS OR DISTRIBUTORS OF THIS SOFTWARE
36  * BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR
37  * CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS
38  * DOCUMENTATION, EVEN IF THE AUTHORS OR ANY OF THE ABOVE PARTIES HAVE BEEN
39  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
40  *
41  * THE AUTHORS AND ROADNARROWS LLC SPECIFICALLY DISCLAIM ANY WARRANTIES,
42  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
43  * FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS ON AN
44  * "AS IS" BASIS, AND THE AUTHORS AND DISTRIBUTORS HAVE NO OBLIGATION TO
45  * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
46  *
47  * @EulaEnd@
48  */
49 ////////////////////////////////////////////////////////////////////////////////
50 
51 #ifndef _ROBO_CLAW_H
52 #define _ROBO_CLAW_H
53 
54 #include <sys/types.h>
55 
56 #ifndef SWIG
57 #include <string>
58 #endif // SWIG
59 
60 #include "rnr/rnrconfig.h"
61 #include "rnr/log.h"
62 
63 #ifndef SWIG
64 namespace motor
65 {
66  namespace roboclaw
67  {
68 #endif // SWIG
69  // -------------------------------------------------------------------------
70  // RoboClaw Data
71  // -------------------------------------------------------------------------
72 
73  // ........................................................................
74  // Serial Message Interface
75  // ........................................................................
76 
77  //
78  // Serial baud rates
79  //
80  static const int SerBaud2400 = 2400; ///< 2400 serial baudrate
81  static const int SerBaud9600 = 9600; ///< 9600 serial baudrate
82  static const int SerBaud19200 = 19200; ///< 19200 serial baudrate
83  static const int SerBaud38400 = 38400; ///< 38400 serial baudrate
84  static const int SerBaud115200 = 115200; ///< 115200 serial baudrate
85  static const int SerBaud230400 = 230400; ///< 230400 serial baudrate
86  static const int SerBaud460800 = 460800; ///< 460800 serial baudrate
87  static const int USBBaud1Mbps = 1000000; ///< 1Mbps USB typical baudrate
88 
89  //
90  // Message addresses.
91  //
92  static const byte_t AddrMin = 0x80; ///< minimum controller address
93  static const byte_t AddrMax = 0x87; ///< maximum controller address
94  static const byte_t AddrDft = 0x80; ///< default controller address
95 
96  //
97  // Message Checksum (obsolete)
98  //
99  static const byte_t CheckSumMask = 0x7f; ///< checksum mask
100  static const byte_t AckReqBit = 0x80; ///< request ack to write commands
101 
102  /*!
103  * \brief Command and response message formats.
104  */
105  enum MsgFmt
106  {
107  MsgWithNoCrc, ///< message does not include a 16-bit CRC
108  MsgWithCrc, ///< message includes a 16-bit CRC
109  MsgIgnoreCrc, ///< response includes a CRC, ignore (fw work-around bug)
110  MsgLenFixed, ///< message is fixed length
111  MsgLenVariable ///< message is variable length
112  };
113 
114  // write acknowledgment
115  static const byte_t RspAck = 0xff; ///< ack response to write commands
116 
117  /*!
118  * \brief Commands Ids
119  */
120  enum Cmd
121  {
122  // compatibility mode commands
123  CmdDriveForwardMot1 = 0, ///< drive motor 1 forward
124  CmdDriveBackwardMot1 = 1, ///< drive motor 1 backward
125  CmdSetMinMainVolt = 2, ///< set main battery minimum voltage
126  CmdSetMaxMainVolt = 3, ///< set main battery maximum voltage
127  CmdDriveForwardMot2 = 4, ///< drive motor 1 forward
128  CmdDriveBackwardMot2 = 5, ///< drive motor 2 backward
129  CmdDriveMot1 = 6, ///< drive motor 1 forward/back (7-bit)
130  CmdDriveMot2 = 7, ///< drive motor 2 foward/back (7-bit)
131 
132  // mix mode commands
133  CmdMixDriveForward = 8, ///< drive motors forward
134  CmdMixDriveBackward = 9, ///< drive motors backward
135  CmdMixTurnRight = 10, ///< drive motors to turn right
136  CmdMixTurnLeft = 11, ///< drive motors to turn left
137  CmdMixDrive = 12, ///< drive motors foward/back (7-bit)
138  CmdMixTurn = 13, ///< drive motors to turn R/L (7-bit)
139 
140  // advance commands
141  CmdReadEncoderMot1 = 16, ///< read motor 1 encoder
142  CmdReadEncoderMot2 = 17, ///< read motor 2 encoder
143  CmdReadSpeedMot1 = 18, ///< read motor 1 speed (qpps)
144  CmdReadSpeedMot2 = 19, ///< read motor 2 speed (qpps)
145  CmdResetEncoderCntrs = 20, ///< reset encoder (quadrature )counters
146  CmdReadFwVersion = 21, ///< read firmware version
147  CmdSetEncoderReg1 = 22, ///< set encoder register 1 (quadrature)
148  CmdSetEncoderReg2 = 23, ///< set encoder register 2 (quadrature)
149  CmdReadMainBattVolt = 24, ///< read main battery voltage
150  CmdReadLogicVolt = 25, ///< read logic battery voltage
151  CmdSetMinLogicVolt = 26, ///< set logic battery minimum voltage
152  CmdSetMaxLogicVolt = 27, ///< set logic battery maximum voltage
153  CmdSetVelPidMot1 = 28, ///< set motor 1 velocity PID constants
154  CmdSetVelPidMot2 = 29, ///< set motor 2 velocity PID constants
155  CmdRead125SpeedMot1 = 30, ///< read motor 1 speed (pulses/125th sec)
156  CmdRead125SpeedMot2 = 31, ///< read motor 2 speed (pulses/125th sec)
157  CmdDriveDutyMot1 = 32, ///< drive motor 1 at duty cycle (no quad.)
158  CmdDriveDutyMot2 = 33, ///< drive motor 2 at duty cycle (no quad.)
159  CmdDriveDuty = 34, ///< drive motors at duty cycle (no quad.)
160  CmdDriveQMot1 = 35, ///< drive motor 1 at quad. pulses/second
161  CmdDriveQMot2 = 36, ///< drive motor 2 at quad. pulses/second
162  CmdDriveQ = 37, ///< drive motors at quad. pulses/second
163  CmdDriveQAccelMot1 = 38, ///< drive motor 1 at quad. pps with accel.
164  CmdDriveQAccelMot2 = 39, ///< drive motor 2 at quad. pps with accel.
165  CmdDriveQAccel = 40, ///< drive motors at quad. pps with accel.
166  CmdBufDriveQDistMot1 = 41, ///< buffered drive motor 1 to dist at qpps
167  CmdBufDriveQDistMot2 = 42, ///< buffered drive motor 2 to dist at qpps
168  CmdBufDriveQDist = 43, ///< buffered drive motors to dist at qpps
170  ///< buffered drive motor 1 to dist at qpps with accel.
172  ///< buffered drive motor 2 to dist at qpps with accel.
174  ///< buffered drive motors to dist at qpps with accel.
175  CmdReadBufLen = 47, ///< read motors bufferd command length
176 
177  // more here...
178 
179  CmdReadMotorDraw = 49, ///< read motors amp draw
180  CmdDriveQAccel2 = 50, ///< drive motros at qpps with 2 accel vals
181  CmdBufDriveQAccel2Dist = 51,
182  /// buffered drive motors to dist at qpps w/ 2 accel
183 
184  // more here...
185 
186  CmdReadVelPidMot1 = 55, ///< read motor 1 velocity PID constants
187  CmdReadVelPidMot2 = 56, ///< read motor 2 velocity PID constants
188  CmdSetMainBattCutoffs = 57, ///< set main battery voltage cutoffs
189  CmdSetLogicCutoffs = 58, ///< set logic voltage cutoffs
190  CmdReadMainBattCutoffs = 59, ///< read main battery cutoff settings
191  CmdReadLogicCutoffs = 60, ///< read logic voltage cutoff settings
192  CmdSetPosPidMot1 = 61, ///< set motor 1 position PID constants
193  CmdSetPosPidMot2 = 62, ///< set motor 2 position PID constants
194  CmdReadPosPidMot1 = 63, ///< read motor 1 position PID constants
195  CmdReadPosPidMot2 = 64, ///< read motor 2 position PID constants
197  ///< drive motor 1 with signed qpps, accel, deccel and position
199  ///< drive motor 2 with signed qpps, accel, deccel and position
201  ///< drive motors with signed qpps, accel, deccel and position
202 
203  // more here...
204 
205  CmdReadTemp = 82, ///< read board temperature
206  CmdReadTemp2 = 83, ///< read board second temperature
207  CmdReadStatus = 90, ///< read current board status
208  CmdReadEncoderMode = 91, ///< read encoder mode for both motors
209  CmdSetEncoderModeMot1 = 92, ///< set motor 1 encoder mode
210  CmdSetEncoderModeMot2 = 93, ///< set motor 2 encoder mode
211  CmdWriteEEPROM = 94, ///< write settings to EEPROM
212 
213  // more here...
214 
215  // Note: RoboClaw User Manual v5 error. The Cmd*MaxCurrentMotn commands
216  // numbers are shifted down by 1.
217  CmdSetMaxCurrentMot1 = 133, ///< set motor 1 maximum current limit
218  CmdSetMaxCurrentMot2 = 134, ///< set motor 2 maximum current limit
219  CmdReadMaxCurrentMot1 = 135, ///< read motor 1 maximum current limit
220  CmdReadMaxCurrentMot2 = 136 ///< read motor 2 maximum current limit
221  };
222 
223  //
224  // Message motor speed parameters
225  //
226 
227  // 8-bit speed with direction determined by command id
228  static const byte_t ParamSpeedMin = 0; ///< minimum absolute speed
229  static const byte_t ParamSpeedMax = 127; ///< maximum absolute speed
230  static const byte_t ParamStop = 0; ///< stop
231 
232  // 7-bit speed
233  static const byte_t ParamSpeed7MaxBwd = 0; ///< minimum absolute speed
234  static const byte_t ParamStop7 = 64; ///< all stop
235  static const byte_t ParamSpeed7MaxFwd = 127; ///< maximum absolute speed
236 
237  //
238  // Message turn speed parameters
239  //
240 
241  // 8-bit turn rate with rotation direction determined by command id
242  static const byte_t ParamTurnMin = 0; ///< min absolute turn speed
243  static const byte_t ParamTurnMax = 127; ///< max absolute turn speed
244  static const byte_t ParamNoTurn = 0; ///< no turn
245 
246  // 7-bit turn rate
247  static const byte_t ParamTurn7MaxLeft = 0; ///< full turn left
248  static const byte_t ParamNoTurn7 = 64; ///< no turn
249  static const byte_t ParamTurn7MaxRight = 127; ///< full turn right
250 
251  //
252  // Duty cycle parameters
253  //
254  static const int ParamDutyCycleMin = -32767; ///< -100% duty cycle
255  static const int ParamDutyCycleStop = 0; ///< 0% duty cycle
256  static const int ParamDutyCycleMax = 32767; ///< 100% duty cycle
257 
258  //
259  // Version: <string><NL>0<CRC16>
260  //
261  static const size_t ParamVerLen = 48; ///< version string length.
262  static const size_t ParamVerLenMin = 4; ///< version minimum length.
263 
264  //
265  // Message voltage and current parameters
266  //
267 
268  // voltages
269  static const double ParamVoltScale = 0.1; ///< 10/th of a volt
270  static const double ParamVoltMainMin = 6.0; ///< min main battery voltage
271  static const double ParamVoltLogicMin = 5.5; ///< minimum logic voltage
272  static const double ParamVoltMax = 34.0; ///< maximum voltage
273 
274  // motor ampere draw
275  static const double ParamAmpScale = 0.01; ///< sensed_value * S = A
276  static const double ParamAmpMin = 0.0; ///< minimum amps
277  static const double ParamAmpMinSane = 0.5; ///< minimum amps for operation
278  static const double ParamAmpMax = 15.0; ///< maximum amps
279 
280  //
281  // These complicated parameter conversion values are for commands
282  // 26, 27. Don't use.
283  //
284  // main battery (powers motors) voltages
285  static const byte_t ParamVoltMinMainMin = 0; ///< 0 == 6 volts
286  static const byte_t ParamVoltMinMainMax = 120; ///< 120 == 30 volts
287  static const double ParamVoltMinMainOff = 6.0; ///< V @ 0 value
288  static const double ParamVotlMinMainDft = 6.0; ///< default on reset
289  static const byte_t ParamVoltMaxMainMin = 0; ///< 0 == 0 volts
290  static const byte_t ParamVoltMaxMainMax = 154; ///< 154 == 30 volts
291 
292  // logic battery (powers circuitry) voltages
293  static const byte_t ParamVoltMinLogicMin = 0; ///< 0 == 6 volts
294  static const byte_t ParamVoltMinLogicMax = 140; ///< 120 == 30 volts
295  static const double ParamVoltMinLogicOff = 6.0; ///< V @ 0 value
296  static const byte_t ParamVoltMaxLogicMin = 30; ///< 30 == 6 volts
297  static const byte_t ParamVoltMaxLogicMax = 175; ///< 175 == 34 volts
298 
299  // battery scaling factors
300  static const double ParamVoltMinS = 5.0; ///< (V - Off) * S = value
301  static const double ParamVoltMaxS = 5.12; ///< V * S = value
302  static const double ParamVoltSensedS = 0.1; ///< sensed_value * S = V
303 
304  //
305  // Temperature parameters
306  //
307  static const double ParamTempScale = 0.1; ///< sensed_value * S = C
308 
309  /*!
310  * \brief Board status bits.
311  */
313  {
314  ParamStatusNormal = 0x0000, ///< normal
315  ParamStatusWarnMot1OverCur = 0x0001, ///< motor 1 over current warning
316  ParamStatusWarnMot2OverCur = 0x0002, ///< motor 2 over current warning
317  ParamStatusEStopped = 0x0004, ///< emergency stopped
318  ParamStatusErrTemp = 0x0008, ///< temperature out-of-range error
319  ParamStatusErrTemp2 = 0x0010, ///< temperature2 out-of-range error
320  ParamStatusErrMainBattHigh = 0x0020, ///< main battery over voltage error
321  ParamStatusErrLogicBattHigh = 0x0040, ///< logic battery over volt error
322  ParamStatusErrLogicBattLow = 0x0080, ///< logic battery under volt error
323  ParamStatusErrMot1Fault = 0x0100, ///< motor 1 drive fault
324  ParamStatusErrMot2Fault = 0x0200, ///< motor 2 drive fault
325  ParamStatusWarnMainBattHigh = 0x0400, ///< main battery over volt warning
326  ParamStatusWarnMainBattLow = 0x0800, ///< main battery under volt warning
327  ParamStatusWarnTemp = 0x1000, ///< temp out-of-range warning
328  ParamStatusWarnTemp2 = 0x2000, ///< temp2 out-of-range warning
329  ParamStatusMot1Home = 0x4000, ///< motor 1 home
330  ParamStatusMot2Home = 0x8000 ///< motor 2 home
331  };
332 
333  //
334  // Encoder parameters
335  //
336  static const byte_t ParamEncModeRCAnalogBit = 0x80; ///< RC/analog bit
337  static const byte_t ParamEncModeRCAnalogDis = 0x00; ///< RC/analog disable
338  static const byte_t ParamEncModeRCAnalogEn = 0x80; ///< RC/analog enable
339  static const byte_t ParamEncModeQuadAbsBit = 0x01; ///< quad/absolute bit
340  static const byte_t ParamEncModeQuad = 0x00; ///< quadrature encoder
341  static const byte_t ParamEncModeAbs = 0x01; ///< absolute encoder
342 
343  static const long long ParamEncQuadMin = 0; ///< quadrature encoder min
344  static const long long ParamEncQuadMax = 4294967295LL;
345  ///< quadrature encoder max
346 
347  /*!
348  * \brief Encoder status on read.
349  */
351  {
352  ParamEncStatusUnderFlow = 0x01, ///< quadrature encoder underflow
353  ParamEncStatusDirBackward = 0x02, ///< direction (sign)
354  ParamEncStatusOverFlow = 0x04 ///< quadrature encoder overflow
355  };
356 
357  //
358  // Velocity PID parameters
359  //
360  static const long ParamVelPidQppsDft = 44000; ///< speed of encoder at max
361  static const long ParamVelPidPDft = 0x00010000; ///< vel proportional const
362  static const long ParamVelPidIDft = 0x00008000; ///< vel integrative const
363  static const long ParamVelPidDDft = 0x00004000; ///< vel derivative const
364  static const long ParamVelPidCvt = 0x00010000; ///< vel const conversion
365 
366  //
367  // Position PID parameters (TBD)
368  //
369  static const long ParamPosPidPDft = 0; ///< pos proportional const
370  static const long ParamPosPidIDft = 0; ///< pos integrative const
371  static const long ParamPosPidDDft = 0; ///< pos derivative const
372  static const long ParamPosPidMaxIDft = 0; ///< max I windup
373  static const long ParamPosPidDeadzoneDft = 0; ///< deadzone
374  static const long ParamPosPidMinPos = 0; ///< min position
375  static const long ParamPosPidMaxPos = 0; ///< max position
376 
377  //
378  // Command buffering
379  //
380  static const byte_t ParamCmdBufQueue = 0; ///< queue command
381  static const byte_t ParamCmdBufPreempt = 1; ///< preempt all buffered cmds
382  static const byte_t ParamCmdBufSize = 31; ///< cmd buffer size (num q'd)
383  static const byte_t ParamCmdBufExec = 0; ///< last command is executing
384  static const byte_t ParamCmdBufEmpty = 0x80; ///< buffer is empty
385 
386  //
387  // Message response timeout
388  //
389  static const uint_t CmdTimeout = 10000; ///< command timeout (usec)
390  static const uint_t RspTimeout = 12000; ///< response timeout (usec)
391 
392  //
393  // Maximum buffers sizes
394  //
395  static const int CmdMaxBufLen = 64; ///< maximum command length (bytes)
396  static const int RspMaxBufLen = 64; ///< maximum response length (bytes)
397  static const int CmdHdrLen = 2; ///< cmd header length [address,cmdid]
398 
399 
400  //
401  // Common parameter field starting byte positions
402  //
403  static const int FieldPosAddr = 0; ///< controller address position
404  static const int FieldPosCmd = 1; ///< command id position
405 
406 
407  // ........................................................................
408  // Abstracted Interface
409  // ........................................................................
410 
411  //
412  // Motor 1 and 2 indices
413  //
414  static const int Motor1 = 0; ///< motor 1
415  static const int Motor2 = 1; ///< motor 2
416  static const int NumMotors = 2; ///< number of motors/controller
417 
418  //
419  // Motor forward/backward rotation sense.
420  //
421  static const int MotorDirUnknown = 0; ///< unknown
422  static const int MotorDirNormal = 1; ///< normal
423  static const int MotorDirReverse = -1; ///< reverse (forward=backward, etc)
424 
425  //
426  // Motor speeds (scaled)
427  //
428  static const int MotorSpeedMaxBackward = -127; ///< full reverse
429  static const int MotorSpeedStop = 0; ///< stop
430  static const int MotorSpeedMaxForward = 127; ///< full forward
431 
432 
433 #ifndef SWIG
434  // -------------------------------------------------------------------------
435  // RoboClawChipSelect Class
436  // -------------------------------------------------------------------------
437 
438  /*!
439  * \brief RoboClaw motor controller chip select class.
440  *
441  * The RoboClawChipSelect class instance is used to select the motor
442  * controller, given its address.
443  */
445  {
446  public:
447  /*!
448  * \brief Default constructor.
449  */
451 
452  /*!
453  * \brief Destructor.
454  */
455  virtual ~RoboClawChipSelect();
456 
457  /*!
458  * \brief Motor controller select function.
459  *
460  * The motor controllers are on a multi-drop serial bus. Serial does not
461  * support multiple tx drivers on the same bus. Since there are two motor
462  * controllers, each with a transmit line (odroid receive), the select
463  * function disconnects one tx while connects the target tx.
464  *
465  * \param fd Open serial file descriptor.
466  * \param addrSel Target motor controller to be selected. Controllers
467  * are identified by their address.
468  */
469  virtual void select(int fd, byte_t addrSel);
470 
471  protected:
472  byte_t m_addrLast; ///< last selected motor controller, id'd by address
473  };
474 #endif // SWIG
475 
476 
477 #ifndef SWIG
478  // -------------------------------------------------------------------------
479  // RoboClawComm Class
480  // -------------------------------------------------------------------------
481 
482  /*!
483  * \brief RoboClaw communication class.
484  *
485  * The RoboClaw class instances bind to this class.
486  */
488  {
489  public:
490  /*!
491  * \brief Default constructor.
492  */
493  RoboClawComm();
494 
495  /*!
496  * \brief Initialization constructor.
497  *
498  * \param strDevName Serial device name.
499  * \param nBaudRate Serial device baud rate.
500  * \param pChipSelect (Derived) motor controller selection class object.
501  *
502  * \copydoc doc_return_mc_std
503  */
504  RoboClawComm(std::string &strDevName,
505  int nBaudRate,
506  RoboClawChipSelect *pChipSelect = NULL);
507 
508  /*!
509  * \brief Destructor.
510  */
511  virtual ~RoboClawComm();
512 
513  /*!
514  * \brief Open connection to motor controller(s).
515  *
516  * \param strDevName Serial device name.
517  * \param nBaudRate Serial device baud rate.
518  * \param pChipSelect (Derived) motor controller selection class object.
519  *
520  * \copydoc doc_return_mc_std
521  */
522  virtual int open(std::string &strDevName,
523  int nBaudRate,
524  RoboClawChipSelect *pChipSelect = NULL);
525 
526  /*!
527  * \brief Close connection to motor controller.
528  *
529  * \copydoc doc_return_mc_std
530  */
531  virtual int close();
532 
533  /*!
534  * \brief Flush UART input FIFO.
535  *
536  * \copydoc doc_return_mc_std
537  */
538  virtual int flushInput();
539 
540  /*!
541  * \brief Test if connection is open.
542  *
543  * \return Returns true or false.
544  */
545  virtual bool isOpen() const
546  {
547  return m_fd >= 0? true: false;
548  }
549 
550  /*!
551  * \brief Test if connection is open.
552  *
553  * \param bEnDis Enable/disable debugging.
554  */
555  virtual void enableDbg(bool bEnDis)
556  {
557  m_bDbgEnable = bEnDis;
558  }
559 
560  /*!
561  * \brief Get last sent command's calculated 16-bit CRC.
562  *
563  * \return Returns CRC.
564  */
565  uint_t getLastCmdCrc()
566  {
567  return m_uCrcCmd;
568  }
569 
570  /*!
571  * \brief Get last received response's appended 16-bit CRC.
572  *
573  * \return Returns CRC.
574  */
575  uint_t getLastRspCrc()
576  {
577  return m_uCrcRsp;
578  }
579 
580  /*!
581  * \brief Execute a command with no response.
582  *
583  * \note Deprecated.
584  *
585  * \param [in] cmd Packed command buffer.
586  * \param lenCmd Length of command (bytes).
587  *
588  * \copydoc doc_return_mc_std
589  */
590  virtual int execCmd(byte_t cmd[], size_t lenCmd);
591 
592  /*!
593  * \brief Execute a command with an acknowledgement response.
594  *
595  * \param [in] cmd Packed command buffer.
596  * \param lenCmd Length of command (bytes).
597  * \param fmtCmd Command format. Do [not] append command with a 16-bit
598  * CRC. If included, the command buffer must be of
599  * length \h_ge lenCmd+2.
600  *
601  * \copydoc doc_return_mc_std
602  */
603  virtual int execCmdWithAckRsp(byte_t cmd[], size_t lenCmd,
604  MsgFmt fmtCmd = MsgWithNoCrc);
605 
606  /*!
607  * \brief Execute a command with an data response.
608  *
609  * \param [in] cmd Packed command buffer.
610  * \param lenCmd Length of command (bytes).
611  * \param [out] rsp Response buffer.
612  * \param lenRsp Expected length of packed response (bytes).
613  * \param fmtCmd Command format. Do [not] append command with a 16-bit
614  * CRC. If included, the command buffer must be of
615  * length \h_ge lenCmd+2.
616  * \param fmtRsp Response format. Response has with a 16-bit
617  * CRC. If ignore, firmware bug.
618  *
619  * \copydoc doc_return_mc_std
620  */
621  virtual int execCmdWithDataRsp(byte_t cmd[], size_t lenCmd,
622  byte_t rsp[], size_t lenRsp,
623  MsgFmt fmtCmd = MsgWithNoCrc,
624  MsgFmt fmtRsp = MsgWithCrc);
625 
626  /*!
627  * \brief Send command over serial connection to motor controller.
628  *
629  * \param [in] cmd Packed command buffer.
630  * \param lenCmd Length of command (bytes).
631  * \param fmtCmd Command format. Do [not] append command with a 16-bit
632  * CRC. If included, the command buffer must be of
633  * length \h_ge lenCmd+2.
634  *
635  * \copydoc doc_return_mc_std
636  */
637  virtual int sendCmd(byte_t cmd[], size_t lenCmd,
638  MsgFmt fmtCmd = MsgWithNoCrc);
639 
640  /*!
641  * \brief Receive data response over serial connection from motor
642  * controller.
643  *
644  * \param [out] rsp Response buffer.
645  * \param lenRsp Expected length of packed response (bytes).
646  *
647  * \return Number of bytes received or -1 on error.
648  */
649  virtual int recvDataRsp(byte_t rsp[], size_t lenRsp);
650 
651  /*!
652  * \brief Receive acknowledgement response over serial connection from
653  * motor controller.
654  *
655  * \copydoc doc_return_mc_std
656  */
657  virtual int recvAck();
658 
659  /*!
660  * \brief Pack 16-bit unsigned value into buffer.
661  *
662  * Order is big-endian (MSB first).
663  *
664  * \param [in] val Value to pack.
665  * \param [out] buf Destination buffer.
666  *
667  * \return Number of bytes packed(2).
668  */
669  int pack16(uint_t val, byte_t buf[]);
670 
671  /*!
672  * \brief Unpack 16-bit unsigned value from buffer.
673  *
674  * Buffer is big-endian (MSB first).
675  *
676  * \param [in] buf Source buffer.
677  * \param [out] val Unpacked value.
678  *
679  * \return Number of bytes unpacked(2).
680  */
681  int unpack16(byte_t buf[], uint_t &val);
682 
683  /*!
684  * \brief Pack 16-bit signed value into buffer.
685  *
686  * Order is big-endian (MSB first).
687  *
688  * \param [in] val Value to pack.
689  * \param [out] buf Destination buffer.
690  *
691  * \return Number of bytes packed(2).
692  */
693  int pack16(int val, byte_t buf[])
694  {
695  return pack16((uint_t)val, buf);
696  }
697 
698  /*!
699  * \brief Unpack 16-bit signed value from buffer.
700  *
701  * Buffer is big-endian (MSB first).
702  *
703  * \param [in] buf Source buffer.
704  * \param [out] val Unpacked value.
705  *
706  * \return Number of bytes unpacked(2).
707  */
708  int unpack16(byte_t buf[], int &val);
709 
710  /*!
711  * \brief Pack 32-bit unsigned value into buffer.
712  *
713  * Order is big-endian (MSB first).
714  *
715  * \param [in] val Value to pack.
716  * \param [out] buf Destination buffer.
717  *
718  * \return Number of bytes packed(4).
719  */
720  int pack32(uint_t val, byte_t buf[]);
721 
722  /*!
723  * \brief Unpack 32-bit unsigned value from buffer.
724  *
725  * Buffer is big-endian (MSB first).
726  *
727  * \param [in] buf Source buffer.
728  * \param [out] val Unpacked value.
729  *
730  * \return Number of bytes unpacked(4).
731  */
732  int unpack32(byte_t buf[], uint_t &val);
733 
734  /*!
735  * \brief Pack 32-bit signed value into buffer.
736  *
737  * Order is big-endian (MSB first).
738  *
739  * \param [in] val Value to pack.
740  * \param [out] buf Destination buffer.
741  *
742  * \return Number of bytes packed(4).
743  */
744  int pack32(int val, byte_t buf[])
745  {
746  return pack32((uint_t)val, buf);
747  }
748 
749  /*!
750  * \brief Unpack 32-bit signed value from buffer.
751  *
752  * Buffer is big-endian (MSB first).
753  *
754  * \param [in] buf Source buffer.
755  * \param [out] val Unpacked value.
756  *
757  * \return Number of bytes unpacked(4).
758  */
759  int unpack32(byte_t buf[], int &val);
760 
761  /*!
762  * \brief Calculate 7-bit checksum over buffer.
763  *
764  * \note For FW versions \h_lt 4.0
765  *
766  * \param [in] buf Buffer holding command/response.
767  * \param lenBuf Length of data in buffer (bytes).
768  * \param bAck If true, or-in request ack bit to checksum
769  * (commands only).
770  *
771  * \return Checksum byte.
772  */
773  virtual byte_t checksum(byte_t buf[], size_t lenBuf, bool bAck=false);
774 
775  /*!
776  * \brief Calculate 16-bit CRC over buffer.
777  *
778  * \param crc CRC starting seed value.
779  * \param [in] buf Buffer.
780  * \param lenbuf Length of data in buffer (bytes).
781  *
782  * \return Returns calculated 16-bit CRC over buffer.
783  */
784  virtual uint_t crc16(uint_t crc, byte_t buf[], size_t lenBuf);
785 
786  protected:
787  std::string m_strDevName; ///< serial device name
788  int m_nBaudRate; ///< serial baud rate
789  int m_fd; ///< opened file descriptor
790  RoboClawChipSelect *m_pChipSelect; ///< motor ctlr select object
791  uint_t m_uCrcCmd; ///< last sent command's CRC
792  uint_t m_uCrcRsp; ///< last received response's CRC
793  bool m_bDbgEnable; ///< do [not] enable debugging
794  };
795 #endif // SWIG
796 
797 
798 #ifndef SWIG
799  // -------------------------------------------------------------------------
800  // RoboClaw Class
801  // -------------------------------------------------------------------------
802 
803  /*!
804  * \brief RoboClaw 2 motor controller class.
805  *
806  * RoboClaw by Ion Motion Control.
807  */
808  class RoboClaw
809  {
810  public:
811  /*!
812  * \brief Initialization constructor.
813  *
814  * \param comm Bound controller communication object.
815  * \param address Motor controller address.
816  * \param strNameId Motor controller name identifier.
817  */
818  RoboClaw(RoboClawComm &comm,
819  const byte_t address=AddrDft,
820  const std::string &strNameId="RoboClaw");
821 
822  /*!
823  * \brief Destructor.
824  */
825  virtual ~RoboClaw();
826 
827  /*!
828  * \brief Probe address of motor controller.
829  *
830  * A weakness of the RoboClaw controller firmware is that there is no
831  * way to fetch its assigned address. The probe function uses a read-only
832  * command to determine, by proxy, whether the address is the controller's
833  * address. A false outcome is assumed if no response is received.
834  *
835  * \param address Motor controller address to test.
836  *
837  * \return Returns true if the motor controller has this address, false
838  * otherwise.
839  */
840  virtual bool probe(byte_t address);
841 
842 
843  //. . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
844  // Attributes
845  //. . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
846 
847  /*!
848  * \brief Get RoboClaw's bound communication object.
849  *
850  * \return Returns object.
851  */
853  {
854  return m_comm;
855  }
856 
857  /*!
858  * \brief Test if connection is open.
859  *
860  * \return Returns true or false.
861  */
862  bool isOpen() const
863  {
864  return m_comm.isOpen();
865  }
866 
867  /*!
868  * \brief Get the controller address associated with this class instance.
869  *
870  * \return Returns address.
871  */
872  byte_t getAddress() const
873  {
874  return m_address;
875  }
876 
877  /*!
878  * \brief Set class instance address.
879  *
880  * \note The address may not match the controller's address. It is up to
881  * the higher-level code to determine that.
882  *
883  * \param address Motor controller address.
884  */
885  void setAddress(byte_t address)
886  {
887  m_address = address;
888  }
889 
890  /*!
891  * \brief Get class instance name identifier.
892  *
893  * \return Returns string id.
894  */
895  std::string getNameId() const
896  {
897  return m_strNameId;
898  }
899 
900  /*!
901  * \brief Set class instance name identifier.
902  *
903  * \param strNameId Motor controller name identifier.
904  */
905  void setNameId(const std::string &strNameId)
906  {
907  m_strNameId = strNameId;
908  }
909 
910  /*!
911  * \brief Get the direction of motor rotation.
912  *
913  * The motor direction is a software construct to apply a normal or
914  * reverse the sense of forward/backward rotation.
915  *
916  * \param motor Motor index Motor1(0) or Motor2(1).
917  *
918  * \return Returns motor direction MotorDirNormal(1) or
919  * MotorDirReverse(-1).
920  */
921  virtual byte_t getMotorDir(int motor) const
922  {
923  if( isValidMotor(motor) )
924  {
925  return m_nMotorDir[motor];
926  }
927  else
928  {
929  return MotorDirNormal;
930  }
931  }
932 
933  /*!
934  * \brief set the direction of motor rotation.
935  *
936  * The motor direction is a software construct to apply a normal or
937  * reverse the sense of forward/backward rotation.
938  *
939  * \param motor Motor index Motor1(0) or Motor2(1).
940  * \param motorDir Motor direction MotorDirNormal(1) or
941  * MotorDirReverse(-1).
942  */
943  virtual void setMotorDir(int motor, int motorDir)
944  {
945  if( isValidMotor(motor) )
946  {
947  m_nMotorDir[motor] = motorDir == MotorDirReverse? MotorDirReverse:
948  MotorDirNormal;
949  }
950  }
951 
952  /*!
953  * \brief Get the RoboClaw's main battery minimum and maximum voltage
954  * cutoff settable range.
955  *
956  * \param [out] minmin Minimum minimum voltage (V).
957  * \param [out] maxmax Maximum maximum voltage (V).
958  */
959  void getMainBattCutoffRange(double &minmin, double &maxmax) const;
960 
961  /*!
962  * \brief Get the RoboClaw's logic minimum and maximum voltage
963  * cutoff settable range.
964  *
965  * \param [out] minmin Minimum minimum voltage (V).
966  * \param [out] maxmax Maximum maximum voltage (V).
967  */
968  void getLogicCutoffRange(double &minmin, double &maxmax) const;
969 
970 
971  //. . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
972  // Commands
973  //. . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . .
974 
975  /*!
976  * \brief Read the RoboClaw's firmware version.
977  *
978  * Command Numbers: 21
979  *
980  * \param [out] strFwVer Read version string.
981  *
982  * \copydoc doc_return_mc_std
983  */
984  virtual int cmdReadFwVersion(std::string &strFwVer);
985 
986  /*!
987  * \brief Read the RoboClaw's main battery input voltage.
988  *
989  * Command Numbers: 24
990  *
991  * \param [out] volts Voltage (V).
992  *
993  * \copydoc doc_return_mc_std
994  */
995  virtual int cmdReadMainBattVoltage(double &volts);
996 
997  /*!
998  * \brief Read the RoboClaw's main battery minimum and maximum voltage
999  * cutoff settings.
1000  *
1001  * Command Numbers: 59
1002  *
1003  * \param [out] min Minimum voltage (V).
1004  * \param [out] max Maximum voltage (V).
1005  *
1006  * \copydoc doc_return_mc_std
1007  */
1008  virtual int cmdReadMainBattCutoffs(double &min, double &max);
1009 
1010  /*!
1011  * \brief Set the RoboClaw's main battery minimum and maximum voltage
1012  * cutoff settings.
1013  *
1014  * Note: The minimum value is always set to 0 (6.0V) on power-up.
1015  *
1016  * The new values are set in volatile memory only. To save to non-volatile
1017  * memory, issue a write settings to EEPROM command.
1018  *
1019  * Command Numbers: 57
1020  *
1021  * \param [in] min Minimum voltage (V).
1022  * \param [in] max Maximum voltage (V).
1023  *
1024  * \copydoc doc_return_mc_std
1025  */
1026  virtual int cmdSetMainBattCutoffs(const double min, const double max);
1027 
1028  /*!
1029  * \brief Read the RoboClaw's LB-/LB+ terminals input voltage powered by
1030  * and optional logic dedicated battery.
1031  *
1032  * Command Numbers: 25
1033  *
1034  * \param [out] volts Voltage (V).
1035  *
1036  * \copydoc doc_return_mc_std
1037  */
1038  virtual int cmdReadLogicVoltage(double &volts);
1039 
1040  /*!
1041  * \brief Read the RoboClaw's optional logic dedicated battery
1042  * minimum and maximum voltage cutoff settings. The battery is connected
1043  * to the LB-/LB+ terminals
1044  *
1045  * Command Numbers: 60
1046  *
1047  * \param [out] min Minimum voltage (V).
1048  * \param [out] max Maximum voltage (V).
1049  *
1050  * \copydoc doc_return_mc_std
1051  */
1052  virtual int cmdReadLogicCutoffs(double &min, double &max);
1053 
1054  /*!
1055  * \brief Set the RoboClaw's optional logic dedicated battery
1056  * minimum and maximum voltage cutoff settings. The battery is connected
1057  * to the LB-/LB+ terminals
1058  *
1059  * Note: The minimum value is always set to 0 (6.0V) on power-up.
1060  * RDK: The documention is conflicted here. 3.0V or 6.0V?
1061  *
1062  * The new values are set in volatile memory only. To save to non-volatile
1063  * memory, issue a write settings to EEPROM command.
1064  *
1065  * Command Numbers: 58
1066  *
1067  * \param [in] min Minimum voltage (V).
1068  * \param [in] max Maximum voltage (V).
1069  *
1070  * \copydoc doc_return_mc_std
1071  */
1072  virtual int cmdSetLogicCutoffs(const double min, const double max);
1073 
1074  /*!
1075  * \brief Read motor's velocity PID constants.
1076  *
1077  * Command Numbers: 55, 56
1078  *
1079  * \param motor Motor index Motor1(0) or Motor2(1).
1080  * \param [out] Kp Velocity PID proportional constant.
1081  * \param [out] Ki Velocity PID intergral constant.
1082  * \param [out] Kd Velocity PID derivative constant.
1083  * \param [out] qpps Maximum speed of motor.
1084  *
1085  * \copydoc doc_return_mc_std
1086  */
1087  virtual int cmdReadVelocityPidConst(int motor,
1088  u32_t &Kp,
1089  u32_t &Ki,
1090  u32_t &Kd,
1091  u32_t &qpps);
1092 
1093  /*!
1094  * \brief Set motor's velocity PID constants.
1095  *
1096  * The new values are set in volatile memory only. To save to non-volatile
1097  * memory, issue a write settings to EEPROM command.
1098  *
1099  * Command Numbers: 28, 29
1100  *
1101  * \param motor Motor index Motor1(0) or Motor2(1).
1102  * \param [in] Kp Velocity PID proportional constant.
1103  * \param [in] Ki Velocity PID intergral constant.
1104  * \param [in] Kd Velocity PID derivative constant.
1105  * \param [in] qpps Maximum speed of motor.
1106  *
1107  * \copydoc doc_return_mc_std
1108  */
1109  virtual int cmdSetVelocityPidConst(int motor,
1110  const u32_t Kp,
1111  const u32_t Ki,
1112  const u32_t Kd,
1113  const u32_t qpps);
1114 
1115  /*!
1116  * \brief Read the motors ampere draw.
1117  *
1118  * Command Numbers: 49
1119  *
1120  * \param [out] amps1 Motor1 current draw (amperes)
1121  * \param [out] amps2 Motor2 current draw (amperes)
1122  *
1123  * \copydoc doc_return_mc_std
1124  */
1125  virtual int cmdReadMotorCurrentDraw(double &amps1, double &amps2);
1126 
1127  /*!
1128  * \brief Read a motor's maximum current limit.
1129  *
1130  * Command Numbers: 136, 137
1131  *
1132  * \param motor Motor index Motor1(0) or Motor2(1).
1133  * \param [out] maxAmps Motor maximum current limit (amperes)
1134  *
1135  * \copydoc doc_return_mc_std
1136  */
1137  virtual int cmdReadMotorMaxCurrentLimit(int motor, double &maxAmps);
1138 
1139  /*!
1140  * \brief Set a motor's maximum current limit.
1141  *
1142  * Command Numbers: 134, 135
1143  *
1144  * \param motor Motor index Motor1(0) or Motor2(1).
1145  * \param maxAmps Motor maximum current limit (amperes)
1146  *
1147  * \copydoc doc_return_mc_std
1148  */
1149  virtual int cmdSetMotorMaxCurrentLimit(int motor, const double maxAmps);
1150 
1151  /*!
1152  * \brief Read RoboClaw board's temperature.
1153  *
1154  * Command Numbers: 82
1155  *
1156  * \param [out] temp Board temperature (C)
1157  *
1158  * \copydoc doc_return_mc_std
1159  */
1160  virtual int cmdReadBoardTemperature(double &temp);
1161 
1162  /*!
1163  * \brief Read RoboClaw board's status bits.
1164  *
1165  * Command Numbers: 90
1166  *
1167  * \param [out] status Board status bits.
1168  *
1169  * \copydoc doc_return_mc_std
1170  */
1171  virtual int cmdReadStatus(uint_t &status);
1172 
1173  /*!
1174  * \brief Read RoboClaw board's temperature.
1175  *
1176  * Command Numbers: 47
1177  *
1178  * \param [out] len1 Motor1 command buffer length.
1179  * \param [out] len2 Motor2 command buffer length.
1180  *
1181  * \copydoc doc_return_mc_std
1182  */
1183  virtual int cmdReadCmdBufLengths(uint_t &len1, uint_t &len2);
1184 
1185  /*!
1186  * \brief Read encoder mode.
1187  *
1188  * Command Numbers: 91
1189  *
1190  * \param [out] mode1 Motor1 encoder mode.
1191  * \param [out] mode2 Motor2 encoder mode.
1192  *
1193  * \copydoc doc_return_mc_std
1194  */
1195  virtual int cmdReadEncoderMode(byte_t &mode1, byte_t &mode2);
1196 
1197  /*!
1198  * \brief Set a motor's encoder mode.
1199  *
1200  * The new values are set in volatile memory only. To save to non-volatile
1201  * memory, issue a write settings to EEPROM command.
1202  *
1203  * Command Numbers: 92, 93
1204  *
1205  * \param motor Motor index Motor1(0) or Motor2(1).
1206  * \param mode Motor encoder mode.
1207  *
1208  * \copydoc doc_return_mc_std
1209  */
1210  virtual int cmdSetEncoderMode(int motor, byte_t mode);
1211 
1212  /*!
1213  * \brief Set both motors' encoder mode.
1214  *
1215  * The new values are set in volatile memory only. To save to non-volatile
1216  * memory, issue a write settings to EEPROM command.
1217  *
1218  * Command Numbers: 92, 93
1219  *
1220  * \param mode1 Motor1 encoder mode.
1221  * \param mode2 Motor2 encoder mode.
1222  *
1223  * \copydoc doc_return_mc_std
1224  */
1225  virtual int cmdSetEncoderMode2(byte_t mode1, byte_t mode2);
1226 
1227  /*!
1228  * \brief Reset both motors' encoders.
1229  *
1230  * Command Numbers: 20
1231  *
1232  * \copydoc doc_return_mc_std
1233  */
1234  virtual int cmdResetQEncoders();
1235 
1236  /*!
1237  * \brief Read motor's encoder.
1238  *
1239  * Command Numbers: 16, 17
1240  *
1241  * \param motor Motor index Motor1(0) or Motor2(1).
1242  * \param [out] encoder Unsigned encoder value (quad pulses).
1243  * \param [out] status Status bits indicating sign, and over/under flow.
1244  *
1245  * \copydoc doc_return_mc_std
1246  */
1247  virtual int cmdReadQEncoder(int motor, s64_t &encoder);
1248 
1249  /*!
1250  * \brief Drive both motors at the given duty cycle.
1251  *
1252  * Motor quadrature encoders are ignored.
1253  *
1254  * Command Numbers: 34
1255  *
1256  * \param duty1 Motor1 normalized duty cycle [-1.0, 1.0].
1257  * Sign indicates direction.
1258  * \param duty2 Motor2 normalized duty cycle [-1.0, 1.0].
1259  * Sign indicates direction.
1260  *
1261  * \copydoc doc_return_mc_std
1262  */
1263  virtual int cmdDutyDrive2(double duty1, double duty2);
1264 
1265  /*!
1266  * \brief Read motor's speed.
1267  *
1268  * Command Numbers: 18, 19
1269  *
1270  * \param motor Motor index Motor1(0) or Motor2(1).
1271  * \param [out] speed Signed speed value (qpps).
1272  *
1273  * \copydoc doc_return_mc_std
1274  */
1275  virtual int cmdReadQSpeed(int motor, s32_t &speed);
1276 
1277  /*!
1278  * \brief Drive a motor at the given speed.
1279  *
1280  * Movement is controlled using quadrature encoders.
1281  *
1282  * Command Numbers: 35, 36
1283  *
1284  * \param motor Motor index Motor1(0) or Motor2(1).
1285  * \param speed Motor speed in quad pulses per second.
1286  * Sign indicates direction.
1287  *
1288  * \copydoc doc_return_mc_std
1289  */
1290  virtual int cmdQDrive(int motor, s32_t speed);
1291 
1292  /*!
1293  * \brief Drive both motors at the given speeds.
1294  *
1295  * Movement is controlled using quadrature encoders.
1296  *
1297  * Command Numbers: 37
1298  *
1299  * \param speed1 Motor1 speed in quad pulses per second.
1300  * Sign indicates direction.
1301  * \param speed2 Motor2 speed in quad pulses per second.
1302  * Sign indicates direction.
1303  *
1304  * \copydoc doc_return_mc_std
1305  */
1306  virtual int cmdQDrive2(s32_t speed1, s32_t speed2);
1307 
1308  /*!
1309  * \brief Drive a motor at the given speed and with the given
1310  * acceleration.
1311  *
1312  * Movement is controlled using quadrature encoders.
1313  *
1314  * Command Numbers: 38, 39
1315  *
1316  * \param motor Motor index Motor1(0) or Motor2(1).
1317  * \param speed Motor speed in quad pulses per second.
1318  * Sign indicates direction.
1319  * \param accel Acceleration (qpps/s).
1320  *
1321  * \copydoc doc_return_mc_std
1322  */
1323  virtual int cmdQDriveWithAccel(int motor, s32_t speed, u32_t accel);
1324 
1325  /*!
1326  * \brief Drive both motors at the given speeds and with the given
1327  * accelerations.
1328  *
1329  * Movement is controlled using quadrature encoders.
1330  *
1331  * Command Numbers: 50
1332  *
1333  * \param speed1 Motor1 speed in quad pulses per second.
1334  * Sign indicates direction.
1335  * \param accel1 Motor1 acceleration (qpps/s).
1336  * \param speed2 Motor2 speed in quad pulses per second.
1337  * Sign indicates direction.
1338  * \param accel2 Motor2 acceleration (qpps/s).
1339  *
1340  * \copydoc doc_return_mc_std
1341  */
1342  virtual int cmdQDriveWithAccel(s32_t speed1, u32_t accel1,
1343  s32_t speed2, u32_t accel2);
1344 
1345  /*!
1346  * \brief Drive a motor at the given speed for a given distance.
1347  *
1348  * Movement is controlled using quadrature encoders.
1349  *
1350  * This is a buffered command. Commands execute immediatly if no commands
1351  * are already in the motor drive queue or if the queue paramter is false.
1352  * Otherwise, the command is placed at end of the command buffer execution
1353  * queue.
1354  *
1355  * Command Numbers: 41, 42
1356  *
1357  * \param motor Motor index Motor1(0) or Motor2(1).
1358  * \param speed Motor speed in quad pulses per second.
1359  * Sign indicates direction.
1360  * \param dist Distance from current position (quad pulses).
1361  * \param bQueue Do [not] queue the command. If false, the motor drive
1362  * queue is flushed and any existing command is preempted
1363  * by this command.
1364  *
1365  * \copydoc doc_return_mc_std
1366  */
1367  virtual int cmdQDriveForDist(int motor, s32_t speed, u32_t dist,
1368  bool bQueue=true);
1369 
1370  /*!
1371  * \brief Drive both motors at the given speeds for a given distances.
1372  *
1373  * Movement is controlled using quadrature encoders.
1374  *
1375  * This is a buffered command. Commands execute immediatly if no commands
1376  * are already in the motor drive queue or if the queue paramter is false.
1377  * Otherwise, the command is placed at end of the command buffer execution
1378  * queue.
1379  *
1380  * Command Numbers: 43
1381  *
1382  * \param speed1 Motor1 speed in quad pulses per second.
1383  * Sign indicates direction.
1384  * \param dist1 Motor1 distance from current position (quad pulses).
1385  * \param speed2 Motor2 speed in quad pulses per second.
1386  * Sign indicates direction.
1387  * \param dist2 Motor2 distance from current position (quad pulses).
1388  * \param bQueue Do [not] queue the command. If false, the motor drive
1389  * queue is flushed and any existing command is preempted
1390  * by this command.
1391  *
1392  * \copydoc doc_return_mc_std
1393  */
1394  virtual int cmdQDriveForDist(s32_t speed1, u32_t dist1,
1395  s32_t speed2, u32_t dist2,
1396  bool bQueue=true);
1397 
1398  /*!
1399  * \brief Drive a motor at the given speed with the given acceleration
1400  * for the given distance.
1401  *
1402  * Movement is controlled using quadrature encoders.
1403  *
1404  * This is a buffered command. Commands execute immediatly if no commands
1405  * are already in the motor drive queue or if the queue paramter is false.
1406  * Otherwise, the command is placed at end of the command buffer execution
1407  * queue.
1408  *
1409  * Command Numbers: 44, 45
1410  *
1411  * \param motor Motor index Motor1(0) or Motor2(1).
1412  * \param speed Speed in quad pulses per second.
1413  * Sign indicates direction.
1414  * \param accel Acceleration (qpps/s).
1415  * \param dist Distance from current position (quad pulses).
1416  * \param bQueue Do [not] queue the command. If false, the motor drive
1417  * queue is flushed and any existing command is preempted
1418  * by this command.
1419  *
1420  * \copydoc doc_return_mc_std
1421  */
1422  virtual int cmdQDriveWithAccelForDist(int motor,
1423  s32_t speed,
1424  u32_t accel,
1425  u32_t dist,
1426  bool bQueue=true);
1427 
1428  /*!
1429  * \brief Drive both motors at the given speeds with the given
1430  * accelerations for the given distances.
1431  *
1432  * Movement is controlled using quadrature encoders.
1433  *
1434  * This is a buffered command. Commands execute immediatly if no commands
1435  * are already in the motor drive queue or if the queue paramter is false.
1436  * Otherwise, the command is placed at end of the command buffer execution
1437  * queue.
1438  *
1439  * Command Numbers: 51
1440  *
1441  * \param speed1 Motor1 peed in quad pulses per second.
1442  * Sign indicates direction.
1443  * \param accel1 Motor1 acceleration (qpps/s).
1444  * \param dist1 Motor1 distance from current position (quad pulses).
1445  * \param speed2 Motor2 peed in quad pulses per second.
1446  * Sign indicates direction.
1447  * \param accel2 Motor2 acceleration (qpps/s).
1448  * \param dist2 Motor2 distance from current position (quad pulses).
1449  * \param bQueue Do [not] queue the command. If false, the motor drive
1450  * queue is flushed and any existing command is preempted
1451  * by this command.
1452  *
1453  * \copydoc doc_return_mc_std
1454  */
1455  virtual int cmdQDriveWithAccelForDist(s32_t speed1,
1456  u32_t accel1,
1457  u32_t dist1,
1458  s32_t speed2,
1459  u32_t accel2,
1460  u32_t dist2,
1461  bool bQueue=true);
1462 
1463  /*!
1464  * \brief Drive a motor at the given speed with the given acceleration/
1465  * decceleration profile to the given absolute position.
1466  *
1467  * Movement is controlled using quadrature encoders.
1468  *
1469  * This is a buffered command. Commands execute immediatly if no commands
1470  * are already in the motor drive queue or if the queue paramter is false.
1471  * Otherwise, the command is placed at end of the command buffer execution
1472  * queue.
1473  *
1474  * Command Numbers: 65, 66
1475  *
1476  * \param motor Motor index Motor1(0) or Motor2(1).
1477  * \param speed Speed in quad pulses per second.
1478  * Sign indicates direction.
1479  * \param accel Acceleration (qpps/s).
1480  * \param deccel Decceleration (qpps/s).
1481  * \param pos Goal absolute position (quad pulses).
1482  * \param bQueue Do [not] queue the command. If false, the motor drive
1483  * queue is flushed and any existing command is preempted
1484  * by this command.
1485  *
1486  * \copydoc doc_return_mc_std
1487  */
1488  virtual int cmdQDriveWithProfileToPos(int motor,
1489  s32_t speed,
1490  u32_t accel,
1491  u32_t deccel,
1492  s32_t pos,
1493  bool bQueue=true);
1494 
1495  /*!
1496  * \brief Drive both motors at the given speeds with the given
1497  * acceleration/decceleration profile to the given absolute position.
1498  *
1499  * Movement is controlled using quadrature encoders.
1500  *
1501  * This is a buffered command. Commands execute immediatly if no commands
1502  * are already in the motor drive queue or if the queue paramter is false.
1503  * Otherwise, the command is placed at end of the command buffer execution
1504  * queue.
1505  *
1506  * Command Numbers: 67
1507  *
1508  * \param speed1 Motor1 speed in quad pulses per second.
1509  * Sign indicates direction.
1510  * \param accel1 Motor1 acceleration (qpps/s).
1511  * \param deccel1 Motor1 decceleration (qpps/s).
1512  * \param pos1 Motor1 goal absolute position (quad pulses).
1513  * \param speed2 Motor2 speed in quad pulses per second.
1514  * Sign indicates direction.
1515  * \param accel2 Motor2 acceleration (qpps/s).
1516  * \param deccel2 Motor2 decceleration (qpps/s).
1517  * \param pos2 Motor2 goal absolute position (quad pulses).
1518  * \param bQueue Do [not] queue the command. If false, the motor drive
1519  * queue is flushed and any existing command is preempted
1520  * by this command.
1521  *
1522  * \copydoc doc_return_mc_std
1523  */
1524  virtual int cmdQDriveWithProfileToPos(s32_t speed1,
1525  u32_t accel1,
1526  u32_t deccel1,
1527  s32_t pos1,
1528  s32_t speed2,
1529  u32_t accel2,
1530  u32_t deccel2,
1531  s32_t pos2,
1532  bool bQueue=true);
1533 
1534  /*!
1535  * \brief Stop both motors.
1536  *
1537  * Movement is controlled using quadrature encoders, with 0 being stop.
1538  *
1539  * Command Numbers: 37
1540  *
1541  * \copydoc doc_return_mc_std
1542  */
1543  virtual int cmdQStop()
1544  {
1545  return cmdQDrive2(0, 0);
1546  }
1547 
1548  /*!
1549  * \brief Drive a motor at the given speed.
1550  *
1551  * Speeds are scaled from [-max, max] with 0 being stop.
1552  *
1553  * Command Numbers: 0, 1, 4, 5
1554  *
1555  * \param motor Motor index Motor1(0) or Motor2(1).
1556  * \param speed Scaled speed
1557  * [MotorSpeedMaxBackward(-127),MotorSpeedMaxForward(127)].
1558  * Sign indicates direction.
1559  *
1560  * \copydoc doc_return_mc_std
1561  */
1562  virtual int cmdSDrive(int motor, int speed);
1563 
1564  /*!
1565  * \brief Drive both motors at the given speeds.
1566  *
1567  * Compatibility command. Speeds are scaled from [-max, max] with
1568  * < 0, 0, > 0 being backwards, stop, and forwards, respectively.
1569  *
1570  * Command Numbers: 0, 1, 4, 5
1571  *
1572  * \param speed1 Motor1 scaled speed
1573  * [MotorSpeedMaxBackward(-127),MotorSpeedMaxForward(127)].
1574  * Sign indicates direction.
1575  * \param speed2 Motor2 scaled speed
1576  * [MotorSpeedMaxBackward(-127),MotorSpeedMaxForward(127)].
1577  * Sign indicates direction.
1578  *
1579  * \copydoc doc_return_mc_std
1580  */
1581  virtual int cmdSDrive2(int speed1, int speed2);
1582 
1583  /*!
1584  * \brief Stop a motor.
1585  *
1586  * Compatibility command.
1587  *
1588  * Command Numbers: 35, 36
1589  *
1590  * \param motor Motor index Motor1(0) or Motor2(1).
1591  *
1592  * \copydoc doc_return_mc_std
1593  */
1594  virtual int cmdStop(int motor);
1595 
1596  /*!
1597  * \brief Stop a motor with the given maximum decelerations.
1598  *
1599  * Stopping is controlled using velocity PID and quadrature encoders.
1600  *
1601  * Compatibility command.
1602  *
1603  * Command Numbers: 38, 39
1604  *
1605  * \param motor Motor index Motor1(0) or Motor2(1).
1606  * \param decel Deceleration (qpps/s).
1607  *
1608  * \copydoc doc_return_mc_std
1609  */
1610  virtual int cmdStopWithDecel(int motor, u32_t decel);
1611 
1612  /*!
1613  * \brief Stop all motors.
1614  *
1615  * Compatibility command.
1616  *
1617  * Command Numbers: 37
1618  *
1619  * \copydoc doc_return_mc_std
1620  */
1621  virtual int cmdStop();
1622 
1623  /*!
1624  * \brief Stop both motors with the given maximum decelerations.
1625  *
1626  * Stopping is controlled using velocity PID and quadrature encoders.
1627  *
1628  * Compatibility command.
1629  *
1630  * Command Numbers: 50
1631  *
1632  * \param decel Deceleration (qpps/s).
1633  *
1634  * \copydoc doc_return_mc_std
1635  */
1636  virtual int cmdStopWithDecel(u32_t decel);
1637 
1638  /*!
1639  * \brief Emergency stop all motors.
1640  *
1641  * Command Numbers: 37
1642  *
1643  * \copydoc doc_return_mc_std
1644  */
1645  virtual int cmdEStop();
1646 
1647  /*!
1648  * \brief Write all settings to EEPROM.
1649  *
1650  * Command Numbers: 94
1651  *
1652  * \copydoc doc_return_mc_std
1653  */
1654  virtual int cmdWriteSettingsToEEPROM();
1655 
1656  protected:
1657  RoboClawComm &m_comm; ///< bound communication object
1658  byte_t m_address; ///< assigned controller address
1659  std::string m_strNameId; ///< controller name identifier
1660  int m_nMotorDir[NumMotors]; ///< motor rotation direction sense
1661  s64_t m_nEncPrev[NumMotors]; ///< encoder prevous values
1662  s64_t m_nEncoder[NumMotors]; ///< 64-bit encoder shadow values
1663 
1664  /*!
1665  * \brief Test if motor index is a valid index.
1666  *
1667  * \param motor Motor index Motor1(0) or Motor2(1).
1668  *
1669  * \return Returns true or false.
1670  */
1671  virtual bool isValidMotor(int motor) const
1672  {
1673  return (motor >= Motor1) && (motor < NumMotors);
1674  }
1675 
1676  /*!
1677  * \brief Integer absolute value.
1678  *
1679  * \param a Integer value.
1680  *
1681  * \return |a|
1682  */
1683  static inline int abs(int a)
1684  {
1685  return a>=0? a: -a;
1686  }
1687 
1688  /*!
1689  * \brief Cap value within limits [min, max].
1690  *
1691  * \param a Value.
1692  * \param min Minimum.
1693  * \param max Maximum.
1694  *
1695  * \return a: min \h_le a \h_le max
1696  */
1697  static inline int cap(int a, int min, int max)
1698  {
1699  return a<min? min: a>max? max: a;
1700  }
1701 
1702  /*!
1703  * \brief Cap FPN value within limits [min, max].
1704  *
1705  * \param a Value.
1706  * \param min Minimum.
1707  * \param max Maximum.
1708  *
1709  * \return a: min \h_le a \h_le max
1710  */
1711  static inline double fcap(double a, double min, double max)
1712  {
1713  return a<min? min: a>max? max: a;
1714  }
1715 
1716  };
1717 #endif // SWIG
1718 
1719 #ifndef SWIG
1720  } // roboclaw namespace
1721 } // motor namespace
1722 #endif // SWIG
1723 
1724 #endif // _ROBO_CLAW_H
static const int MotorDirUnknown
unknown
Definition: RoboClaw.h:421
std::string m_strNameId
controller name identifier
Definition: RoboClaw.h:1659
static const int ParamDutyCycleStop
0% duty cycle
Definition: RoboClaw.h:255
logic battery under volt error
Definition: RoboClaw.h:322
drive motros at qpps with 2 accel vals
Definition: RoboClaw.h:180
static const byte_t ParamVoltMaxMainMin
0 == 0 volts
Definition: RoboClaw.h:289
buffered drive motor 1 to dist at qpps
Definition: RoboClaw.h:166
RoboClaw 2 motor controller class.
Definition: RoboClaw.h:808
static const long ParamVelPidDDft
vel derivative const
Definition: RoboClaw.h:363
uint_t m_uCrcRsp
last received response&#39;s CRC
Definition: RoboClaw.h:792
static const byte_t ParamTurn7MaxRight
full turn right
Definition: RoboClaw.h:249
static const double ParamAmpMin
minimum amps
Definition: RoboClaw.h:276
drive motor 2 backward
Definition: RoboClaw.h:128
message includes a 16-bit CRC
Definition: RoboClaw.h:108
static const byte_t ParamSpeed7MaxBwd
minimum absolute speed
Definition: RoboClaw.h:233
read motor 2 velocity PID constants
Definition: RoboClaw.h:187
buffered drive motor 2 to dist at qpps with accel.
Definition: RoboClaw.h:171
static const int MotorSpeedMaxForward
full forward
Definition: RoboClaw.h:430
static const double ParamVotlMinMainDft
default on reset
Definition: RoboClaw.h:288
Cmd
Commands Ids.
Definition: RoboClaw.h:120
ParamEncStatus
Encoder status on read.
Definition: RoboClaw.h:350
static const int FieldPosCmd
command id position
Definition: RoboClaw.h:404
static const int USBBaud1Mbps
1Mbps USB typical baudrate
Definition: RoboClaw.h:87
drive motor 1 forward
Definition: RoboClaw.h:127
int m_nBaudRate
serial baud rate
Definition: RoboClaw.h:788
read current board status
Definition: RoboClaw.h:207
virtual void enableDbg(bool bEnDis)
Test if connection is open.
Definition: RoboClaw.h:555
read motor 1 speed (qpps)
Definition: RoboClaw.h:143
virtual void setMotorDir(int motor, int motorDir)
set the direction of motor rotation.
Definition: RoboClaw.h:943
static const int CmdHdrLen
cmd header length [address,cmdid]
Definition: RoboClaw.h:397
drive motor 1 forward
Definition: RoboClaw.h:123
static const long ParamPosPidPDft
pos proportional const
Definition: RoboClaw.h:369
drive motor 1 at quad. pulses/second
Definition: RoboClaw.h:160
message does not include a 16-bit CRC
Definition: RoboClaw.h:107
static const uint_t RspTimeout
response timeout (usec)
Definition: RoboClaw.h:390
static const byte_t ParamVoltMinMainMin
0 == 6 volts
Definition: RoboClaw.h:285
read motor 2 position PID constants
Definition: RoboClaw.h:195
static const double ParamVoltMinS
(V - Off) * S = value
Definition: RoboClaw.h:300
reset encoder (quadrature )counters
Definition: RoboClaw.h:145
set motor 2 encoder mode
Definition: RoboClaw.h:210
static const long ParamPosPidMinPos
min position
Definition: RoboClaw.h:374
read board second temperature
Definition: RoboClaw.h:206
write settings to EEPROM
Definition: RoboClaw.h:211
drive motor 1 at duty cycle (no quad.)
Definition: RoboClaw.h:157
bool m_bDbgEnable
do [not] enable debugging
Definition: RoboClaw.h:793
read motor 1 position PID constants
Definition: RoboClaw.h:194
static const byte_t ParamEncModeRCAnalogEn
RC/analog enable.
Definition: RoboClaw.h:338
static const byte_t AddrMin
minimum controller address
Definition: RoboClaw.h:92
static const byte_t ParamSpeedMin
minimum absolute speed
Definition: RoboClaw.h:228
drive motors forward
Definition: RoboClaw.h:133
drive motor 1 at quad. pps with accel.
Definition: RoboClaw.h:163
set motor 1 position PID constants
Definition: RoboClaw.h:192
static const byte_t ParamEncModeRCAnalogBit
RC/analog bit.
Definition: RoboClaw.h:336
drive motors with signed qpps, accel, deccel and position
Definition: RoboClaw.h:200
virtual bool isValidMotor(int motor) const
Test if motor index is a valid index.
Definition: RoboClaw.h:1671
temp2 out-of-range warning
Definition: RoboClaw.h:328
static double fcap(double a, double min, double max)
Cap FPN value within limits [min, max].
Definition: RoboClaw.h:1711
drive motors at quad. pps with accel.
Definition: RoboClaw.h:165
static const double ParamAmpScale
sensed_value * S = A
Definition: RoboClaw.h:275
static const byte_t AddrMax
maximum controller address
Definition: RoboClaw.h:93
static const byte_t ParamVoltMinMainMax
120 == 30 volts
Definition: RoboClaw.h:286
static const int RspMaxBufLen
maximum response length (bytes)
Definition: RoboClaw.h:396
set main battery minimum voltage
Definition: RoboClaw.h:125
set logic battery maximum voltage
Definition: RoboClaw.h:152
set main battery voltage cutoffs
Definition: RoboClaw.h:188
set encoder register 2 (quadrature)
Definition: RoboClaw.h:148
RoboClawChipSelect()
Default constructor.
Definition: RoboClaw.cxx:186
static const long ParamPosPidIDft
pos integrative const
Definition: RoboClaw.h:370
static const long ParamPosPidMaxPos
max position
Definition: RoboClaw.h:375
buffered drive motor 2 to dist at qpps
Definition: RoboClaw.h:167
ParamStatus
Board status bits.
Definition: RoboClaw.h:312
static const byte_t ParamCmdBufQueue
queue command
Definition: RoboClaw.h:380
buffered drive motors to dist at qpps w/ 2 accel
Definition: RoboClaw.h:186
static const int MotorDirReverse
reverse (forward=backward, etc)
Definition: RoboClaw.h:423
static const int ParamDutyCycleMin
-100% duty cycle
Definition: RoboClaw.h:254
static const int MotorSpeedStop
stop
Definition: RoboClaw.h:429
set main battery maximum voltage
Definition: RoboClaw.h:126
static const byte_t ParamEncModeAbs
absolute encoder
Definition: RoboClaw.h:341
int m_fd
opened file descriptor
Definition: RoboClaw.h:789
drive motor 2 with signed qpps, accel, deccel and position
Definition: RoboClaw.h:198
static const byte_t ParamCmdBufExec
last command is executing
Definition: RoboClaw.h:383
static const long ParamPosPidDDft
pos derivative const
Definition: RoboClaw.h:371
static const double ParamVoltMinLogicOff
V @ 0 value.
Definition: RoboClaw.h:295
static const int SerBaud115200
115200 serial baudrate
Definition: RoboClaw.h:84
static const byte_t ParamVoltMinLogicMax
120 == 30 volts
Definition: RoboClaw.h:294
drive motors to turn left
Definition: RoboClaw.h:136
static const int SerBaud460800
460800 serial baudrate
Definition: RoboClaw.h:86
static const byte_t ParamEncModeRCAnalogDis
RC/analog disable.
Definition: RoboClaw.h:337
set motor 2 velocity PID constants
Definition: RoboClaw.h:154
drive motor 1 backward
Definition: RoboClaw.h:124
read motor 1 maximum current limit
Definition: RoboClaw.h:219
set motor 1 maximum current limit
Definition: RoboClaw.h:217
read motors amp draw
Definition: RoboClaw.h:179
static const byte_t ParamSpeed7MaxFwd
maximum absolute speed
Definition: RoboClaw.h:235
int pack16(int val, byte_t buf[])
Pack 16-bit signed value into buffer.
Definition: RoboClaw.h:693
virtual void select(int fd, byte_t addrSel)
Motor controller select function.
Definition: RoboClaw.cxx:196
static const int NumMotors
number of motors/controller
Definition: RoboClaw.h:416
std::string getNameId() const
Get class instance name identifier.
Definition: RoboClaw.h:895
static const double ParamVoltLogicMin
minimum logic voltage
Definition: RoboClaw.h:271
temperature out-of-range error
Definition: RoboClaw.h:318
RoboClaw motor controller chip select class.
Definition: RoboClaw.h:444
static const double ParamAmpMinSane
minimum amps for operation
Definition: RoboClaw.h:277
std::string m_strDevName
serial device name
Definition: RoboClaw.h:787
static const byte_t ParamTurn7MaxLeft
full turn left
Definition: RoboClaw.h:247
static const byte_t ParamVoltMaxLogicMin
30 == 6 volts
Definition: RoboClaw.h:296
RoboClawComm & m_comm
bound communication object
Definition: RoboClaw.h:1657
byte_t m_address
assigned controller address
Definition: RoboClaw.h:1658
RoboClawChipSelect * m_pChipSelect
motor ctlr select object
Definition: RoboClaw.h:790
virtual int cmdQStop()
Stop both motors.
Definition: RoboClaw.h:1543
static const long ParamPosPidMaxIDft
max I windup
Definition: RoboClaw.h:372
main battery over voltage error
Definition: RoboClaw.h:320
static const byte_t ParamVoltMaxMainMax
154 == 30 volts
Definition: RoboClaw.h:290
static const byte_t ParamStop7
all stop
Definition: RoboClaw.h:234
static const int MotorDirNormal
normal
Definition: RoboClaw.h:422
read motor 1 speed (pulses/125th sec)
Definition: RoboClaw.h:155
read motor 1 encoder
Definition: RoboClaw.h:141
set motor 1 velocity PID constants
Definition: RoboClaw.h:153
static const int FieldPosAddr
controller address position
Definition: RoboClaw.h:403
static const int SerBaud230400
230400 serial baudrate
Definition: RoboClaw.h:85
temp out-of-range warning
Definition: RoboClaw.h:327
static const double ParamVoltMainMin
min main battery voltage
Definition: RoboClaw.h:270
static const long ParamVelPidQppsDft
speed of encoder at max
Definition: RoboClaw.h:360
static const byte_t ParamCmdBufEmpty
buffer is empty
Definition: RoboClaw.h:384
static const uint_t CmdTimeout
command timeout (usec)
Definition: RoboClaw.h:389
static const double ParamVoltSensedS
sensed_value * S = V
Definition: RoboClaw.h:302
static int cap(int a, int min, int max)
Cap value within limits [min, max].
Definition: RoboClaw.h:1697
static const size_t ParamVerLenMin
version minimum length.
Definition: RoboClaw.h:262
drive motors to turn R/L (7-bit)
Definition: RoboClaw.h:138
read encoder mode for both motors
Definition: RoboClaw.h:208
read motor 2 speed (pulses/125th sec)
Definition: RoboClaw.h:156
static const byte_t ParamNoTurn7
no turn
Definition: RoboClaw.h:248
main battery over volt warning
Definition: RoboClaw.h:325
set motor 2 position PID constants
Definition: RoboClaw.h:193
virtual ~RoboClawChipSelect()
Destructor.
Definition: RoboClaw.cxx:191
static const long ParamPosPidDeadzoneDft
deadzone
Definition: RoboClaw.h:373
read firmware version
Definition: RoboClaw.h:146
byte_t m_addrLast
last selected motor controller, id&#39;d by address
Definition: RoboClaw.h:472
static const byte_t CheckSumMask
checksum mask
Definition: RoboClaw.h:99
static const long long ParamEncQuadMax
quadrature encoder max
Definition: RoboClaw.h:344
static const byte_t ParamSpeedMax
maximum absolute speed
Definition: RoboClaw.h:229
bool isOpen() const
Test if connection is open.
Definition: RoboClaw.h:862
buffered drive motors to dist at qpps with accel.
Definition: RoboClaw.h:173
message is fixed length
Definition: RoboClaw.h:110
drive motors at quad. pulses/second
Definition: RoboClaw.h:162
static const int ParamDutyCycleMax
100% duty cycle
Definition: RoboClaw.h:256
drive motors foward/back (7-bit)
Definition: RoboClaw.h:137
read motor 2 speed (qpps)
Definition: RoboClaw.h:144
static const long ParamVelPidPDft
vel proportional const
Definition: RoboClaw.h:361
read motors bufferd command length
Definition: RoboClaw.h:175
static const byte_t ParamStop
stop
Definition: RoboClaw.h:230
static const long ParamVelPidCvt
vel const conversion
Definition: RoboClaw.h:364
read main battery voltage
Definition: RoboClaw.h:149
message is variable length
Definition: RoboClaw.h:111
RoboClawComm & getComm()
Get RoboClaw&#39;s bound communication object.
Definition: RoboClaw.h:852
static int abs(int a)
Integer absolute value.
Definition: RoboClaw.h:1683
static const int SerBaud19200
19200 serial baudrate
Definition: RoboClaw.h:82
static const double ParamVoltMaxS
V * S = value.
Definition: RoboClaw.h:301
response includes a CRC, ignore (fw work-around bug)
Definition: RoboClaw.h:109
drive motor 1 with signed qpps, accel, deccel and position
Definition: RoboClaw.h:196
drive motors backward
Definition: RoboClaw.h:134
static const byte_t ParamTurnMin
min absolute turn speed
Definition: RoboClaw.h:242
static const long long ParamEncQuadMin
quadrature encoder min
Definition: RoboClaw.h:343
main battery under volt warning
Definition: RoboClaw.h:326
int pack32(int val, byte_t buf[])
Pack 32-bit signed value into buffer.
Definition: RoboClaw.h:744
read main battery cutoff settings
Definition: RoboClaw.h:190
static const int SerBaud9600
9600 serial baudrate
Definition: RoboClaw.h:81
set logic battery minimum voltage
Definition: RoboClaw.h:151
read logic voltage cutoff settings
Definition: RoboClaw.h:191
static const double ParamVoltMax
maximum voltage
Definition: RoboClaw.h:272
logic battery over volt error
Definition: RoboClaw.h:321
static const byte_t RspAck
ack response to write commands
Definition: RoboClaw.h:115
motor 1 over current warning
Definition: RoboClaw.h:315
set encoder register 1 (quadrature)
Definition: RoboClaw.h:147
static const byte_t ParamVoltMinLogicMin
0 == 6 volts
Definition: RoboClaw.h:293
byte_t getAddress() const
Get the controller address associated with this class instance.
Definition: RoboClaw.h:872
virtual byte_t getMotorDir(int motor) const
Get the direction of motor rotation.
Definition: RoboClaw.h:921
buffered drive motor 1 to dist at qpps with accel.
Definition: RoboClaw.h:169
uint_t getLastCmdCrc()
Get last sent command&#39;s calculated 16-bit CRC.
Definition: RoboClaw.h:565
Definition: RoboClaw.h:64
uint_t m_uCrcCmd
last sent command&#39;s CRC
Definition: RoboClaw.h:791
buffered drive motors to dist at qpps
Definition: RoboClaw.h:168
static const size_t ParamVerLen
version string length.
Definition: RoboClaw.h:261
static const int SerBaud38400
38400 serial baudrate
Definition: RoboClaw.h:83
static const byte_t ParamTurnMax
max absolute turn speed
Definition: RoboClaw.h:243
static const byte_t AddrDft
default controller address
Definition: RoboClaw.h:94
set motor 1 encoder mode
Definition: RoboClaw.h:209
drive motor 2 at quad. pps with accel.
Definition: RoboClaw.h:164
drive motor 1 forward/back (7-bit)
Definition: RoboClaw.h:129
static const byte_t ParamEncModeQuad
quadrature encoder
Definition: RoboClaw.h:340
static const byte_t ParamCmdBufSize
cmd buffer size (num q&#39;d)
Definition: RoboClaw.h:382
RoboClaw communication class.
Definition: RoboClaw.h:487
drive motor 2 at duty cycle (no quad.)
Definition: RoboClaw.h:158
read board temperature
Definition: RoboClaw.h:205
static const double ParamVoltScale
10/th of a volt
Definition: RoboClaw.h:269
drive motor 2 foward/back (7-bit)
Definition: RoboClaw.h:130
set logic voltage cutoffs
Definition: RoboClaw.h:189
static const byte_t ParamEncModeQuadAbsBit
quad/absolute bit
Definition: RoboClaw.h:339
static const byte_t ParamCmdBufPreempt
preempt all buffered cmds
Definition: RoboClaw.h:381
drive motor 2 at quad. pulses/second
Definition: RoboClaw.h:161
static const int SerBaud2400
2400 serial baudrate
Definition: RoboClaw.h:80
void setNameId(const std::string &strNameId)
Set class instance name identifier.
Definition: RoboClaw.h:905
MsgFmt
Command and response message formats.
Definition: RoboClaw.h:105
virtual bool isOpen() const
Test if connection is open.
Definition: RoboClaw.h:545
drive motors to turn right
Definition: RoboClaw.h:135
motor 2 over current warning
Definition: RoboClaw.h:316
temperature2 out-of-range error
Definition: RoboClaw.h:319
quadrature encoder underflow
Definition: RoboClaw.h:352
static const byte_t ParamNoTurn
no turn
Definition: RoboClaw.h:244
static const long ParamVelPidIDft
vel integrative const
Definition: RoboClaw.h:362
quadrature encoder overflow
Definition: RoboClaw.h:354
uint_t getLastRspCrc()
Get last received response&#39;s appended 16-bit CRC.
Definition: RoboClaw.h:575
read motor 2 encoder
Definition: RoboClaw.h:142
drive motors at duty cycle (no quad.)
Definition: RoboClaw.h:159
static const int CmdMaxBufLen
maximum command length (bytes)
Definition: RoboClaw.h:395
static const double ParamVoltMinMainOff
V @ 0 value.
Definition: RoboClaw.h:287
static const int Motor2
motor 2
Definition: RoboClaw.h:415
static const int Motor1
motor 1
Definition: RoboClaw.h:414
void setAddress(byte_t address)
Set class instance address.
Definition: RoboClaw.h:885
static const int MotorSpeedMaxBackward
full reverse
Definition: RoboClaw.h:428
static const double ParamTempScale
sensed_value * S = C
Definition: RoboClaw.h:307
read motor 2 maximum current limit
Definition: RoboClaw.h:220
static const byte_t ParamVoltMaxLogicMax
175 == 34 volts
Definition: RoboClaw.h:297
read logic battery voltage
Definition: RoboClaw.h:150
static const double ParamAmpMax
maximum amps
Definition: RoboClaw.h:278
set motor 2 maximum current limit
Definition: RoboClaw.h:218
static const byte_t AckReqBit
request ack to write commands
Definition: RoboClaw.h:100