TPDO.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 TPDO_H
23 #define TPDO_H
24 
25 #include "PDO.h"
26 
27 namespace icl_hardware {
28 namespace canopen_schunk {
29 
33 class TPDO : public PDO
34 {
35 public:
39  typedef std::vector<boost::shared_ptr<TPDO> > PtrList;
40 
41  static const uint16_t OD_TPDO_COMMUNICATION_MIN = 0x1800;
42  static const uint16_t OD_TPDO_MAPPING_PARAMETER_MIN = 0x1A00;
43 
51  TPDO(const uint8_t node_id, const uint8_t pdo_nr, const CanDevPtr& can_device);
52 
57  void update(const CanMsg& msg);
58 
64  void upload ();
65 
88  const MappingConfigurationList& mappings,
89  const eTransmissionType& transmission_type,
90  const bool dummy_mapping = false,
91  const uint8_t cyclic_timeout_cycles = 0);
92 
114  const MappingConfigurationList& mappings,
115  const eTransmissionType& transmission_type,
116  const bool dummy_mapping = false,
117  const uint8_t cyclic_timeout_cycles = 0);
118 
124  void registerNotifyCallback (const boost::function <void()>& f);
125 
126 private:
127  std::vector<boost::function <void()> > m_notify_callbacks;
128 
129  boost::mutex m_data_buffer_mutex;
132  std::vector<uint8_t> m_data_buffer;
133 };
134 
135 
136 }} // end of NS
137 #endif // TPDO_H
void update(const CanMsg &msg)
update updates the TPDO data with newly received messages
Definition: TPDO.cpp:37
static const uint16_t OD_TPDO_COMMUNICATION_MIN
Definition: TPDO.h:41
std::vector< MappingConfiguration > MappingConfigurationList
The MappingConfigurationList holds multiple Mapping configurations. The Mapping of a single PDO is de...
Definition: PDO.h:70
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: TPDO.cpp:84
void upload()
Upload data from the slave to the master (Node to PC)
Definition: TPDO.cpp:76
std::vector< boost::function< void()> > m_notify_callbacks
Definition: TPDO.h:127
boost::shared_ptr< TPDO > Ptr
Convenience typedef to use PDOs with shared pointers.
Definition: TPDO.h:37
static const uint16_t OD_TPDO_MAPPING_PARAMETER_MIN
Definition: TPDO.h:42
std::vector< boost::shared_ptr< TPDO > > PtrList
Convenience typedef to use PDO lists with shared pointers.
Definition: TPDO.h:39
void registerNotifyCallback(const boost::function< void()> &f)
Register a notification callback function for incoming PDO messages.
Definition: TPDO.cpp:125
eTransmissionType
Transmission types of a PDO, needed when mapping PDOs.
Definition: PDO.h:122
unsigned char uint8_t
This class describes Transmit PDOs, meaning PDOs that send data from the device to the host...
Definition: TPDO.h:33
TPDO(const uint8_t node_id, const uint8_t pdo_nr, const CanDevPtr &can_device)
Construct a new TPDO.
Definition: TPDO.cpp:31
boost::mutex m_data_buffer_mutex
Definition: TPDO.h:129
std::vector< PDOStringMatch > PDOStringMatchVec
Definition: PDO.h:119
std::vector< uint8_t > m_data_buffer
Definition: TPDO.h:132
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: TPDO.cpp:104
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
boost::condition_variable m_data_buffer_updated_cond
Definition: TPDO.h:130
unsigned short uint16_t


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