Class that holds devices according to the DS402 (drives and motion control) specification. More...
#include <DS402Node.h>
Public Types | |
typedef boost::shared_ptr < const DS402Node > | ConstPtr |
Shared pointer to a const DS402Node. | |
enum | eDefaultPDOMapping { PDO_MAPPING_CONTROLWORD_STATUSWORD, PDO_MAPPING_INTERPOLATED_POSITION_MODE, PDO_MAPPING_PROFILE_POSITION_MODE } |
typedef boost::shared_ptr < DS402Node > | Ptr |
Shared pointer to a DS402Node. | |
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. | |
virtual void | closeBrakes () |
When the device is in OperationEnabled mode, this function disable the drive motion. | |
virtual void | configureHomingMethod (const int8_t homing_method) |
Set the device's homing method through an SDO (OD 0x6098) | |
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. | |
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. | |
virtual void | disableNode () |
Puts the device into STATE_SWITCHED_ON mode. If the device was in InterpolatedPositionMode, interpolation will be stopped here, as well. | |
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. | |
size_t | getMaximumNumberOfStateTransitions () const |
ds402::eModeOfOperation | getModeOfOperation () const |
Get the current mode of operation. | |
virtual ds402::Statusword | getStatus () |
virtual double | getTargetFeedback () |
Depending on the mode of operation, this will return the current position, velocity or torque. | |
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. | |
virtual void | home () |
Perform homing for this node. | |
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. | |
virtual void | initNode () |
Initializes the node. Tries to query all required data from the device. | |
virtual bool | isModeSupported (const ds402::eModeOfOperation op_mode) |
Tests whether a given mode of operation is supported by the device. | |
virtual bool | isTargetReached () |
Returns whether the device has reached it's recent target. | |
virtual void | openBrakes () |
When the device is in OperationEnabled mode, this function enables the drive motion. | |
virtual void | printStatus () |
Prints a stringified version of the statusword to the logging system. | |
void | printSupportedModesOfOperation () |
Prints out all Modes on which the device claims to be able to operate on. | |
virtual void | querySupportedDeviceModes () |
Uploads all supported modes of operation from the device. and stores them in the m_supported_modes member. | |
virtual void | quickStop () |
This sends the controlword for performing a quick_stop. | |
virtual bool | resetFault () |
This function is used to recover from a fault state. | |
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. | |
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. | |
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. | |
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. | |
virtual void | setupHomingMode (const ds402::HomingModeConfiguration &config) |
Configure the mandatory parameters for a homing mode. | |
virtual void | setupProfilePositionMode (const ds402::ProfilePositionModeConfiguration &config) |
Configure the mandatory parameters for a profile position mode. | |
virtual void | setupProfileTorqueMode (const ds402::ProfileTorqueModeConfiguration &config) |
Configure the mandatory parameters for a profile torque mode. | |
virtual void | setupProfileVelocityMode (const ds402::ProfileVelocityModeConfiguration &config) |
Configure the mandatory parameters for a profile velocity mode. | |
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. | |
virtual void | stopNode () |
This redefines the basic stopNode function. | |
Protected Member Functions | |
void | configureHomingAcceleration (const uint32_t acceleration) |
Set the device's homing acceleration through an SDO (OD 0x609A) | |
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. | |
void | configureMaxAcceleration (const uint32_t acceleration) |
Set the device's maximum acceleration through an SDO (OD 0x60c5) | |
void | configureMaxDeceleration (const uint32_t deceleration) |
Set the device's maximum deceleration through an SDO (OD 0x60c6) | |
void | configureMotionProfileType (const int16_t motion_type) |
Set the device's motion profile type through an SDO (OD 0x6086) | |
void | configureProfileAcceleration (const uint32_t acceleration) |
Set the device's profile acceleration through an SDO (OD 0x6083) | |
void | configureProfileDeceleration (const uint32_t deceleration) |
Set the device's profile deceleration through an SDO (OD 0x6084) | |
void | configureProfileVelocity (const uint32_t velocity) |
Set the device's profile velocity through an SDO (OD 0x6081) | |
void | configureQuickStopDeceleration (const uint32_t deceleration) |
Set the device's quick stop deceleration through an SDO (OD 0x6085) | |
void | configureSensorSelectionCode (const int16_t sensor_selection_code) |
Set the device's sensor selection code through an SDO (OD 0x606a) | |
void | configureTorqueProfileType (const int16_t torque_profile_type) |
Set the device's torque profile type through an SDO (OD 0x6088) | |
void | configureTorqueSlope (const uint32_t torque_slope) |
Set the device's torque slope through an SDO (OD 0x6087) | |
void | doDS402StateTransition (const ds402::eStateTransission transition) |
Performs a state transition in the DS402 state machine. | |
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. | |
std::string | operationModeSpecificStatus (const ds402::Statusword &statusword) |
This function queries the two operation mode specific bits and turns them to a human-readable string. | |
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. | |
size_t | m_max_number_of_state_transitions |
ds402::eModeOfOperation | m_op_mode |
The mode of operation of this device. | |
ds402::ProfilePositionModeConfiguration | m_ppm_config |
ds402::SupportedDriveModes | m_supported_modes |
supported modes of operation | |
double | m_transmission_factor |
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.
typedef boost::shared_ptr<const DS402Node> icl_hardware::canopen_schunk::DS402Node::ConstPtr |
Shared pointer to a const DS402Node.
Reimplemented from icl_hardware::canopen_schunk::DS301Node.
Reimplemented in icl_hardware::canopen_schunk::SchunkPowerBallNode.
Definition at line 49 of file DS402Node.h.
typedef boost::shared_ptr<DS402Node> icl_hardware::canopen_schunk::DS402Node::Ptr |
Shared pointer to a DS402Node.
Reimplemented from icl_hardware::canopen_schunk::DS301Node.
Reimplemented in icl_hardware::canopen_schunk::SchunkPowerBallNode.
Definition at line 47 of file DS402Node.h.
PDO_MAPPING_CONTROLWORD_STATUSWORD | |
PDO_MAPPING_INTERPOLATED_POSITION_MODE | |
PDO_MAPPING_PROFILE_POSITION_MODE |
Definition at line 51 of file DS402Node.h.
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.
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.
interpolation_cycle_time_ms | Interpolation 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 |
||
) | [protected, virtual] |
Configure the buffer for the interpolated position mode.
buffer_organization | 0: FIFO buffer, 1: Ring buffer |
interpolation_type | Type of interpolation
|
size_of_data_record | Size 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.
transition | Transition that should be performed |
ProtocolException | on 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.
operation_mode | DS402 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.
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.
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.
requested_state | Target state |
DeviceException | if 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.
op_mode | Mode of operation that should be checked |
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.
Definition at line 1159 of file DS402Node.cpp.
void icl_hardware::canopen_schunk::DS402Node::onStatusWordUpdate | ( | ) | [protected, virtual] |
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.
statusword | the statusword |
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.
Prints out all Modes on which the device claims to be able to operate on.
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.
mapping | Mapping 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.
op_mode | Operation mode according to ds402::eModeOfOperation. |
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
target | Target value for current mode of operation |
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.
config | Struct 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.
config | Struct 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.
config | Struct 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.
config | Struct 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.
Definition at line 388 of file DS402Node.h.
Definition at line 389 of file DS402Node.h.
Definition at line 398 of file DS402Node.h.
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.
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.
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.