CORC Project
CANOpen Robot Controller Software Documentation
Drive.h
Go to the documentation of this file.
1 
16 #ifndef DRIVE_H_INCLUDED
17 #define DRIVE_H_INCLUDED
18 
19 #include <CANopen.h>
20 #include <CO_command.h>
21 #include <string.h>
22 
23 #include <map>
24 #include <sstream>
25 #include <vector>
26 
37  ERROR = -1
38 };
43 enum DriveState {
44  DISABLED = 0,
46  ENABLED = 2,
47 };
48 
54 enum OD_Entry_t {
59  TARGET_POS = 11,
61 };
62 
68 static std::map<OD_Entry_t, int> OD_Addresses = {
69  {STATUS_WORD, 0x6041},
70  {ACTUAL_POS, 0x6064},
71  {ACTUAL_VEL, 0x606C},
72  {ACTUAL_TOR, 0x6077},
73  {TARGET_POS, 0x607A},
74  {TARGET_VEL, 0x60FF},
75 };
76 
82 static std::map<OD_Entry_t, int> OD_Data_Size = {
83  {STATUS_WORD, 0x0010},
84  {ACTUAL_POS, 0x0020},
85  {ACTUAL_VEL, 0x0020},
86  {ACTUAL_TOR, 0x0010},
87  {TARGET_POS, 0x0020},
88  {TARGET_VEL, 0x0020},
89 };
94 struct motorProfile {
98 };
99 
105 class Drive {
106  protected:
111  int NodeID;
112 
121  std::vector<std::string> generateTPDOConfigSDO(std::vector<OD_Entry_t> items, int PDO_Num, int SyncRate);
122 
131  std::vector<std::string> generateRPDOConfigSDO(std::vector<OD_Entry_t> items, int PDO_Num, int UpdateTiming);
132 
147  std::vector<std::string> generatePosControlConfigSDO(motorProfile positionProfile);
148 
163  std::vector<std::string> generateVelControlConfigSDO(motorProfile velocityProfile);
164 
170  int
171  sendSDOMessages(std::vector<std::string> messages);
172 
173  private:
179 
184  int error;
185 
190  DriveState driveState = DISABLED;
191 
196  ControlMode controlMode = UNCONFIGURED;
197 
198  public:
203  Drive();
204 
210  Drive(int NodeID);
211 
216  virtual ~Drive(){};
217 
223  virtual bool Init() = 0;
224 
238  virtual bool initPDOs();
239 
250  virtual bool initPosControl(motorProfile posControlMotorProfile) = 0;
251 
260  virtual bool initVelControl(motorProfile velControlMotorProfile) = 0;
261 
270  virtual bool initTorqControl() = 0;
271 
277  virtual int updateDriveStatus();
278 
285  virtual bool setPos(int position);
286 
293  virtual bool setVel(int velocity);
294 
301  virtual bool setTorque(int torque);
302 
308  virtual int getPos();
309 
315  virtual int getVel();
316 
322  virtual int getTorque();
323 
324  // Drive State Modifiers
334  virtual bool readyToSwitchOn();
335 
345  virtual bool enable();
346 
356  virtual bool disable();
357 
364  virtual bool posControlConfirmSP();
365 
371  virtual DriveState getDriveState();
372 
373  // CANOpen
379  int getNodeID();
380 };
381 
382 #endif
OD_Entry_t
Definition: Drive.h:54
int profileAccelration
Definition: Drive.h:96
Definition: Drive.h:44
Abstract class describing a Drive used to communicate with a CANbus device. Note that many functions ...
Definition: Drive.h:105
ControlMode
Definition: Drive.h:32
Definition: Drive.h:46
int error
Current error state of the drive.
Definition: Drive.h:184
int profileDeceleration
Definition: Drive.h:97
int NodeID
The CAN Node ID used to address this particular drive on the CAN bus.
Definition: Drive.h:111
int profileVelocity
Definition: Drive.h:95
struct to hold desired velocity, acceleration and deceleration values for a drives motor controller p...
Definition: Drive.h:94
DriveState
Definition: Drive.h:43
virtual ~Drive()
Destroy the Drive object.
Definition: Drive.h:216
Definition: Drive.h:37
int statusWord
Current status word of the drive.
Definition: Drive.h:178