CDxlCom.h
Go to the documentation of this file.
00001 // Dynamixel control code - header file
00002 // Copyright (c) 2008 Erik Schuitema, Eelko van Breda
00003 // Delft University of Technology
00004 // www.dbl.tudelft.nl
00005 
00006 #ifndef __DYNAMIXELCOM_H_INCLUDED__
00007 #define __DYNAMIXELCOM_H_INCLUDED__
00008 
00009 #include <stdio.h>
00010 #include <string.h>
00011 #include <unistd.h>
00012 #include <errno.h>
00013 #include <sys/time.h>
00014 
00015 #include <threemxl/platform/hardware/serial/LxSerial.h>
00016 #ifdef XENOMAI
00017 #include <threemxl/platform/hardware/serial/LxRtSerial.h>
00018 #include <native/timer.h>
00019 #endif //XENOMAI
00020 
00021 
00022 #include "CDxlPacket.hpp"
00023 #include <threemxl/platform/io/logging/Log2.h>
00024 
00025 #define SEND_RETRY_FACTOR 1             ///< the number of times we want to retry a send if it fails
00026 #define RECEIVE_RETRY_FACTOR 0  ///< the number of times we want to retry a receive if it fails
00027 
00028 #define MAX_NUM_DYNAMIXELS                              254     ///< In any case, no more than 254 dynamixels may reside on one bus (IDs 0-253)
00029 
00030 // error return codes Dynamixel Class: they are all < 0
00031 #define DXL_SUCCESS                                             0
00032 #define DXL_ERROR                                               -1
00033 #define DXL_PKT_RECV_ERROR                              -9001
00034 #define DXL_PKT_RECV_CHECKSUM_ERR               -9002
00035 #define DXL_PKT_RECV_LENGTH_ERR                 -9003
00036 #define DXL_PKT_RECV_ID_ERR                             -9004
00037 #define DXL_PKT_RECV_TIMEOUT                    (-ETIMEDOUT)
00038 #define DXL_ALREADY_INITIALIZED                 -9006
00039 #define DXL_NOT_INITIALIZED                             -9007
00040 #define DXL_NO_SERIAL_PORT                              -9008
00041 #define DXL_INVALID_PARAMETER                   -9009
00042 
00043 #define DXL_PKT_SEND_ERROR                              -9101
00044 #define DXL_PKT_SEND_LENGTH_ERR                 -9102
00045 
00046 #define DXL_CHECKSUM_ERROR                              0x10
00047 // standard Dynamixel status errorcode bits
00048 // these are now stored at  M3XL_DONE  = 0x87
00049 #define M3XL_NO_ERROR                                           0b00000000
00050 #define M3XL_INSTRUCTION_ERROR                          0b01000000
00051 #define M3XL_OVERLOAD_ERROR                                     0b00100000
00052 #define M3XL_CHECKSUM_ERROR                                     0b00010000
00053 #define M3XL_RANGE_ERROR                                        0b00001000
00054 #define M3XL_OVERHEATING_ERROR                          0b00000100
00055 #define M3XL_ANGLE_LIMIT_ERROR                          0b00000010
00056 #define M3XL_INPUT_VOLTAGE_ERROR                        0b00000001
00057 
00058 #define M3XL_STATUS_EEPROM_ERROR                        0x80
00059 #define M3XL_STATUS_NOT_INITIALIZED                     0x81
00060 #define M3XL_STATUS_EM_STOP_ERROR                       0x82
00061 #define M3XL_STATUS_INIT_TIME_OUT_ERROR         0x83
00062 #define M3XL_STATUS_MAX_POS_ERROR                       0x84
00063 #define M3XL_STATUS_MAX_TORQUE_ERROR            0x85
00064 #define M3XL_STATUS_MAX_CURRENT_ERROR           0x86
00065 #define M3XL_STATUS_MOTOR_STUCK_ERROR           0x87
00066 #define M3XL_STATUS_JOINT_STUCK_ERROR           0x88
00067 #define M3XL_STATUS_PROTOCOL_TIME_OUT_ERROR     0x89
00068 
00069 // dxlPkgRecvWait // TODO: Tune these parameters
00070 #define DXL_PKT_RECV_WAIT_TIME_USEC             100000 // 100ms
00071 #define DXL_PKT_RECV_WAIT_TIME_SEC              0
00072 
00073 // Instruction constants
00074 #define INST_PING                                       0x01
00075 #define INST_READ                                       0x02
00076 #define INST_WRITE                                      0x03
00077 #define INST_REG_WRITE                          0x04
00078 #define INST_ACTION                                     0x05
00079 #define INST_RESET                                      0x06
00080 #define INST_DIGITAL_RESET                      0x07
00081 #define INST_SYSTEM_READ                        0x0C
00082 #define INST_SYSTEM_WRITE                       0x0D
00083 #define INST_SYNC_WRITE                         0x83
00084 #define INST_SYNC_REG_WRITE                     0x84
00085 
00086 
00087 class CDxlPacketHandler;
00088 
00090 
00092 class CDxlCom
00093 {
00094         protected:
00095                 CLog2           mLog;
00096                 bool            mInitialized;
00097                 int                     mLastError;
00098 
00099                 LxSerial*       mSerialPort;
00100                 CDxlPacketHandler*      mPacketHandler;
00101                 
00103                 int                     sendPacket(CDxlPacket *packet, bool replyExpected=true);
00104 
00106                 int                     receivePacketWait(CDxlStatusPacket *packet, int seconds=DXL_PKT_RECV_WAIT_TIME_SEC, int microseconds=DXL_PKT_RECV_WAIT_TIME_USEC);
00107                 //int                   receivePacket(CDxlStatusPacket *packet); //not used at the moment
00108 
00109         public:
00110                 CDxlCom();
00111 
00112                 bool            isInitialized() {return mInitialized;}
00113 
00115 
00116                 int                     setPacketHandler(CDxlPacketHandler *packetHandler);
00117                 
00118                 int                     initPacketHandler();
00119 
00121                 static const char*      translateErrorCode(int errorCode);
00122 
00123                 int                     getLastError()                  {return mLastError;}
00124 };
00125 
00126 #endif // __DYNAMIXELCOM_H_INCLUDED__


threemxl
Author(s):
autogenerated on Fri Aug 28 2015 13:21:08