34 namespace canopen_schunk {
73 virtual bool setTarget (
const float target );
356 const int16_t interpolation_type = 0,
357 const uint8_t size_of_data_record = 4);
404 #endif // DS402NODE_H 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.
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...
void setTransmissionFactor(const double transmission_factor)
The Transmission factor is used for converting radiant units into device ticks. By default it's value...
void configureMotionProfileType(const int16_t motion_type)
Set the device's motion profile type through an SDO (OD 0x6086)
double m_transmission_factor
Configuration parameters for a Profile_Position_Mode according to CiA DSP-402 V1.1 section 12...
std::string operationModeSpecificStatus(const ds402::Statusword &statusword)
This function queries the two operation mode specific bits and turns them to a human-readable string...
virtual bool isTargetReached()
Returns whether the device has reached it's recent target.
ds402::eModeOfOperation getModeOfOperation() const
Get the current mode of operation.
virtual void setupProfileTorqueMode(const ds402::ProfileTorqueModeConfiguration &config)
Configure the mandatory parameters for a profile torque mode.
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 i...
void doDS402StateTransition(const ds402::eStateTransission transition)
Performs a state transition in the DS402 state machine.
virtual void closeBrakes()
When the device is in OperationEnabled mode, this function disable the drive motion.
virtual void initNode()
Initializes the node. Tries to query all required data from the device.
void configureTorqueSlope(const uint32_t torque_slope)
Set the device's torque slope through an SDO (OD 0x6087)
void configureProfileAcceleration(const uint32_t acceleration)
Set the device's profile acceleration through an SDO (OD 0x6083)
virtual bool resetFault()
This function is used to recover from a fault state.
data union for access to DSP 402 6041 statusword,
eNMT_SubState
The NMT Substate is only used during initialization of a device. Meaning the substates are only usefu...
uint8_t m_interpolation_cycle_time_ms
Cycle time of interpolation mode.
Configuration parameters for a Profile_Velocity_Mode according to CiA DSP-402 V1.1 section 16...
void configureHomingAcceleration(const uint32_t acceleration)
Set the device's homing acceleration through an SDO (OD 0x609A)
virtual void querySupportedDeviceModes()
Uploads all supported modes of operation from the device. and stores them in the m_supported_modes me...
void setMaximumNumberOfStateTransitions(const size_t max_number_of_state_transitions)
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 ta...
double getTransmissionFactor() const
The Transmission factor is used for converting radiant units into device ticks. By default it's value...
void printSupportedModesOfOperation()
Prints out all Modes on which the device claims to be able to operate on.
void configureProfileVelocity(const uint32_t velocity)
Set the device's profile velocity through an SDO (OD 0x6081)
ds402::ProfilePositionModeConfiguration m_ppm_config
virtual void startPPMovement()
This sets the RPDO communication for enabling the movement after a target has been set...
void configureSensorSelectionCode(const int16_t sensor_selection_code)
Set the device's sensor selection code through an SDO (OD 0x606a)
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...
virtual void home()
Perform homing for this node.
virtual void openBrakes()
When the device is in OperationEnabled mode, this function enables the drive motion.
void configureMaxDeceleration(const uint32_t deceleration)
Set the device's maximum deceleration through an SDO (OD 0x60c6)
boost::shared_ptr< DS402Node > Ptr
Shared pointer to a DS402Node.
virtual bool isModeSupported(const ds402::eModeOfOperation op_mode)
Tests whether a given mode of operation is supported by the device.
DS402Node(const uint8_t node_id, const icl_hardware::canopen_schunk::CanDevPtr &can_device, HeartBeatMonitor::Ptr heartbeat_monitor)
ds402::SupportedDriveModes m_supported_modes
supported modes of operation
virtual void disableNode()
Puts the device into STATE_SWITCHED_ON mode. If the device was in InterpolatedPositionMode, interpolation will be stopped here, as well.
void configureQuickStopDeceleration(const uint32_t deceleration)
Set the device's quick stop deceleration through an SDO (OD 0x6085)
virtual void setDefaultPDOMapping(const eDefaultPDOMapping mapping)
Choose one of the predefined default mappings. Please see the enum eDefaultPDOMapping for a list of a...
virtual void onStatusWordUpdate()
This will be called when a new statusword PDO comes in. If the device's state differs from the one ex...
virtual void printStatus()
Prints a stringified version of the statusword to the logging system.
virtual void configureHomingMethod(const int8_t homing_method)
Set the device's homing method through an SDO (OD 0x6098)
size_t getMaximumNumberOfStateTransitions() const
virtual void stopNode()
This redefines the basic stopNode function.
Configuration parameters for a Profile_Torque_Mode according to CiA DSP-402 V1.1 section 17...
void configureTorqueProfileType(const int16_t torque_profile_type)
Set the device's torque profile type through an SDO (OD 0x6088)
virtual void acceptPPTargets()
After enabling PP movement, this enables accepting new targets again. Remember to sync all nodes and ...
virtual void setupHomingMode(const ds402::HomingModeConfiguration &config)
Configure the mandatory parameters for a homing mode.
boost::shared_ptr< const DS402Node > ConstPtr
Shared pointer to a const DS402Node.
void configureProfileDeceleration(const uint32_t deceleration)
Set the device's profile deceleration through an SDO (OD 0x6084)
eState
DS402 states as described in Figure 6.3 in ELMO DS402 implementation guide V1.000.
virtual void setupProfileVelocityMode(const ds402::ProfileVelocityModeConfiguration &config)
Configure the mandatory parameters for a profile velocity mode.
virtual bool setModeOfOperation(const ds402::eModeOfOperation op_mode)
Sets and initializes a mode of operation. First it will check whether the device supports the request...
virtual void quickStop()
This sends the controlword for performing a quick_stop.
ds402::eModeOfOperation m_op_mode
The mode of operation of this device.
virtual void setNMTState(const NMT::eNMT_State state, const NMT::eNMT_SubState sub_state)
eNMT_State
The NMT state indicates the behavior of the communication of a device, everything else is device spec...
size_t m_max_number_of_state_transitions
void configureMaxAcceleration(const uint32_t acceleration)
Set the device's maximum acceleration through an SDO (OD 0x60c5)
virtual ds402::Statusword getStatus()
ds402::eState m_expected_ds402_state
data union for access to DSP 402 6041 statusword,
virtual void setupProfilePositionMode(const ds402::ProfilePositionModeConfiguration &config)
Configure the mandatory parameters for a profile position mode.
Class that holds devices according to the DS402 (drives and motion control) specification.
virtual double getTargetFeedback()
Depending on the mode of operation, this will return the current position, velocity or torque...
The DS301Node class Is the base class representation of canOpen devices. It is the access point to th...
ds402::eState m_current_ds402_state
virtual bool setTarget(const float target)
Sets the target for the motor. What that target is, depends on the selected mode of operation...
Configuration parameters for a Homing_Mode according to CiA DSP-402 V1.1 section 13.2.1.