Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
icl_hardware::canopen_schunk::DS402Node Class Reference

Class that holds devices according to the DS402 (drives and motion control) specification. More...

#include <DS402Node.h>

Inheritance diagram for icl_hardware::canopen_schunk::DS402Node:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< const DS402NodeConstPtr
 Shared pointer to a const DS402Node. More...
 
enum  eDefaultPDOMapping { PDO_MAPPING_CONTROLWORD_STATUSWORD, PDO_MAPPING_INTERPOLATED_POSITION_MODE, PDO_MAPPING_PROFILE_POSITION_MODE }
 
typedef boost::shared_ptr< DS402NodePtr
 Shared pointer to a DS402Node. More...
 
- Public Types inherited from icl_hardware::canopen_schunk::DS301Node
typedef boost::shared_ptr< const DS301NodeConstPtr
 Shared pointer to a const DS301Node. More...
 
enum  ePDO_TYPE { RECEIVE_PDO, TRANSMIT_PDO }
 Type of a PDO. RECEIVE_PDOs carry data from the host to the device, TRANSMIT_PDOs from the device to the host. More...
 
typedef boost::shared_ptr< DS301NodePtr
 Shared pointer to a DS301Node. More...
 

Public Member Functions

virtual void acceptPPTargets ()
 After enabling PP movement, this enables accepting new targets again. Remember to sync all nodes and download RPDOs before and after. More...
 
virtual void closeBrakes ()
 When the device is in OperationEnabled mode, this function disable the drive motion. More...
 
virtual void configureHomingMethod (const int8_t homing_method)
 Set the device's homing method through an SDO (OD 0x6098) More...
 
virtual void configureHomingSpeeds (const uint32_t low_speed, const uint32_t high_speed=0)
 Set the speeds for homing through SDO 6099. Typically, a high speed is used when searching for a home switch and the slow speed is used when searching for the index. More...
 
virtual void configureInterpolationCycleTime (const uint8_t interpolation_cycle_time_ms=8)
 Set the interpolation cycle time in milliseconds. If no time is given the default will be used. More...
 
virtual void disableNode ()
 Puts the device into STATE_SWITCHED_ON mode. If the device was in InterpolatedPositionMode, interpolation will be stopped here, as well. More...
 
 DS402Node (const uint8_t node_id, const icl_hardware::canopen_schunk::CanDevPtr &can_device, HeartBeatMonitor::Ptr heartbeat_monitor)
 
virtual void enableNode (const ds402::eModeOfOperation operation_mode=ds402::MOO_RESERVED_0)
 Switches on the device and enters Operation Enabled mode with the given mode. If the requested mode is InterpolatedPositionMode, interpolation will be started automatically. More...
 
size_t getMaximumNumberOfStateTransitions () const
 
ds402::eModeOfOperation getModeOfOperation () const
 Get the current mode of operation. More...
 
virtual ds402::Statusword getStatus ()
 
virtual double getTargetFeedback ()
 Depending on the mode of operation, this will return the current position, velocity or torque. More...
 
double getTransmissionFactor () const
 The Transmission factor is used for converting radiant units into device ticks. By default it's value is 1, so you can configure the conversion pipeline in the device. However, if the device does not implement any conversion, this can be done on host side with this factor. More...
 
virtual void home ()
 Perform homing for this node. More...
 
virtual void initDS402State (const icl_hardware::canopen_schunk::ds402::eState &requested_state)
 Initializes a state of the DS402 state machine. Performs all necessary state transitions until the target state is reached. However, it performs a maximum of m_max_number_of_state_transitions transitions. More...
 
virtual void initNode ()
 Initializes the node. Tries to query all required data from the device. More...
 
virtual bool isModeSupported (const ds402::eModeOfOperation op_mode)
 Tests whether a given mode of operation is supported by the device. More...
 
virtual bool isTargetReached ()
 Returns whether the device has reached it's recent target. More...
 
virtual void openBrakes ()
 When the device is in OperationEnabled mode, this function enables the drive motion. More...
 
virtual void printStatus ()
 Prints a stringified version of the statusword to the logging system. More...
 
void printSupportedModesOfOperation ()
 Prints out all Modes on which the device claims to be able to operate on. More...
 
virtual void querySupportedDeviceModes ()
 Uploads all supported modes of operation from the device. and stores them in the m_supported_modes member. More...
 
virtual void quickStop ()
 This sends the controlword for performing a quick_stop. More...
 
virtual bool resetFault ()
 This function is used to recover from a fault state. More...
 
virtual void setDefaultPDOMapping (const eDefaultPDOMapping mapping)
 Choose one of the predefined default mappings. Please see the enum eDefaultPDOMapping for a list of available mappings. See the implementation for further details about the mappings. More...
 
void setMaximumNumberOfStateTransitions (const size_t max_number_of_state_transitions)
 
virtual bool setModeOfOperation (const ds402::eModeOfOperation op_mode)
 Sets and initializes a mode of operation. First it will check whether the device supports the requested mode. So if you request a mode that the device does not support, it just returns false and does nothing. More...
 
virtual void setNMTState (const NMT::eNMT_State state, const NMT::eNMT_SubState sub_state)
 
virtual bool setTarget (const float target)
 Sets the target for the motor. What that target is, depends on the selected mode of operation. The value will be clamped into the range value that is defined by the CanOpen specification. More...
 
void setTransmissionFactor (const double transmission_factor)
 The Transmission factor is used for converting radiant units into device ticks. By default it's value is 1, so you can configure the conversion pipeline in the device. However, if the device does not implement any conversion, this can be done on host side with this factor. More...
 
virtual void setupHomingMode (const ds402::HomingModeConfiguration &config)
 Configure the mandatory parameters for a homing mode. More...
 
virtual void setupProfilePositionMode (const ds402::ProfilePositionModeConfiguration &config)
 Configure the mandatory parameters for a profile position mode. More...
 
virtual void setupProfileTorqueMode (const ds402::ProfileTorqueModeConfiguration &config)
 Configure the mandatory parameters for a profile torque mode. More...
 
virtual void setupProfileVelocityMode (const ds402::ProfileVelocityModeConfiguration &config)
 Configure the mandatory parameters for a profile velocity mode. More...
 
virtual void startPPMovement ()
 This sets the RPDO communication for enabling the movement after a target has been set. Note, that sync and pdo-download has to be called in between setting the target and enabling movement. Afterwards call acceptPPTarget() to enable setting following targets. More...
 
virtual void stopNode ()
 This redefines the basic stopNode function. More...
 
- Public Member Functions inherited from icl_hardware::canopen_schunk::DS301Node
virtual void appendPDOMappingSingle (const PDO::MappingConfigurationList &config, const uint16_t pdo_nr, const PDO::eTransmissionType &transmission_type, const ePDO_TYPE &pdo_type, const bool dummy_mapping=false, const uint8_t cyclic_timeout_cycles=0)
 Appends one or more mapping parameters to the existing mapping. Note that the PDO will be disabled while appending another mapping. More...
 
void downloadPDOs ()
 Downloads all Receive-PDOs of this node to the device. More...
 
 DS301Node (const uint8_t node_id, const CanDevPtr &can_device, HeartBeatMonitor::Ptr heartbeat_monitor)
 
uint8_t getNodeId () const
 
template<typename T >
getRPDOValue (const std::string &identifier)
 
template<typename T >
getTPDOValue (const std::string &identifier)
 Get the value of a PDO which is mapped to a given identifier. More...
 
virtual void initPDOMappingSingle (const PDO::MappingConfigurationList &config, const uint16_t pdo_nr, const PDO::eTransmissionType &transmission_type, const ePDO_TYPE &pdo_type, const bool dummy_mapping=false, const uint8_t cyclic_timeout_cycles=0)
 Init PDO mapping with a given mapping configuration for a given pdo nr. More...
 
void printPDOMapping ()
 Will query the PDO mapping from the device and print that to the output. More...
 
