CDxlGroup.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 __DYNAMIXELGROUP_H_INCLUDED__
00007 #define __DYNAMIXELGROUP_H_INCLUDED__
00008 
00009 #include "CDxlGeneric.h"
00010 #include "CDxlPacket.hpp"
00011 #include "CDxlConfig.h"
00012 #include <threemxl/platform/io/logging/Log2.h>
00013 
00014 
00015 // Forward declarations
00016 class CDxlGeneric;
00017 class CDxlConfig;
00018 class CDxlGroupConfig;
00019 class CDxlSyncWritePacket;
00020 
00021 class CDxlGroup: public CDxlCom
00022 {
00023         protected:
00024                 std::string                             mName;                                                          // Unique name of the group. Generated in setSerialPort using the serial port name.
00025                 CDxlGeneric*                    mDynamixels[MAX_NUM_DYNAMIXELS];        // Array of dynamixel pointers
00026                 int                                             mNumDynamixels;
00027                 CDxlSyncWritePacket*    mSyncPacket; //< this is the goup packet that is used for group messages
00028                 int                                             initAll();
00029                 int                                             action();       // Sends the ACTION command with the broadcast ID.
00030                 CLog2                                   mLog;
00031                 bool          mSyncRead;
00032                 CDxlStatusPacket* mStatusPackets[MAX_NUM_DYNAMIXELS];
00033         public:
00034                                                 CDxlGroup();
00035                 virtual                 ~CDxlGroup();
00036                 CDxlGeneric*    getDynamixel(const int index);
00037                 int                             getNumDynamixels();
00038                 std::string&    getName();
00039                 int                             getStateAll();
00040                 int                             getPosAll();
00041                 int                     getStatusAll();
00042                 int                             getPosAndSpeedAll();
00043                 int                     getPosSpeedTorqueAll();
00044                 int                             getTempAll();   // Request temperature of all dynamixels in this group
00045                 int                             enableTorqueAll(int state);
00046                 int                             setEndlessTurnModeAll(bool enabled);
00047 
00048 
00063                 int                             sendSyncWritePacket();                  // Sends out a group packet that has been filled with data by the inividual servo's
00064                 int                             writeData(int ID, int startingAddress, int dataLength, BYTE* data); //< servo's can use this function to write data to a group packet in stead of directly to a serial port
00065                 void                    setSyncWriteType(const BYTE instruction=INST_SYNC_WRITE);
00066 
00067                 // Read a certain part from the control table of all dynamixels in the group. interpretControlData
00068                 // will be called on each dynamixel afterwards.
00069                 int       syncRead(int startingAddress, int dataLength);
00070 
00071                 // Automatic configuration
00072                 int                             setConfig(CDxlGroupConfig *config); //< Loads group configuration class and adds servo to group. Returns 0 on success.
00073 
00074                 // Manual configuration
00075                 void                    setName(const std::string& name);
00076                 void                    setSerialPort(LxSerial* serialport);
00077                 int                             addNewDynamixel(CDxlConfig* config); //< Adds servo to group. Returns 0 on success
00078                 int       setupSyncReadChain();
00079 
00080                 // Init and deinit. Make sure you set the configuration before calling init!
00081                 virtual bool    init();
00082                 virtual bool    deinit();
00083 
00084 };
00085 
00086 
00087 #endif //__DYNAMIXELGROUP_H_INCLUDED__


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