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

The DS402Group class is the base class for canOpen devices implementing the DS402 device protocol (motors) More...

#include <DS402Group.h>

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

Public Types

typedef boost::shared_ptr< const DS402GroupConstPtr
 Shared pointer to a const DS402Group. More...
 
typedef boost::shared_ptr< DS402GroupPtr
 Shared pointer to a DS402Group. More...
 
- Public Types inherited from icl_hardware::canopen_schunk::DS301Group
typedef boost::shared_ptr< const DS301GroupConstPtr
 Shared pointer to a const DS301Group. More...
 
typedef boost::shared_ptr< DS301GroupPtr
 Shared pointer to a DS301Group. More...
 

Public Member Functions

virtual void acceptPPTargets (const int16_t node_id=-1)
 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 (const int16_t node_id=-1)
 When the device is in OperationEnabled mode, this function disables the drive motion. More...
 
virtual void configureHomingMethod (const int8_t homing_method, const int16_t node_id=-1)
 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, const int16_t node_id=-1)
 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 int16_t node_id=-1, const uint8_t interpolation_cycle_time_ms=20)
 Set the interpolation cycle time in milliseconds. If no time is given the default will be used. More...
 
virtual void disableNodes (const int16_t node_id=-1)
 Puts the device into STATE_SWITCHED_ON mode. If the device was in InterpolatedPositionMode, interpolation will be stopped here, as well. More...
 
 DS402Group (const std::string &name="")
 
virtual void enableNodes (const ds402::eModeOfOperation operation_mode=ds402::MOO_RESERVED_0, const int16_t node_id=-1)
 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...
 
virtual void getModeOfOperation (std::vector< ds402::eModeOfOperation > &modes)
 Gets a vector of the Mode of operation of all nodes within this group. More...
 
virtual void getTargetFeedback (std::vector< double > &feedback)
 Depending on the mode of operation, this will return the current position, velocity or torque. More...
 
virtual void home (const int16_t node_id=-1)
 Perform homing for nodes. More...
 
virtual void initNodes (const int16_t node_id=-1)
 Initializes the node. Tries to query all required data from the device. More...
 
virtual bool isModeSupported (const ds402::eModeOfOperation op_mode, const int16_t node_id=-1)
 Tests whether a given mode of operation is supported by the device. More...
 
virtual bool isTargetReached (std::vector< bool > &reached_single)
 Returns whether the device has reached it's recent target. More...
 
virtual void openBrakes (const int16_t node_id=-1)
 When the device is in OperationEnabled mode, this function enables the drive motion. More...
 
virtual void printStatus (const int16_t node_id=-1)
 Prints a stringified version of the statusword to the logging system. More...
 
virtual void quickStop (const int16_t node_id=-1)
 This sends the controlword for performing a quick_stop. More...
 
virtual bool resetFault (const int16_t node_id=-1)
 This function is used to recover from a fault state. More...
 
virtual void setDefaultPDOMapping (const DS402Node::eDefaultPDOMapping mapping, const int16_t node_id=-1)
 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...
 
virtual bool setModeOfOperation (const ds402::eModeOfOperation op_mode, const int16_t node_id=-1)
 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 bool setTarget (const std::vector< float > &targets)
 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...
 
virtual bool setTarget (const float target, const uint8_t node_id)
 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...
 
virtual void setupHomingMode (const ds402::HomingModeConfiguration &config, const int16_t node_id=-1)
 Configure the mandatory parameters for a homing mode. More...
 
virtual void setupProfilePositionMode (const ds402::ProfilePositionModeConfiguration &config, const int16_t node_id=-1)
 Configure the mandatory parameters for a profile position mode. More...
 
virtual void setupProfileTorqueMode (const ds402::ProfileTorqueModeConfiguration &config, const int16_t node_id=-1)
 Configure the mandatory parameters for a profile torque mode. More...
 
virtual void setupProfileVelocityMode (const ds402::ProfileVelocityModeConfiguration &config, const int16_t node_id=-1)
 Configure the mandatory parameters for a profile velocity mode. More...
 
virtual void startPPMovement (const int16_t node_id=-1)
 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...
 
- Public Member Functions inherited from icl_hardware::canopen_schunk::DS301Group
virtual void appendPDOMappingSingle (const PDO::MappingConfigurationList &config, const uint16_t pdo_nr, const PDO::eTransmissionType &transmission_type, const DS301Node::ePDO_TYPE &pdo_type, const bool dummy_mapping=false, const uint8_t cyclic_timeout_cycles=0, const int16_t node_id=-1)
 Appends one or more mapping parameters to the existing mapping. Note that the PDO will be disabled while appending another mapping. More...
 
virtual bool deleteNodeFromId (const uint8_t node_id)
 Deletes a node with a given node id from the node list, if it is present. If the node can't be found in this group, this function will return false;. More...
 
