Abstract class describing a Drive used to communicate with a CANbus device. Note that many functions are implemented according to the CiA 402 Standard (but can be overridden)
More...
#include <Drive.h>
|
int | NodeID |
| The CAN Node ID used to address this particular drive on the CAN bus. More...
|
|
Abstract class describing a Drive used to communicate with a CANbus device. Note that many functions are implemented according to the CiA 402 Standard (but can be overridden)
Definition at line 93 of file Drive.h.
Drive::Drive |
( |
int |
NodeID | ) |
|
Construct a new Drive object.
- Parameters
-
NodeID | the CANopen Node ID of this drive |
Definition at line 11 of file Drive.cpp.
virtual Drive::~Drive |
( |
| ) |
|
|
virtual |
sets the state of the drive to "disabled"
This is equivalent to setting the control word (0x06064) to 0 See also the CANopen Programmer's Manual (from Copley Controls)
- Returns
- true if operation successful
-
false if operation unsuccessful
Definition at line 60 of file Drive.cpp.
Sets the state of the drive to "enabled".
This is equivalent to setting bits 0, 1, 2, 3 of the control word (0x06064) to 1 See also the CANopen Programmer's Manual (from Copley Controls)
- Returns
- true if operation successful
-
false if operation unsuccessful
Definition at line 55 of file Drive.cpp.
std::vector< std::string > Drive::generatePosControlConfigSDO |
( |
motorProfile |
positionProfile | ) |
|
|
protected |
Generates the list of commands required to configure Position control in CANopen motor drive.
- Parameters
-
Profile | Velocity, value used by position mode motor trajectory generator. Units: 0.1 counts/sec Range:0 - 500,000,000 |
Profile | Acceleration, value position mode motor trajectory generator will attempt to achieve. Units: 10 counts/sec^2 Range:0 - 200,000,000 |
Profile | Deceleration, value position mode motor trajectory generator will use at end of trapezoidal profile. see programmers manual for other profile types use. Units: 10 counts/sec^2 Range:0 - 200,000,000 |
NOTE: More details on params and profiles can be found in the CANopne CiA 402 series specifications: https://www.can-cia.org/can-knowledge/canopen/cia402/
Definition at line 198 of file Drive.cpp.
std::vector< std::string > Drive::generateRPDOConfigSDO |
( |
std::vector< OD_Entry_t > |
items, |
|
|
int |
PDO_Num, |
|
|
int |
UpdateTiming |
|
) |
| |
|
protected |
Generates the list of commands required to configure RPDOs on the drives.
- Parameters
-
items | A list of OD_Entry_t items which are to be configured with this RPDO |
PDO_Num | The number/index of this PDO |
UpdateTiming | 0-240 represents hold until next sync message, 0xFF represents immediate update |
- Returns
- std::string
Definition at line 151 of file Drive.cpp.
std::vector< std::string > Drive::generateTPDOConfigSDO |
( |
std::vector< OD_Entry_t > |
items, |
|
|
int |
PDO_Num, |
|
|
int |
SyncRate |
|
) |
| |
|
protected |
Generates the list of commands required to configure TPDOs on the drives.
- Parameters
-
items | A list of OD_Entry_t items which are to be configured with this TPDO |
PDO_Num | The number/index of this PDO |
SyncRate | The rate at which this PDO transmits (e.g. number of Sync Messages. 0xFF represents internal trigger event) |
- Returns
- std::string
Definition at line 104 of file Drive.cpp.
Get the current state of the drive.
- Returns
- DriveState
Definition at line 65 of file Drive.cpp.
Get returns the CanNode ID.
- Returns
- int the Node ID
Definition at line 17 of file Drive.cpp.
Returns the current position from the motor drive (0x6064)
- Returns
- Position from the motor drive
Definition at line 37 of file Drive.cpp.
Returns the current torque from the motor drive (0x6077)
- Returns
- Torque from the motor drive
Definition at line 46 of file Drive.cpp.
Returns the current velocity from the motor drive (0x606C)
- Returns
- Velocity from the motor drive
Definition at line 42 of file Drive.cpp.
virtual bool Drive::Init |
( |
| ) |
|
|
pure virtual |
Initialises the drive (SDO start message)
- Returns
- True if successful, False if not
Implemented in CopleyDrive.
Initialises a standard set of PDOs for the use of the drive. These are:
TPDO1: COB-ID 180+{NODE-ID}: Status Word (0x6041), Send on Internal Event Trigger TPDO2: COB-ID 280+{NODE-ID}: Actual Position (0x6064), Actual Velocity (0x606C), Sent every SYNC Message TPDO3: COB-ID 380+{NODE-ID}: Actual Torque (0x607C), Sent every SYNC MEssage
RPDO1: COB-ID 300+{NODE-ID}: Target Position (0x607A), Applied immediately when received RPDO2: COB-ID 400+{NODE-ID}: Target Velocity (0x60FF), Applied immediately when received
- Returns
- true
-
false
Definition at line 84 of file Drive.cpp.
virtual bool Drive::initPosControl |
( |
motorProfile |
posControlMotorProfile | ) |
|
|
pure virtual |
Sets the drive to Position control with set parameters (through SDO messages)
Note: Should be overloaded to allow parameters to be set
- Parameters
-
- Returns
- true if successful
-
false if not
Implemented in CopleyDrive.
virtual bool Drive::initTorqControl |
( |
| ) |
|
|
pure virtual |
Sets the drive to Torque control with default parameters (through SDO messages)
Note: Should be overloaded to allow parameters to be set
- Returns
- true if successful
-
false if not
Implemented in CopleyDrive.
virtual bool Drive::initVelControl |
( |
| ) |
|
|
pure virtual |
Sets the drive to Velocity control with default parameters (through SDO messages)
Note: Should be overloaded to allow parameters to be set
- Returns
- true if successful
-
false if not
Implemented in CopleyDrive.
bool Drive::posControlConfirmSP |
( |
| ) |
|
|
virtual |
Flips Bit 4 of Control Word (0x6041) - A new set point is only confirmed if the transition is from 0 to 1.
- Returns
- true The control word was previously 0 (i.e. successful set point confirm)
-
false The control word was previously 1 (i.e. unsuccessful set point confirm)
Definition at line 74 of file Drive.cpp.
bool Drive::readyToSwitchOn |
( |
| ) |
|
|
virtual |
Changes the state of the drive to "ready to switch on".
This is equivalent to setting bits 2 and 3 of Control Word (0x6064) to 1. See also the CANopen Programmer's Manual (from Copley Controls)
- Returns
- true if operation successful
-
false if operation unsuccessful
Definition at line 50 of file Drive.cpp.
int Drive::sendSDOMessages |
( |
std::vector< std::string > |
messages | ) |
|
|
protected |
messages Properly formatted SDO Messages
@ return int number of messages successfully processed(return OK)
Definition at line 230 of file Drive.cpp.
bool Drive::setPos |
( |
int |
position | ) |
|
|
virtual |
Writes the desired position to the Target Position of the motor drive (0x607A)
- Returns
- true if successful
-
false if not
Definition at line 21 of file Drive.cpp.
bool Drive::setTorque |
( |
int |
torque | ) |
|
|
virtual |
Writes the desired torque to the Target Torque of the motor drive (0x6071)
- Returns
- true if successful
-
false if not
Definition at line 32 of file Drive.cpp.
bool Drive::setVel |
( |
int |
velocity | ) |
|
|
virtual |
Writes the desired velocity to the Target Velocity of the motor drive (0x60FF)
- Returns
- true if successful
-
false if not
Definition at line 27 of file Drive.cpp.
int Drive::updateDriveStatus |
( |
| ) |
|
|
virtual |
Updates the internal representation of the state of the drive
- Returns
- The current value of the status word (0x6041)
Definition at line 69 of file Drive.cpp.
The mode in which the drive is currently configured.
Definition at line 170 of file Drive.h.
Current error state of the drive.
Definition at line 158 of file Drive.h.
The CAN Node ID used to address this particular drive on the CAN bus.
Definition at line 99 of file Drive.h.
Current status word of the drive.
Definition at line 152 of file Drive.h.
The documentation for this class was generated from the following files: