KaCanOpen
 All Classes Functions Variables Typedefs Enumerations Pages
Public Types | Public Member Functions | List of all members
kaco::Device Class Reference

This class represents a CanOpen slave device in the network. More...

#include <device.h>

Public Types

using Operation = std::function< Value(Device &, const Value &)>
 Type of a operation. See Profiles::Operation in profiles.h.
 

Public Member Functions

 Device (Core &core, uint8_t node_id)
 Constructor. More...
 
 Device (const Device &)=delete
 Copy constructor deleted because of callbacks with self-references.
 
 Device (Device &&)=delete
 Move constructor deleted because of callbacks with self-references.
 
 ~Device ()
 Destructor. More...
 
uint8_t get_node_id () const
 Returns the node ID of the device. More...
 
(1) Methods which manipulate the dictionary structure
void start ()
 Starts the node via NMT protocol and loads mandatory entries, operations, and constants. More...
 
std::string load_dictionary_from_library ()
 Tries to load the most specific EDS file available in KaCanOpen's internal EDS library. This is either device specific, CiA profile specific, or mandatory CiA 301. More...
 
void load_dictionary_from_eds (const std::string &path)
 Loads the dictionary from a custom EDS file. More...
 
bool load_operations ()
 Loads convenience operations associated with the device profile. More...
 
void add_operation (const std::string &coperation_name, const Operation &operation)
 Adds a convenience operation.
 
bool load_constants ()
 Loads constants associated with the device profile. More...
 
void add_constant (const std::string &constant_name, const Value &constant)
 Adds a constant.
 
(2) Methods which access dictionary entries
bool has_entry (const std::string &entry_name)
 Returns true if the entry is contained in the device dictionary. More...
 
bool has_entry (const uint16_t index, const uint8_t subindex=0)
 Returns true if the entry is contained in the device dictionary. More...
 
Type get_entry_type (const std::string &entry_name)
 Returns the type of a dictionary entry identified by name as it is defined in the local dictionary. More...
 
Type get_entry_type (const uint16_t index, const uint8_t subindex=0)
 Returns the type of a dictionary entry identified by name as it is defined in the local dictionary. More...
 
const Valueget_entry (const std::string &entry_name, const ReadAccessMethod access_method=ReadAccessMethod::use_default)
 Gets the value of a dictionary entry by name internally. If there is no cached value or the entry is configured to send an SDO on request, the new value is fetched from the device via SDO. Otherwise it returns the cached value. This makes sense, if a Reveive PDO is configured on the corresponding entry. More...
 
const Valueget_entry (const uint16_t index, const uint8_t subindex=0, const ReadAccessMethod access_method=ReadAccessMethod::use_default)
 Gets the value of a dictionary entry by name internally. If there is no cached value or the entry is configured to send an SDO on request, the new value is fetched from the device via SDO. Otherwise it returns the cached value. This makes sense, if a Reveive PDO is configured on the corresponding entry. More...
 
void set_entry (const std::string &entry_name, const Value &value, const WriteAccessMethod access_method=WriteAccessMethod::use_default)
 Sets the value of a dictionary entry by name internally. If the entry is configured to send an SDO on update, the new value is also sent to the device via SDO. If a PDO is configured on the corresponding entry, it will from now on use the new value stored internally. More...
 
void set_entry (const uint16_t index, const uint8_t subindex, const Value &value, const WriteAccessMethod access_method=WriteAccessMethod::use_default)
 Sets the value of a dictionary entry by name internally. If the entry is configured to send an SDO on update, the new value is also sent to the device via SDO. If a PDO is configured on the corresponding entry, it will from now on use the new value stored internally. More...
 
void add_entry (const uint16_t index, const uint8_t subindex, const std::string &name, const Type type, const AccessType access_type)
 Adds an entry to the dictionary. You have to take care that exactly this entry exists on the device for yourself! More...
 
uint16_t get_device_profile_number ()
 Returns the CiA profile number. More...
 
Value execute (const std::string &operation_name, const Value &argument=m_dummy_value)
 Executes a convenience operation. It must exist due to a previous load_operations() or add_operation() call. More...
 
const Valueget_constant (const std::string &constant_name) const
 Returns a constant. It must exist due to a previous load_constants() or add_constant() call. More...
 
void add_receive_pdo_mapping (uint16_t cob_id, const std::string &entry_name, uint8_t offset)
 Adds a receive PDO mapping. This means values sent by the device via PDO are saved into the dictionary cache. More...
 
void add_transmit_pdo_mapping (uint16_t cob_id, const std::vector< Mapping > &mappings, TransmissionType transmission_type=TransmissionType::ON_CHANGE, std::chrono::milliseconds repeat_time=std::chrono::milliseconds(0))
 Adds a transmit PDO mapping. This means values from the dictionary cache are sent to the device. More...
 
void print_dictionary () const
 Prints the dictionary together with currently cached values to command line.
 
void read_complete_dictionary ()
 Fetches all dictionary entries from the device. Afterwards, all values exist in cache and can for example be printed via print_dictionary().
 

Detailed Description

This class represents a CanOpen slave device in the network.

It provides easy access to it's object dictionary entries via addesses or names. There is a locally cached version of the device's object dictionary. This allows for dynamically mapping entries to transmit and receive PDOs. This abstracts away the underlaying communication method when manipulating the dictionary. The device object must know the structure of the slave's dictionary for these features, however, it can be fetched automatically from an EDS file or from KaCanOpen's EDS library.

Call print_dictionary() if you want to know which entries are accessible by name.

Remarks on thread-safety:

There are three classes of methods:

(1) Methods which manipulate the dictionary structure

(2) Methods which access dictionary entries

(3) Methods which only access Core (private)

Methods in (3) as well as get_node_id() are always thread-safe.

Methods in (2) are thread-safe if they are not intermixed with methods in (1).

Methods in (1) should be run in sequence before accessing dictionary entries (group 2).

Examples:
examples/listdevices.cpp, examples/master.cpp, examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 83 of file device.h.

Constructor & Destructor Documentation

kaco::Device::Device ( Core core,
uint8_t  node_id 
)

Constructor.

Parameters
coreReference of a Core instance
node_idID of the represented device

Definition at line 48 of file device.cpp.

kaco::Device::~Device ( )

Destructor.

Todo:
Something to shut down? NMT?

Definition at line 51 of file device.cpp.

Member Function Documentation

void kaco::Device::add_entry ( const uint16_t  index,
const uint8_t  subindex,
const std::string &  name,
const Type  type,
const AccessType  access_type 
)

Adds an entry to the dictionary. You have to take care that exactly this entry exists on the device for yourself!

Parameters
indexIndex
subindexSub-index
nameName
typeData type
access_typeAccess rights
Exceptions
canopen_errorif entry with this name or index already exists.

Definition at line 149 of file device.cpp.

void kaco::Device::add_receive_pdo_mapping ( uint16_t  cob_id,
const std::string &  entry_name,
uint8_t  offset 
)

Adds a receive PDO mapping. This means values sent by the device via PDO are saved into the dictionary cache.

Parameters
cob_idCOB-ID of the PDO
entry_nameName of the dictionary entry
offsetindex of the first mapped byte in the PDO message
Exceptions
dictionary_errorif there is no entry with the given name.
Todo:
Add index/subindex overload?
Examples:
examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 163 of file device.cpp.

void kaco::Device::add_transmit_pdo_mapping ( uint16_t  cob_id,
const std::vector< Mapping > &  mappings,
TransmissionType  transmission_type = TransmissionType::ON_CHANGE,
std::chrono::milliseconds  repeat_time = std::chrono::milliseconds(0) 
)

Adds a transmit PDO mapping. This means values from the dictionary cache are sent to the device.

Example:

The following command maps the "Controlword" entry (2 bytes, see CiA 402)
to the first two bytes of the PDO channel with cob_id 0x206 (RPDO1 of CANOpen device 6),
and the "Target Position" entry (4 bytes, see CiA 402) to bytes 2-5 of this PDO channel.
The PDO is sent whenever one of the values is changed via set_entry("Controlword", ...)
or set_entry("Target Position", ...),

device.add_transmit_pdo_mapping(0x206, {{"Controlword", 0, 0},{"Target Position", 2, 0}});
Parameters
cob_idThe cob_id of the PDO to transmit
mappingsA vector of mappings. A mapping maps a dictionary entry (by name) to a part of a PDO (by first and last byte index)
transmission_typeSend PDO "ON_CHANGE" or "PERIODIC"
repeat_timeIf transmission_type==TransmissionType::PERIODIC, PDO is sent periodically according to repeat_time.
Exceptions
dictionary_error
Examples:
examples/pdo.cpp.

Definition at line 200 of file device.cpp.

Value kaco::Device::execute ( const std::string &  operation_name,
const Value argument = m_dummy_value 
)

Executes a convenience operation. It must exist due to a previous load_operations() or add_operation() call.

Parameters
operation_nameName of the operation.
argumentOptional argument to be passed to the operation.
Returns
The result value of the operation. Invalid value in case there is no result.
Exceptions
dictionary_errorif operation is not available
Examples:
examples/master.cpp, and examples/ros/motor_and_io_bridge.cpp.

Definition at line 428 of file device.cpp.

const Value & kaco::Device::get_constant ( const std::string &  constant_name) const

Returns a constant. It must exist due to a previous load_constants() or add_constant() call.

Exceptions
dictionary_errorif constant is not available
Examples:
examples/master.cpp, and examples/ros/motor_and_io_bridge.cpp.

Definition at line 453 of file device.cpp.

uint16_t kaco::Device::get_device_profile_number ( )

Returns the CiA profile number.

Exceptions
sdo_error
Todo:
Make this an operation?
Examples:
examples/master.cpp, examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 274 of file device.cpp.

const Value & kaco::Device::get_entry ( const std::string &  entry_name,
const ReadAccessMethod  access_method = ReadAccessMethod::use_default 
)

Gets the value of a dictionary entry by name internally. If there is no cached value or the entry is configured to send an SDO on request, the new value is fetched from the device via SDO. Otherwise it returns the cached value. This makes sense, if a Reveive PDO is configured on the corresponding entry.

Parameters
entry_nameName of the dictionary entry
access_methodMethod of value retrival
Exceptions
dictionary_errorif there is no entry with the given name.
sdo_error
Todo:
check access_type from dictionary
Examples:
examples/master.cpp, examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 102 of file device.cpp.

const Value & kaco::Device::get_entry ( const uint16_t  index,
const uint8_t  subindex = 0,
const ReadAccessMethod  access_method = ReadAccessMethod::use_default 
)

Gets the value of a dictionary entry by name internally. If there is no cached value or the entry is configured to send an SDO on request, the new value is fetched from the device via SDO. Otherwise it returns the cached value. This makes sense, if a Reveive PDO is configured on the corresponding entry.

Parameters
indexIndex of the dictionary entry.
subindexSub-index of the dictionary entry. Default is zero.
access_methodMethod of value retrival
Exceptions
dictionary_errorif there is no entry with the given name.
sdo_error
Todo:
check access_type from dictionary

Definition at line 111 of file device.cpp.

Type kaco::Device::get_entry_type ( const std::string &  entry_name)

Returns the type of a dictionary entry identified by name as it is defined in the local dictionary.

Parameters
entry_nameName of the dictionary entry
Exceptions
dictionary_errorif there is no entry with the given name
Todo:
Overload with index+subindex.

Definition at line 87 of file device.cpp.

Type kaco::Device::get_entry_type ( const uint16_t  index,
const uint8_t  subindex = 0 
)

Returns the type of a dictionary entry identified by name as it is defined in the local dictionary.

Parameters
indexIndex of the dictionary entry.
subindexSub-index of the dictionary entry. Default is zero.
Exceptions
dictionary_errorif there is no entry with the given name