virtual void deleteNodes (std::vector< uint8_t > &deleted_ids)
 Deletes all nodes assigned to the group. More...
 
void downloadPDOs ()
 
 DS301Group (const std::string &name="")
 
std::string getName () const
 Returns the group's identifier string. More...
 
virtual std::vector< DS301Node::PtrgetNodes () const
 Returns the group's node vector. More...
 
virtual void initPDOMappingSingle (const PDO::MappingConfigurationList &config, const uint16_t pdo_nr, const PDO::eTransmissionType &transmission_type, const DS301Node::ePDO_TYPE &pdo_type, const bool dummy_mapping=false, const uint8_t cyclic_timeout_cycles=0, const int16_t node_id=-1)
 Init PDO mapping with a given mapping configuration for a given pdo nr. More...
 
void printPDOMapping (const uint8_t node_id=-1)
 Will query the PDO mapping from the device and print that to the output. More...
 
void registerWSBroadcaster (boost::shared_ptr< icl_comm::websocket::WsBroadcaster > broadcaster)
 registerWSBroadcaster Adds a debug interface More...
 
void uploadPDOs ()
 

Protected Member Functions

template<typename NodeT >
DS301Node::Ptr addNode (const uint8_t node_id, const CanDevPtr can_device, HeartBeatMonitor::Ptr heartbeat_monitor)
 Creates a new node and adds it to the group. More...
 
- Protected Member Functions inherited from icl_hardware::canopen_schunk::DS301Group
template<typename NodeT >
DS301Node::Ptr addNode (const uint8_t node_id, const CanDevPtr can_device, HeartBeatMonitor::Ptr heartbeat_monitor)
 Creates a new DS301Node and adds it to the group-. More...
 

Protected Attributes

std::vector< DS402Node::Ptrm_ds402_nodes
 
- Protected Attributes inherited from icl_hardware::canopen_schunk::DS301Group
std::string m_name
 
std::vector< DS301Node::Ptrm_nodes
 
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...
 

Friends

class CanOpenController
 

Detailed Description

The DS402Group class is the base class for canOpen devices implementing the DS402 device protocol (motors)

The DS402Group provides interfaces to a group of canOpen defices implementing the DS402 device profile. This includes mainly the management of the internal statemachine by NMT protocoll but also interfaces for inclusion into custom software such as setTarget or getStatus which can be uses for cyclic commandation of target positions (or other values if so desired) The DS402Group is intentionally kept generic in its interface as it is supposed to control various DS402 devices. If a more specific interface is required for the devices it is intended that the developer inherits from this class and implements further interfaces. By building on the DS301Group the most common functionalities of the canOpen protocol should be inherited

Definition at line 45 of file DS402Group.h.

Member Typedef Documentation

Shared pointer to a const DS402Group.

Definition at line 51 of file DS402Group.h.

Shared pointer to a DS402Group.

Definition at line 49 of file DS402Group.h.

Constructor & Destructor Documentation

icl_hardware::canopen_schunk::DS402Group::DS402Group ( const std::string &  name = "")

Definition at line 30 of file DS402Group.cpp.

Member Function Documentation

void icl_hardware::canopen_schunk::DS402Group::acceptPPTargets ( const int16_t  node_id = -1)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 120 of file DS402Group.cpp.

template<typename NodeT >
DS301Node::Ptr icl_hardware::canopen_schunk::DS402Group::addNode ( const uint8_t  node_id,
const CanDevPtr  can_device,
HeartBeatMonitor::Ptr  heartbeat_monitor 
)
protected

Creates a new node and adds it to the group.

Note
This method is protected, as new nodes should be added through the controller only (Which is why the controller is a friend class)
Parameters
node_idID of the new node
can_deviceShared pointer to the can device
Returns
shared pointer to the new DS301Node

Definition at line 31 of file DS402Group.hpp.

void icl_hardware::canopen_schunk::DS402Group::closeBrakes ( const int16_t  node_id = -1)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 424 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::configureHomingMethod ( const int8_t  homing_method,
const int16_t  node_id = -1 
)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.
homing_methodHoming method index that should be used

Definition at line 347 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::configureHomingSpeeds ( const uint32_t  low_speed,
const uint32_t  high_speed = 0,
const int16_t  node_id = -1 
)
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.

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 333 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::configureInterpolationCycleTime ( const int16_t  node_id = -1,
const uint8_t  interpolation_cycle_time_ms = 20 
)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.
interpolation_cycle_time_msInterpolation cycle time in milliseconds

Definition at line 319 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::disableNodes ( const int16_t  node_id = -1)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 383 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::enableNodes ( const ds402::eModeOfOperation  operation_mode = ds402::MOO_RESERVED_0,
const int16_t  node_id = -1 
)
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 (Which might be done in initialization already).
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 361 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::getModeOfOperation ( std::vector< ds402::eModeOfOperation > &  modes)
virtual

Gets a vector of the Mode of operation of all nodes within this group.

Parameters
[out]modesVector of all modes of operation in this group.
Note
: The order in this vector is the one, the nodes have been added to the group!

Definition at line 176 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::getTargetFeedback ( std::vector< double > &  feedback)
virtual

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

Parameters
[out]feedbackVector of target_feedback for all nodes in this group.
Note
The entries in this vector don't necessarily represent the same physical property, as nodes could be in different modes of operation.
: The order in this vector is the one, the nodes have been added to the group!

Definition at line 134 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::home ( const int16_t  node_id = -1)
virtual

Perform homing for nodes.

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 162 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::initNodes ( const int16_t  node_id = -1)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 35 of file DS402Group.cpp.

bool icl_hardware::canopen_schunk::DS402Group::isModeSupported ( const ds402::eModeOfOperation  op_mode,
const int16_t  node_id = -1 
)
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
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.
Returns
True if mode is supported by all nodes, false otherwise.

Definition at line 207 of file DS402Group.cpp.

bool icl_hardware::canopen_schunk::DS402Group::isTargetReached ( std::vector< bool > &  reached_single)
virtual

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

Parameters
[out]reached_singleBoolean vector that contains the taget-reached status for each node individually.
Returns
True, if current target is reached for all nodes, false otherwise

Definition at line 444 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::openBrakes ( const int16_t  node_id = -1)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 404 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::printStatus ( const int16_t  node_id = -1)
virtual

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

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 50 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::quickStop ( const int16_t  node_id = -1)
virtual

This sends the controlword for performing a quick_stop.

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 224 of file DS402Group.cpp.

bool icl_hardware::canopen_schunk::DS402Group::resetFault ( const int16_t  node_id = -1)
virtual

This function is used to recover from a fault state.

It clears the error register and performs state transition 15.

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 302 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::setDefaultPDOMapping ( const DS402Node::eDefaultPDOMapping  mapping,
const int16_t  node_id = -1 
)
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.
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 148 of file DS402Group.cpp.

bool icl_hardware::canopen_schunk::DS402Group::setModeOfOperation ( const ds402::eModeOfOperation  op_mode,
const int16_t  node_id = -1 
)
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.
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.
Returns
True if mode was successfully initialized for all nodes, false otherwise.

Definition at line 190 of file DS402Group.cpp.

bool icl_hardware::canopen_schunk::DS402Group::setTarget ( const std::vector< float > &  targets)
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
targetsVector of targets for all nodes value for current mode of operation
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.
Returns
True if target could be set for all nodes, false otherwise

Definition at line 81 of file DS402Group.cpp.

bool icl_hardware::canopen_schunk::DS402Group::setTarget ( const float  target,
const uint8_t  node_id 
)
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
node_idNode-ID of the node this target should be applied to
Returns
True if target could be set, false otherwise

Definition at line 64 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::setupHomingMode ( const ds402::HomingModeConfiguration config,
const int16_t  node_id = -1 
)
virtual

Configure the mandatory parameters for a homing mode.

Parameters
configStruct of mandatory parameters for a homing mode
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 260 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::setupProfilePositionMode ( const ds402::ProfilePositionModeConfiguration config,
const int16_t  node_id = -1 
)
virtual

Configure the mandatory parameters for a profile position mode.

Parameters
configStruct of parameters used for profile position mode
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 246 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::setupProfileTorqueMode ( const ds402::ProfileTorqueModeConfiguration config,
const int16_t  node_id = -1 
)
virtual

Configure the mandatory parameters for a profile torque mode.

Parameters
configStruct of mandatory parameters for a profile torque mode
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 288 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::setupProfileVelocityMode ( const ds402::ProfileVelocityModeConfiguration config,
const int16_t  node_id = -1 
)
virtual

Configure the mandatory parameters for a profile velocity mode.

Parameters
configStruct of mandatory parameters for a profile velocity mode
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 274 of file DS402Group.cpp.

void icl_hardware::canopen_schunk::DS402Group::startPPMovement ( const int16_t  node_id = -1)
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.

Parameters
node_idIf left out or given a negative value, the function will be called for all nodes in the group, otherwise it will only be used for the given node-id.

Definition at line 106 of file DS402Group.cpp.

Friends And Related Function Documentation

friend class CanOpenController
friend

Definition at line 329 of file DS402Group.h.

Member Data Documentation

std::vector<DS402Node::Ptr> icl_hardware::canopen_schunk::DS402Group::m_ds402_nodes
protected

Definition at line 326 of file DS402Group.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