void registerPDONotifyCallback (const std::string &identifier, const boost::function< void()> &f)
 This function maps a callback to a specific mapped PDO entry. This callback will be called by the PDO upload function, whenever a PDO with the specified data will arrive. Please note, that the callback function will only be notified of new data, but the data must be queried from the PDO separately. A PDO entry can call multiple callbacks, currently callbacks can't be unregistered. More...
 
virtual void registerWSBroadcaster (boost::shared_ptr< icl_comm::websocket::WsBroadcaster > broadcaster)
 registerWSBroadcaster Adds a debug interface More...
 
template<typename T >
bool setRPDOValue (const std::string &identifier, const T value)
 Set the value of a PDO which is mapped to a given identifier. More...
 
template<typename T >
bool setTPDOValue (const std::string &identifier, const T value)
 Set the value of a PDO which is mapped to a given identifier. More...
 
virtual void startHeartbeat ()
 Initializes the heartbeat for the node. Throws ProtocolException it heartbeat cannot be initialized. More...
 
void uploadPDOs ()
 Uploads all Transmit-PDOs of this node from the device. More...
 

Protected Member Functions

void configureHomingAcceleration (const uint32_t acceleration)
 Set the device's homing acceleration through an SDO (OD 0x609A) More...
 
virtual void configureInterpolationData (const uint8_t buffer_organization=0, const int16_t interpolation_type=0, const uint8_t size_of_data_record=4)
 Configure the buffer for the interpolated position mode. More...
 
void configureMaxAcceleration (const uint32_t acceleration)
 Set the device's maximum acceleration through an SDO (OD 0x60c5) More...
 
void configureMaxDeceleration (const uint32_t deceleration)
 Set the device's maximum deceleration through an SDO (OD 0x60c6) More...
 
void configureMotionProfileType (const int16_t motion_type)
 Set the device's motion profile type through an SDO (OD 0x6086) More...
 
void configureProfileAcceleration (const uint32_t acceleration)
 Set the device's profile acceleration through an SDO (OD 0x6083) More...
 
void configureProfileDeceleration (const uint32_t deceleration)
 Set the device's profile deceleration through an SDO (OD 0x6084) More...
 
void configureProfileVelocity (const uint32_t velocity)
 Set the device's profile velocity through an SDO (OD 0x6081) More...
 
void configureQuickStopDeceleration (const uint32_t deceleration)
 Set the device's quick stop deceleration through an SDO (OD 0x6085) More...
 
void configureSensorSelectionCode (const int16_t sensor_selection_code)
 Set the device's sensor selection code through an SDO (OD 0x606a) More...
 
void configureTorqueProfileType (const int16_t torque_profile_type)
 Set the device's torque profile type through an SDO (OD 0x6088) More...
 
void configureTorqueSlope (const uint32_t torque_slope)
 Set the device's torque slope through an SDO (OD 0x6087) More...
 
void doDS402StateTransition (const ds402::eStateTransission transition)
 Performs a state transition in the DS402 state machine. More...
 
virtual void onStatusWordUpdate ()
 This will be called when a new statusword PDO comes in. If the device's state differs from the one expected, the local status will be changed accordingly. More...
 
std::string operationModeSpecificStatus (const ds402::Statusword &statusword)
 This function queries the two operation mode specific bits and turns them to a human-readable string. More...
 

Protected Attributes

ds402::eState m_current_ds402_state
 
ds402::eState m_expected_ds402_state
 
int8_t m_homing_method
 
uint8_t m_interpolation_cycle_time_ms
 Cycle time of interpolation mode. More...
 
size_t m_max_number_of_state_transitions
 
ds402::eModeOfOperation m_op_mode
 The mode of operation of this device. More...
 
ds402::ProfilePositionModeConfiguration m_ppm_config
 
ds402::SupportedDriveModes m_supported_modes
 supported modes of operation More...
 
double m_transmission_factor
 
- Protected Attributes inherited from icl_hardware::canopen_schunk::DS301Node
CanDevPtr m_can_dev
 Device handle for transmission of messages. More...
 
uint16_t m_heartbeat_cycle_time_ms
 
HeartBeatMonitor::Ptr m_heartbeat_monitor
 
uint8_t m_node_id
 CANOPEN ID of the node. More...
 
boost::unordered_map< std::string, PDOMapEntrym_rpdo_mapping
 This map holds a mapping between an identifier string and a mapped position in a RPDO. More...
 
boost::unordered_map< std::string, PDOMapEntrym_tpdo_mapping
 This map holds a mapping between an identifier string and a mapped position in a TPDO. More...
 
boost::shared_ptr< icl_comm::websocket::WsBroadcaster > m_ws_broadcaster
 Interface to send out diagnostics data. Only available if compiled with IC_BUILDER_ICL_COMM_WEBSOCKET More...
 

Additional Inherited Members

- Public Attributes inherited from icl_hardware::canopen_schunk::DS301Node
EMCY::Ptr m_emcy
 EMCY object to handle spontaneous callbacks with emergency messages. More...
 
NMT m_nmt
 Object to handle NMT calls and status. More...
 
RPDO::PtrList m_rpdos
 RPDOS of this node (up to 4 in standard config) More...
 
SDO m_sdo
 SDO object for specific calls. More...
 
TPDO::PtrList m_tpdos
 TPDOS of this node (up to 4 in standard config) More...
 

Detailed Description

Class that holds devices according to the DS402 (drives and motion control) specification.

It defines interfaces to different DS402 operation modes and offers many comfort interface methods to acquire typical device operations such as e.g. QuickStop triggering.

Definition at line 43 of file DS402Node.h.

Member Typedef Documentation

Shared pointer to a const DS402Node.

Definition at line 49 of file DS402Node.h.

Shared pointer to a DS402Node.

Definition at line 47 of file DS402Node.h.

Member Enumeration Documentation

Enumerator
PDO_MAPPING_CONTROLWORD_STATUSWORD 
PDO_MAPPING_INTERPOLATED_POSITION_MODE 
PDO_MAPPING_PROFILE_POSITION_MODE 

Definition at line 51 of file DS402Node.h.

Constructor & Destructor Documentation

icl_hardware::canopen_schunk::DS402Node::DS402Node ( const uint8_t  node_id,
const icl_hardware::canopen_schunk::CanDevPtr can_device,
HeartBeatMonitor::Ptr  heartbeat_monitor 
)

Definition at line 35 of file DS402Node.cpp.

Member Function Documentation

void icl_hardware::canopen_schunk::DS402Node::acceptPPTargets ( )
virtual

After enabling PP movement, this enables accepting new targets again. Remember to sync all nodes and download RPDOs before and after.

Definition at line 175 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::closeBrakes ( )
virtual

When the device is in OperationEnabled mode, this function disable the drive motion.

Definition at line 1116 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureHomingAcceleration ( const uint32_t  acceleration)
protected

Set the device's homing acceleration through an SDO (OD 0x609A)

Definition at line 921 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureHomingMethod ( const int8_t  homing_method)
virtual

Set the device's homing method through an SDO (OD 0x6098)

Definition at line 927 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureHomingSpeeds ( const uint32_t  low_speed,
const uint32_t  high_speed = 0 
)
virtual

Set the speeds for homing through SDO 6099. Typically, a high speed is used when searching for a home switch and the slow speed is used when searching for the index.

Reimplemented in icl_hardware::canopen_schunk::SchunkPowerBallNode.

Definition at line 912 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureInterpolationCycleTime ( const uint8_t  interpolation_cycle_time_ms = 8)
virtual

Set the interpolation cycle time in milliseconds. If no time is given the default will be used.

Parameters
interpolation_cycle_time_msInterpolation cycle time in milliseconds

Definition at line 764 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureInterpolationData ( const uint8_t  buffer_organization = 0,
const int16_t  interpolation_type = 0,
const uint8_t  size_of_data_record = 4 
)
protectedvirtual

Configure the buffer for the interpolated position mode.

Parameters
buffer_organization0: FIFO buffer, 1: Ring buffer
interpolation_typeType of interpolation
  • -32768 ... -1 : manufacturer specific
  • 0: linear interpolation, 1: Ring buffer
  • +1 ... 32767: reserved
size_of_data_recordSize of interpolation buffer. Should be 4 for linear interpolation

Reimplemented in icl_hardware::canopen_schunk::SchunkPowerBallNode.

Definition at line 952 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureMaxAcceleration ( const uint32_t  acceleration)
protected

Set the device's maximum acceleration through an SDO (OD 0x60c5)

Definition at line 864 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureMaxDeceleration ( const uint32_t  deceleration)
protected

Set the device's maximum deceleration through an SDO (OD 0x60c6)

Definition at line 871 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureMotionProfileType ( const int16_t  motion_type)
protected

Set the device's motion profile type through an SDO (OD 0x6086)

Definition at line 904 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureProfileAcceleration ( const uint32_t  acceleration)
protected

Set the device's profile acceleration through an SDO (OD 0x6083)

Definition at line 885 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureProfileDeceleration ( const uint32_t  deceleration)
protected

Set the device's profile deceleration through an SDO (OD 0x6084)

Definition at line 892 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureProfileVelocity ( const uint32_t  velocity)
protected

Set the device's profile velocity through an SDO (OD 0x6081)

Definition at line 877 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureQuickStopDeceleration ( const uint32_t  deceleration)
protected

Set the device's quick stop deceleration through an SDO (OD 0x6085)

Definition at line 897 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureSensorSelectionCode ( const int16_t  sensor_selection_code)
protected

Set the device's sensor selection code through an SDO (OD 0x606a)

Definition at line 934 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureTorqueProfileType ( const int16_t  torque_profile_type)
protected

Set the device's torque profile type through an SDO (OD 0x6088)

Definition at line 940 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::configureTorqueSlope ( const uint32_t  torque_slope)
protected

Set the device's torque slope through an SDO (OD 0x6087)

Definition at line 946 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::disableNode ( )
virtual

Puts the device into STATE_SWITCHED_ON mode. If the device was in InterpolatedPositionMode, interpolation will be stopped here, as well.

Definition at line 1069 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::doDS402StateTransition ( const ds402::eStateTransission  transition)
protected

Performs a state transition in the DS402 state machine.

Parameters
transitionTransition that should be performed
Exceptions
ProtocolExceptionon error

Definition at line 974 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::enableNode ( const ds402::eModeOfOperation  operation_mode = ds402::MOO_RESERVED_0)
virtual

Switches on the device and enters Operation Enabled mode with the given mode. If the requested mode is InterpolatedPositionMode, interpolation will be started automatically.

Parameters
operation_modeDS402 Operation mode that should be used. If left blank, no mode will be set. However, then you should make sure to set it in advance.

Definition at line 1049 of file DS402Node.cpp.

size_t icl_hardware::canopen_schunk::DS402Node::getMaximumNumberOfStateTransitions ( ) const
inline

Definition at line 235 of file DS402Node.h.

ds402::eModeOfOperation icl_hardware::canopen_schunk::DS402Node::getModeOfOperation ( ) const
inline

Get the current mode of operation.

Definition at line 122 of file DS402Node.h.

ds402::Statusword icl_hardware::canopen_schunk::DS402Node::getStatus ( )
virtual

Definition at line 1167 of file DS402Node.cpp.

double icl_hardware::canopen_schunk::DS402Node::getTargetFeedback ( )
virtual

Depending on the mode of operation, this will return the current position, velocity or torque.

Returns
double

Definition at line 185 of file DS402Node.cpp.

double icl_hardware::canopen_schunk::DS402Node::getTransmissionFactor ( ) const
inline

The Transmission factor is used for converting radiant units into device ticks. By default it's value is 1, so you can configure the conversion pipeline in the device. However, if the device does not implement any conversion, this can be done on host side with this factor.