Definition at line 95 of file device.cpp.

uint8_t kaco::Device::get_node_id ( ) const

Returns the node ID of the device.

Remarks
thread-safe
Examples:
examples/listdevices.cpp, examples/master.cpp, examples/pdo.cpp, and examples/ros/motor_and_io_bridge.cpp.

Definition at line 74 of file device.cpp.

bool kaco::Device::has_entry ( const std::string &  entry_name)

Returns true if the entry is contained in the device dictionary.

Parameters
entry_nameName of the dictionary entry
Returns
True if entry_name is contained in the device dictionary.
Todo:
Overload with index+subindex.

Definition at line 78 of file device.cpp.

bool kaco::Device::has_entry ( const uint16_t  index,
const uint8_t  subindex = 0 
)

Returns true if the entry is contained in the device dictionary.

Parameters
indexIndex of the dictionary entry.
subindexSub-index of the dictionary entry. Default is zero.
Returns
True if entry_name is contained in the device dictionary.

Definition at line 83 of file device.cpp.

bool kaco::Device::load_constants ( )

Loads constants associated with the device profile.

Returns
true, if successful

Definition at line 436 of file device.cpp.

void kaco::Device::load_dictionary_from_eds ( const std::string &  path)

Loads the dictionary from a custom EDS file.

Parameters
pathA filesystem path where the EDS library can be found.
Exceptions
canopen_errorif the EDS file cannot be loaded.

Definition at line 381 of file device.cpp.

std::string kaco::Device::load_dictionary_from_library ( )

Tries to load the most specific EDS file available in KaCanOpen's internal EDS library. This is either device specific, CiA profile specific, or mandatory CiA 301.

Returns
Path to the loaded EDS file.
Exceptions
canopen_errorif mandatory CiA 301 dictionary entries cannot be loaded.
Examples:
examples/listdevices.cpp, examples/master.cpp, examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 327 of file device.cpp.

bool kaco::Device::load_operations ( )

Loads convenience operations associated with the device profile.

Returns
true, if successful

Definition at line 411 of file device.cpp.

void kaco::Device::set_entry ( const std::string &  entry_name,
const Value value,
const WriteAccessMethod  access_method = WriteAccessMethod::use_default 
)

Sets the value of a dictionary entry by name internally. If the entry is configured to send an SDO on update, the new value is also sent to the device via SDO. If a PDO is configured on the corresponding entry, it will from now on use the new value stored internally.

Parameters
entry_nameName of the dictionary entry
valueThe value to write, wrapped in a Value object. The Value class has implicit cast constructors for all supported data types.
access_methodHow, where and when to write the value.
Exceptions
dictionary_errorif there is no entry with the given name.
sdo_error
Todo:
check access_type from dictionary
Examples:
examples/master.cpp, examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 123 of file device.cpp.

void kaco::Device::set_entry ( const uint16_t  index,
const uint8_t  subindex,
const Value value,
const WriteAccessMethod  access_method = WriteAccessMethod::use_default 
)

Sets the value of a dictionary entry by name internally. If the entry is configured to send an SDO on update, the new value is also sent to the device via SDO. If a PDO is configured on the corresponding entry, it will from now on use the new value stored internally.

Parameters
indexIndex of the dictionary entry.
subindexSub-index of the dictionary entry.
valueThe value to write, wrapped in a Value object. The Value class has implicit cast constructors for all supported data types.
access_methodHow, where and when to write the value.
Exceptions
dictionary_errorif there is no entry with the given name.
sdo_error
Todo:
check access_type from dictionary

Definition at line 132 of file device.cpp.

void kaco::Device::start ( )

Starts the node via NMT protocol and loads mandatory entries, operations, and constants.

Todo:
Add m_started member?
Examples:
examples/listdevices.cpp, examples/master.cpp, examples/pdo.cpp, examples/ros/motor_and_io_bridge.cpp, and examples/ros/ros.cpp.

Definition at line 54 of file device.cpp.


The documentation for this class was generated from the following files: