DS402Group.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // This file is part of the SCHUNK Canopen Driver suite.
5 //
6 // This program is free software licensed under the LGPL
7 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
8 // You can find a copy of this license in LICENSE folder in the top
9 // directory of the source code.
10 //
11 // © Copyright 2016 SCHUNK GmbH, Lauffen/Neckar Germany
12 // © Copyright 2016 FZI Forschungszentrum Informatik, Karlsruhe, Germany
13 // -- END LICENSE BLOCK ------------------------------------------------
14 
15 //----------------------------------------------------------------------
23 //----------------------------------------------------------------------
24 
25 #ifndef DS402GROUP_H
26 #define DS402GROUP_H
27 
28 #include "DS301Group.h"
29 #include "DS402Node.h"
30 
31 
32 namespace icl_hardware {
33 namespace canopen_schunk {
34 
45 class DS402Group : public DS301Group
46 {
47 public:
52 
53  DS402Group(const std::string& name = "");
54 
61  virtual void initNodes(const int16_t node_id = -1);
62 
69  virtual void printStatus(const int16_t node_id = -1);
70 
84  virtual bool setTarget ( const std::vector<float>& targets );
85 
94  virtual void startPPMovement (const int16_t node_id = -1);
95 
103  virtual void acceptPPTargets (const int16_t node_id = -1);
104 
117  virtual bool setTarget ( const float target, const uint8_t node_id );
118 
128  virtual void getTargetFeedback(std::vector<double>& feedback);
129 
138  virtual void setDefaultPDOMapping (const DS402Node::eDefaultPDOMapping mapping, const int16_t node_id = -1);
139 
146  virtual void home(const int16_t node_id = -1);
147 
154  virtual void getModeOfOperation (std::vector<ds402::eModeOfOperation>& modes);
155 
167  virtual bool setModeOfOperation (const ds402::eModeOfOperation op_mode, const int16_t node_id = -1);
168 
179  virtual bool isModeSupported (const ds402::eModeOfOperation op_mode, const int16_t node_id = -1);
180 
187  virtual void quickStop (const int16_t node_id = -1);
188 
189 
197  virtual void setupProfilePositionMode (const ds402::ProfilePositionModeConfiguration& config, const int16_t node_id = -1);
198 
206  virtual void setupHomingMode (const ds402::HomingModeConfiguration& config, const int16_t node_id = -1);
207 
215  virtual void setupProfileVelocityMode (const ds402::ProfileVelocityModeConfiguration& config, const int16_t node_id = -1);
216 
224  virtual void setupProfileTorqueMode (const ds402::ProfileTorqueModeConfiguration& config, const int16_t node_id = -1);
225 
234  virtual bool resetFault (const int16_t node_id = -1);
235 
243  virtual void configureInterpolationCycleTime (const int16_t node_id = -1, const uint8_t interpolation_cycle_time_ms = 20);
244 
252  virtual void configureHomingMethod ( const int8_t homing_method, const int16_t node_id = -1);
253 
262  virtual void configureHomingSpeeds (const uint32_t low_speed, const uint32_t high_speed = 0, const int16_t node_id = -1);
263 
274  virtual void enableNodes (const ds402::eModeOfOperation operation_mode = ds402::MOO_RESERVED_0,
275  const int16_t node_id = -1);
276 
284  virtual void disableNodes (const int16_t node_id = -1);
285 
292  virtual void openBrakes (const int16_t node_id = -1);
293 
300  virtual void closeBrakes (const int16_t node_id = -1);
301 
310  virtual bool isTargetReached (std::vector<bool>& reached_single);
311 
312 protected:
323  template <typename NodeT>
324  DS301Node::Ptr addNode(const uint8_t node_id, const CanDevPtr can_device, HeartBeatMonitor::Ptr heartbeat_monitor);
325 
326  std::vector<DS402Node::Ptr> m_ds402_nodes;
327 
328  // the add-node method should be callable from the controller
329  friend class CanOpenController;
330 
331 };
332 
333 }}// end of NS
334 
335 // include template implementations
336 #include "DS402Group.hpp"
337 
338 #endif // DS402GROUP_H
std::vector< DS402Node::Ptr > m_ds402_nodes
Definition: DS402Group.h:326
unsigned int uint32_t
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...
Definition: DS402Group.cpp:333
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 a...
Definition: DS402Group.cpp:148
Configuration parameters for a Profile_Position_Mode according to CiA DSP-402 V1.1 section 12...
Definition: ds402.h:169
virtual void setupHomingMode(const ds402::HomingModeConfiguration &config, const int16_t node_id=-1)
Configure the mandatory parameters for a homing mode.
Definition: DS402Group.cpp:260
boost::shared_ptr< const DS402Group > ConstPtr
Shared pointer to a const DS402Group.
Definition: DS402Group.h:51
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.
Definition: DS402Group.hpp:31
signed char int8_t
virtual void getTargetFeedback(std::vector< double > &feedback)
Depending on the mode of operation, this will return the current position, velocity or torque...
Definition: DS402Group.cpp:134
Configuration parameters for a Profile_Velocity_Mode according to CiA DSP-402 V1.1 section 16...
Definition: ds402.h:246
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...
Definition: DS402Group.cpp:81
virtual void getModeOfOperation(std::vector< ds402::eModeOfOperation > &modes)
Gets a vector of the Mode of operation of all nodes within this group.
Definition: DS402Group.cpp:176
The DS301Group class is the base Class for all canOpen device groups, providing basic interfaces to t...
Definition: DS301Group.h:41
The DS402Group class is the base class for canOpen devices implementing the DS402 device protocol (mo...
Definition: DS402Group.h:45
virtual void openBrakes(const int16_t node_id=-1)
When the device is in OperationEnabled mode, this function enables the drive motion.
Definition: DS402Group.cpp:404
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.
Definition: DS402Group.cpp:207
virtual void startPPMovement(const int16_t node_id=-1)
This sets the RPDO communication for enabling the movement after a target has been set...
Definition: DS402Group.cpp:106
The CanOpenController class is the main entry point for any calls to the canOpen System.
unsigned char uint8_t
virtual void printStatus(const int16_t node_id=-1)
Prints a stringified version of the statusword to the logging system.
Definition: DS402Group.cpp:50
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 i...
Definition: DS402Group.cpp:361
virtual void setupProfilePositionMode(const ds402::ProfilePositionModeConfiguration &config, const int16_t node_id=-1)
Configure the mandatory parameters for a profile position mode.
Definition: DS402Group.cpp:246
virtual bool resetFault(const int16_t node_id=-1)
This function is used to recover from a fault state.
Definition: DS402Group.cpp:302
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 ...
Definition: DS402Group.cpp:120
virtual void setupProfileVelocityMode(const ds402::ProfileVelocityModeConfiguration &config, const int16_t node_id=-1)
Configure the mandatory parameters for a profile velocity mode.
Definition: DS402Group.cpp:274
virtual void initNodes(const int16_t node_id=-1)
Initializes the node. Tries to query all required data from the device.
Definition: DS402Group.cpp:35
virtual void home(const int16_t node_id=-1)
Perform homing for nodes.
Definition: DS402Group.cpp:162
boost::shared_ptr< DS402Group > Ptr
Shared pointer to a DS402Group.
Definition: DS402Group.h:49
virtual bool isTargetReached(std::vector< bool > &reached_single)
Returns whether the device has reached it&#39;s recent target.
Definition: DS402Group.cpp:444
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 request...
Definition: DS402Group.cpp:190
Configuration parameters for a Profile_Torque_Mode according to CiA DSP-402 V1.1 section 17...
Definition: ds402.h:261
virtual void setupProfileTorqueMode(const ds402::ProfileTorqueModeConfiguration &config, const int16_t node_id=-1)
Configure the mandatory parameters for a profile torque mode.
Definition: DS402Group.cpp:288
signed short int16_t
virtual void closeBrakes(const int16_t node_id=-1)
When the device is in OperationEnabled mode, this function disables the drive motion.
Definition: DS402Group.cpp:424
virtual void quickStop(const int16_t node_id=-1)
This sends the controlword for performing a quick_stop.
Definition: DS402Group.cpp:224
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...
Definition: DS402Group.cpp:319
virtual void configureHomingMethod(const int8_t homing_method, const int16_t node_id=-1)
Set the device&#39;s homing method through an SDO (OD 0x6098)
Definition: DS402Group.cpp:347
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.
Definition: DS402Group.cpp:383
DS402Group(const std::string &name="")
Definition: DS402Group.cpp:30
Configuration parameters for a Homing_Mode according to CiA DSP-402 V1.1 section 13.2.1.
Definition: ds402.h:229


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