RPDO.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 // -- BEGIN LICENSE BLOCK ----------------------------------------------
3 // This file is part of the SCHUNK Canopen Driver suite.
4 //
5 // This program is free software licensed under the LGPL
6 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
7 // You can find a copy of this license in LICENSE folder in the top
8 // directory of the source code.
9 //
10 // © Copyright 2016 SCHUNK GmbH, Lauffen/Neckar Germany
11 // © Copyright 2016 FZI Forschungszentrum Informatik, Karlsruhe, Germany
12 // -- END LICENSE BLOCK ------------------------------------------------
13 //----------------------------------------------------------------------
20 //----------------------------------------------------------------------
21 
22 #ifndef RPDO_H
23 #define RPDO_H
24 
25 #include "PDO.h"
26 
27 namespace icl_hardware {
28 namespace canopen_schunk {
29 
33 class RPDO : public PDO
34 {
35 public:
39  typedef std::vector<boost::shared_ptr<RPDO> > PtrList;
40 
41  static const uint16_t OD_RPDO_COMMUNICATION_MIN = 0x1400;
42  static const uint16_t OD_RPDO_MAPPING_PARAMETER_MIN = 0x1600;
43 
51  RPDO(const uint8_t node_id, const uint8_t pdo_nr, const CanDevPtr& can_device);
52 
59  bool download();
60 
61 
84  const MappingConfigurationList& mappings,
85  const eTransmissionType& transmission_type,
86  const bool dummy_mapping = false,
87  const uint8_t cyclic_timeout_cycles = 0
88  );
89 
111  const MappingConfigurationList& mappings,
112  const eTransmissionType& transmission_type,
113  const bool dummy_mapping = false,
114  const uint8_t cyclic_timeout_cycles = 0
115  );
116 };
117 
118 }} // end of NS
119 
120 #endif // RPDO_H
bool download()
Downloads RPDO data from the master to the slave (From PC to node)
Definition: RPDO.cpp:39
std::vector< MappingConfiguration > MappingConfigurationList
The MappingConfigurationList holds multiple Mapping configurations. The Mapping of a single PDO is de...
Definition: PDO.h:70
This class describes Receive PDOs, meaning PDOs that send data from the host to the device...
Definition: RPDO.h:33
eTransmissionType
Transmission types of a PDO, needed when mapping PDOs.
Definition: PDO.h:122
static const uint16_t OD_RPDO_COMMUNICATION_MIN
Definition: RPDO.h:41
unsigned char uint8_t
boost::shared_ptr< RPDO > Ptr
Convenience typedef to use PDOs with shared pointers.
Definition: RPDO.h:37
static const uint16_t OD_RPDO_MAPPING_PARAMETER_MIN
Definition: RPDO.h:42
PDOStringMatchVec remap(SDO &sdo, const MappingConfigurationList &mappings, const eTransmissionType &transmission_type, const bool dummy_mapping=false, const uint8_t cyclic_timeout_cycles=0)
Configure a PDO by sending some SDO packages. This can be either done during NMT state pre-operationa...
Definition: RPDO.cpp:77
std::vector< boost::shared_ptr< RPDO > > PtrList
Convenience typedef to use PDO lists with shared pointers.
Definition: RPDO.h:39
std::vector< PDOStringMatch > PDOStringMatchVec
Definition: PDO.h:119
The PDO class provides access to one (of the possible multiple) Process Data Object of a canOpen node...
Definition: PDO.h:44
The SDO class represents Service Data Objects (SDO) that are used for slow access of the canOpen obje...
Definition: SDO.h:40
RPDO(const uint8_t node_id, const uint8_t pdo_nr, const CanDevPtr &can_device)
Construct a new RPDO.
Definition: RPDO.cpp:33
unsigned short uint16_t
PDOStringMatchVec appendMapping(SDO &sdo, const MappingConfigurationList &mappings, const eTransmissionType &transmission_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 wh...
Definition: RPDO.cpp:99


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