Definition at line 195 of file DS402Node.h.

void icl_hardware::canopen_schunk::DS402Node::home ( )
virtual

Perform homing for this node.

Definition at line 502 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::initDS402State ( const icl_hardware::canopen_schunk::ds402::eState requested_state)
virtual

Initializes a state of the DS402 state machine. Performs all necessary state transitions until the target state is reached. However, it performs a maximum of m_max_number_of_state_transitions transitions.

Parameters
requested_stateTarget state
Exceptions
DeviceExceptionif the device is in a fault state from which it can't recover

Definition at line 302 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::initNode ( )
virtual

Initializes the node. Tries to query all required data from the device.

Reimplemented from icl_hardware::canopen_schunk::DS301Node.

Reimplemented in icl_hardware::canopen_schunk::SchunkPowerBallNode.

Definition at line 639 of file DS402Node.cpp.

bool icl_hardware::canopen_schunk::DS402Node::isModeSupported ( const ds402::eModeOfOperation  op_mode)
virtual

Tests whether a given mode of operation is supported by the device.

Note
This function will only compare it to the cached information about supported modes. The user has to call querySupportedDeviceModes() at some earlier point.
Parameters
op_modeMode of operation that should be checked
Returns
True if mode is supported, false otherwise.

Definition at line 651 of file DS402Node.cpp.

bool icl_hardware::canopen_schunk::DS402Node::isTargetReached ( )
virtual

Returns whether the device has reached it's recent target.

Returns
True, if current target is reached, false otherwise

Definition at line 1159 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::onStatusWordUpdate ( )
protectedvirtual

This will be called when a new statusword PDO comes in. If the device's state differs from the one expected, the local status will be changed accordingly.

Definition at line 1136 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::openBrakes ( )
virtual

When the device is in OperationEnabled mode, this function enables the drive motion.

Definition at line 1079 of file DS402Node.cpp.

std::string icl_hardware::canopen_schunk::DS402Node::operationModeSpecificStatus ( const ds402::Statusword statusword)
protected

This function queries the two operation mode specific bits and turns them to a human-readable string.

Parameters
statuswordthe statusword
Returns
Stringified opMode specific status

Definition at line 576 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::printStatus ( )
virtual

Prints a stringified version of the statusword to the logging system.

Definition at line 554 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::printSupportedModesOfOperation ( )

Prints out all Modes on which the device claims to be able to operate on.

Note
Make sure to call either initNode() or querySupportedDeviceModes() before calling this function.

Definition at line 664 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::querySupportedDeviceModes ( )
virtual

Uploads all supported modes of operation from the device. and stores them in the m_supported_modes member.

Definition at line 634 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::quickStop ( )
virtual

This sends the controlword for performing a quick_stop.

Definition at line 266 of file DS402Node.cpp.

bool icl_hardware::canopen_schunk::DS402Node::resetFault ( )
virtual

This function is used to recover from a fault state.

It clears the error register and performs state transition 15.

Definition at line 828 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setDefaultPDOMapping ( const eDefaultPDOMapping  mapping)
virtual

Choose one of the predefined default mappings. Please see the enum eDefaultPDOMapping for a list of available mappings. See the implementation for further details about the mappings.

Parameters
mappingMapping that should be set.

Reimplemented in icl_hardware::canopen_schunk::SchunkPowerBallNode.

Definition at line 44 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setMaximumNumberOfStateTransitions ( const size_t  max_number_of_state_transitions)
inline

Definition at line 236 of file DS402Node.h.

bool icl_hardware::canopen_schunk::DS402Node::setModeOfOperation ( const ds402::eModeOfOperation  op_mode)
virtual

Sets and initializes a mode of operation. First it will check whether the device supports the requested mode. So if you request a mode that the device does not support, it just returns false and does nothing.

Parameters
op_modeOperation mode according to ds402::eModeOfOperation.
Returns
True if mode was successfully initialized, false otherwise.

Definition at line 709 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setNMTState ( const NMT::eNMT_State  state,
const NMT::eNMT_SubState  sub_state 
)
virtual

Definition at line 261 of file DS402Node.cpp.

bool icl_hardware::canopen_schunk::DS402Node::setTarget ( const float  target)
virtual

Sets the target for the motor. What that target is, depends on the selected mode of operation. The value will be clamped into the range value that is defined by the CanOpen specification.

It might be for example a position, a velocity or a torque. For transmission to the device PDOs are used. Make sure that those PDOs are configured correctly

Parameters
targetTarget value for current mode of operation
Returns
True if target could be set, false otherwise

Definition at line 96 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setTransmissionFactor ( const double  transmission_factor)
inline

The Transmission factor is used for converting radiant units into device ticks. By default it's value is 1, so you can configure the conversion pipeline in the device. However, if the device does not implement any conversion, this can be done on host side with this factor.

Definition at line 203 of file DS402Node.h.

void icl_hardware::canopen_schunk::DS402Node::setupHomingMode ( const ds402::HomingModeConfiguration config)
virtual

Configure the mandatory parameters for a homing mode.

Parameters
configStruct of mandatory parameters for a homing mode

Definition at line 811 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setupProfilePositionMode ( const ds402::ProfilePositionModeConfiguration config)
virtual

Configure the mandatory parameters for a profile position mode.

Parameters
configStruct of parameters used for profile position mode

Definition at line 775 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setupProfileTorqueMode ( const ds402::ProfileTorqueModeConfiguration config)
virtual

Configure the mandatory parameters for a profile torque mode.

Parameters
configStruct of mandatory parameters for a profile torque mode

Definition at line 822 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::setupProfileVelocityMode ( const ds402::ProfileVelocityModeConfiguration config)
virtual

Configure the mandatory parameters for a profile velocity mode.

Parameters
configStruct of mandatory parameters for a profile velocity mode

Definition at line 817 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::startPPMovement ( )
virtual

This sets the RPDO communication for enabling the movement after a target has been set. Note, that sync and pdo-download has to be called in between setting the target and enabling movement. Afterwards call acceptPPTarget() to enable setting following targets.

Definition at line 165 of file DS402Node.cpp.

void icl_hardware::canopen_schunk::DS402Node::stopNode ( )
virtual

This redefines the basic stopNode function.

Currently this simply calls quickStop()

Reimplemented from icl_hardware::canopen_schunk::DS301Node.

Definition at line 296 of file DS402Node.cpp.

Member Data Documentation

ds402::eState icl_hardware::canopen_schunk::DS402Node::m_current_ds402_state
protected

Definition at line 388 of file DS402Node.h.

ds402::eState icl_hardware::canopen_schunk::DS402Node::m_expected_ds402_state
protected

Definition at line 389 of file DS402Node.h.

int8_t icl_hardware::canopen_schunk::DS402Node::m_homing_method
protected

Definition at line 398 of file DS402Node.h.

uint8_t icl_hardware::canopen_schunk::DS402Node::m_interpolation_cycle_time_ms
protected

Cycle time of interpolation mode.

Definition at line 396 of file DS402Node.h.

size_t icl_hardware::canopen_schunk::DS402Node::m_max_number_of_state_transitions
protected

Definition at line 397 of file DS402Node.h.

ds402::eModeOfOperation icl_hardware::canopen_schunk::DS402Node::m_op_mode
protected

The mode of operation of this device.

Definition at line 386 of file DS402Node.h.

ds402::ProfilePositionModeConfiguration icl_hardware::canopen_schunk::DS402Node::m_ppm_config
protected

Definition at line 391 of file DS402Node.h.

ds402::SupportedDriveModes icl_hardware::canopen_schunk::DS402Node::m_supported_modes
protected

supported modes of operation

Definition at line 383 of file DS402Node.h.

double icl_hardware::canopen_schunk::DS402Node::m_transmission_factor
protected

Definition at line 399 of file DS402Node.h.


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


schunk_canopen_driver
Author(s): Felix Mauch , Georg Heppner
autogenerated on Mon Jun 10 2019 15:07:49