CORC Project
CANOpen Robot Controller Software Documentation
Public Member Functions | List of all members
CopleyDrive Class Reference

An implementation of the Drive Object, specifically for Copley-branded devices (currently used on the X2 Exoskeleton) More...

#include <CopleyDrive.h>

Inheritance diagram for CopleyDrive:
Inheritance graph
Collaboration diagram for CopleyDrive:
Collaboration graph

Public Member Functions

 CopleyDrive (int NodeID)
 Construct a new Copley Drive object. More...
 
 ~CopleyDrive ()
 Destroy the Copley Drive object. More...
 
bool Init ()
 
bool initPosControl (motorProfile posControlMotorProfile)
 
bool initVelControl (motorProfile velControlMotorProfile)
 
bool initTorqControl ()
 
std::vector< std::string > generatePosControlConfigSDO (motorProfile positionProfile)
 Overloaded method from Drive, specifically for Copley Drive implementation. Generates the list of commands required to configure Position control in CANopen motor drive. More...
 
std::vector< std::string > generateVelControlConfigSDO (motorProfile velocityProfile)
 Overloaded method from Drive, specifically for Copley Drive implementation. Generates the list of commands required to configure Velocity control in CANopen motor drive. More...
 
- Public Member Functions inherited from Drive
 Drive ()
 Construct a new Drive object. More...
 
 Drive (int NodeID)
 Construct a new Drive object. More...
 
virtual ~Drive ()
 Destroy the Drive object. More...
 
virtual bool initPDOs ()
 Initialises a standard set of PDOs for the use of the drive. These are: More...
 
virtual int updateDriveStatus ()
 
virtual bool setPos (int position)
 
virtual bool setVel (int velocity)
 
virtual bool setTorque (int torque)
 
virtual int getPos ()
 
virtual int getVel ()
 
virtual int getTorque ()
 
virtual bool readyToSwitchOn ()
 Changes the state of the drive to "ready to switch on". More...
 
virtual bool enable ()
 Sets the state of the drive to "enabled". More...
 
virtual bool disable ()
 sets the state of the drive to "disabled" More...
 
virtual bool posControlConfirmSP ()
 Flips Bit 4 of Control Word (0x6041) - A new set point is only confirmed if the transition is from 0 to 1. More...
 
virtual DriveState getDriveState ()
 Get the current state of the drive. More...
 
int getNodeID ()
 Get returns the CanNode ID. More...
 

Additional Inherited Members

- Protected Member Functions inherited from Drive
std::vector< std::string > generateTPDOConfigSDO (std::vector< OD_Entry_t > items, int PDO_Num, int SyncRate)
 Generates the list of commands required to configure TPDOs on the drives. More...
 
std::vector< std::string > generateRPDOConfigSDO (std::vector< OD_Entry_t > items, int PDO_Num, int UpdateTiming)
 Generates the list of commands required to configure RPDOs on the drives. More...
 
std::vector< std::string > generatePosControlConfigSDO (motorProfile positionProfile)
 Generates the list of commands required to configure Position control in CANopen motor drive. More...
 
std::vector< std::string > generateVelControlConfigSDO (motorProfile velocityProfile)
 Generates the list of commands required to configure Velocity control in CANopen motor drive. More...
 
int sendSDOMessages (std::vector< std::string > messages)
 messages Properly formatted SDO Messages More...
 
- Protected Attributes inherited from Drive
int NodeID
 The CAN Node ID used to address this particular drive on the CAN bus. More...
 

Detailed Description

An implementation of the Drive Object, specifically for Copley-branded devices (currently used on the X2 Exoskeleton)

Definition at line 23 of file CopleyDrive.h.

Constructor & Destructor Documentation

CopleyDrive::CopleyDrive ( int  NodeID)

Construct a new Copley Drive object.

An implementation of the Drive Object, specifically for the Copley Drive.

Parameters
NodeIDCANopen Node ID

Definition at line 11 of file CopleyDrive.cpp.

CopleyDrive::~CopleyDrive ( )

Destroy the Copley Drive object.

Definition at line 14 of file CopleyDrive.cpp.

Member Function Documentation

std::vector< std::string > CopleyDrive::generatePosControlConfigSDO ( motorProfile  positionProfile)

Overloaded method from Drive, specifically for Copley Drive implementation. Generates the list of commands required to configure Position control in CANopen motor drive.

/param Profile Velocity, value used by position mode motor trajectory generator. Units: 0.1 counts/sec Range:0 - 500,000,000 /param Profile Acceleration, value position mode motor trajectory generator will attempt to achieve. Units: 10 counts/sec^2 Range:0 - 200,000,000 /param 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 42 of file CopleyDrive.cpp.

std::vector< std::string > CopleyDrive::generateVelControlConfigSDO ( motorProfile  velocityProfile)

Overloaded method from Drive, specifically for Copley Drive implementation. Generates the list of commands required to configure Velocity control in CANopen motor drive.

/param Profile Acceleration, value Velocity mode motor trajectory generator will attempt to achieve. Units: 10 counts/sec^2 Range:0 - 200,000,000 /param Profile Deceleration, value Velocity 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 46 of file CopleyDrive.cpp.

bool CopleyDrive::Init ( )
virtual

Initialises the drive (SDO start message)

Returns
True if successful, False if not

Implements Drive.

Definition at line 18 of file CopleyDrive.cpp.

bool CopleyDrive::initPosControl ( motorProfile  posControlMotorProfile)
virtual

Sets the drive to Position control with default parameters (through SDO messages)

Note: Should be overloaded to allow parameters to be set

Returns
true if successful
false if not

Implements Drive.

Definition at line 22 of file CopleyDrive.cpp.

bool CopleyDrive::initTorqControl ( )
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

Implements Drive.

Definition at line 39 of file CopleyDrive.cpp.

bool CopleyDrive::initVelControl ( motorProfile  velControlMotorProfile)
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

Implements Drive.

Definition at line 31 of file CopleyDrive.cpp.


The documentation for this class was generated from the following files: