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

This class gives a device specific interface for Schunk Powerballs, as they need some "special" treatment such as commutation search instead of homing. More...

#include <SchunkPowerBallNode.h>

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

Public Types

typedef boost::shared_ptr< const SchunkPowerBallNodeConstPtr
 Shared pointer to a const SchunkPowerBallNode. More...
 
typedef boost::shared_ptr< SchunkPowerBallNodePtr
 Shared pointer to a SchunkPowerBallNode. More...
 
- Public Types inherited from icl_hardware::canopen_schunk::DS402Node
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

void commutationSearch ()
 Performs a commutation search for a Schunk powerball module. More...
 
virtual void configureHomingMethod (const uint8_t homing_method)
 Set the device's homing method for a Schunk PowerBall. More...
 
virtual void configureHomingSpeeds (const uint32_t low_speed, const uint32_t high_speed=0)
 Set the speeds for homing for a Schunk PowerBall. More...
 
virtual void initNode ()
 Initializes the node and sets the Schunk Default PDO mapping. More...
 
 SchunkPowerBallNode (const uint8_t node_id, const icl_hardware::canopen_schunk::CanDevPtr &can_device, HeartBeatMonitor::Ptr heartbeat_monitor)
 
virtual void setDefaultPDOMapping (const DS402Node::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...
 
- Public Member Functions inherited from icl_hardware::canopen_schunk::DS402Node
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 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 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...
 
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...
 

Static Public Attributes

static const double RAD_TO_STEPS_FACTOR = 57295.7795131
 This factor will be used to convert RAD numbers into encoder ticks. More...
 

Protected Member Functions

virtual void configureInterpolationData (const uint8_t buffer_organization=0, const int16_t interpolation_type=0, const uint8_t size_of_data_record=4)
 Additionally to the basis implementation this sets a number of cycles that are allowed to be missed by device before stopping execution. More...
 
- Protected Member Functions inherited from icl_hardware::canopen_schunk::DS402Node
void configureHomingAcceleration (const uint32_t acceleration)
 Set the device's homing acceleration through an SDO (OD 0x609A) 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...
 

Private Member Functions

bool CommutationCalibrated ()
 Checks if the device is already correctly commutated by checking the value of the relevant register entry (via SDO communication). 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...
 
- Protected Attributes inherited from icl_hardware::canopen_schunk::DS402Node
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...
 

Detailed Description

This class gives a device specific interface for Schunk Powerballs, as they need some "special" treatment such as commutation search instead of homing.

Also, the powerballs have predefined PDO mappings: RPDO0 (Commands from PC to device):

TPDO (Information from device to PC):

Definition at line 46 of file SchunkPowerBallNode.h.

Member Typedef Documentation

Shared pointer to a const SchunkPowerBallNode.

Definition at line 52 of file SchunkPowerBallNode.h.

Shared pointer to a SchunkPowerBallNode.

Definition at line 50 of file SchunkPowerBallNode.h.

Constructor & Destructor Documentation

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

Definition at line 37 of file SchunkPowerBallNode.cpp.

Member Function Documentation

bool icl_hardware::canopen_schunk::SchunkPowerBallNode::CommutationCalibrated ( )
private

Checks if the device is already correctly commutated by checking the value of the relevant register entry (via SDO communication).

Returns
True, if commutation is already achieved, false otherwise.

Definition at line 171 of file SchunkPowerBallNode.cpp.

void icl_hardware::canopen_schunk::SchunkPowerBallNode::commutationSearch ( )

Performs a commutation search for a Schunk powerball module.

The commutation search gives information about where the module is when it is switched on. Basically, this gets called automatically the first time a movement is requested from the device.

Make sure, this is called during the initialization process (This should be taken care of by this driver already)

Definition at line 109 of file SchunkPowerBallNode.cpp.

void icl_hardware::canopen_schunk::SchunkPowerBallNode::configureHomingMethod ( const uint8_t  homing_method)
virtual

Set the device's homing method for a Schunk PowerBall.

Reimplementation for a Schunk powerball. It does not support to write the homing method register 0x6098. Therefor this only sets the internal member variable to the given value. Any value different from 0 enables the homing mode. Apart from that, it's value will be ignored.

Parameters
homing_methodNote that this parameter will be ignored.

Definition at line 188 of file SchunkPowerBallNode.cpp.

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

Set the speeds for homing for a Schunk PowerBall.

Reimplementation for a Schunk powerball. It does not support to write the homing method register 0x6099.

Parameters
low_speedNote that this parameter will be ignored.
high_speedNote that this parameter will be ignored.

Reimplemented from icl_hardware::canopen_schunk::DS402Node.

Definition at line 196 of file SchunkPowerBallNode.cpp.

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

Additionally to the basis implementation this sets a number of cycles that are allowed to be missed by device before stopping execution.

See the basis implementation for member documentation.

Reimplemented from icl_hardware::canopen_schunk::DS402Node.

Definition at line 204 of file SchunkPowerBallNode.cpp.

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

Initializes the node and sets the Schunk Default PDO mapping.

Reimplemented from icl_hardware::canopen_schunk::DS402Node.

Definition at line 44 of file SchunkPowerBallNode.cpp.

void icl_hardware::canopen_schunk::SchunkPowerBallNode::setDefaultPDOMapping ( const DS402Node::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 from icl_hardware::canopen_schunk::DS402Node.

Definition at line 52 of file SchunkPowerBallNode.cpp.

Member Data Documentation

const double icl_hardware::canopen_schunk::SchunkPowerBallNode::RAD_TO_STEPS_FACTOR = 57295.7795131
static

This factor will be used to convert RAD numbers into encoder ticks.

Definition at line 57 of file SchunkPowerBallNode.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