Lely Driver Bridge.
More...
#include <lely_driver_bridge.hpp>
|
| LelyDriverBridge (ev_exec_t *exec, canopen::AsyncMaster &master, uint8_t id, std::string name, std::string eds, std::string bin, std::chrono::milliseconds timeout=20ms) |
| Construct a new Lely Bridge object. More...
|
|
std::future< bool > | async_sdo_write (COData data) |
| Asynchronous SDO Write. More...
|
|
template<typename T > |
std::future< bool > | async_sdo_write_typed (uint16_t idx, uint8_t subidx, T value) |
|
template<typename T > |
bool | sync_sdo_write_typed (uint16_t idx, uint8_t subidx, T value, std::chrono::milliseconds timeout) |
|
std::future< COData > | async_sdo_read (COData data) |
| Aynchronous SDO Read. More...
|
|
template<typename T > |
std::future< T > | async_sdo_read_typed (uint16_t idx, uint8_t subidx) |
|
template<typename T > |
bool | sync_sdo_read_typed (uint16_t idx, uint8_t subidx, T &value, std::chrono::milliseconds timeout) |
|
std::future< canopen::NmtState > | async_request_nmt () |
| Asynchronous request for NMT. More...
|
|
std::shared_ptr< SafeQueue< COData > > | get_rpdo_queue () |
| Asynchronous request for RPDO. More...
|
|
std::shared_ptr< SafeQueue< COEmcy > > | get_emcy_queue () |
| Asynchronous request for EMCY. More...
|
|
void | tpdo_transmit (COData data) |
| Executes a TPDO transmission. More...
|
|
void | nmt_command (canopen::NmtCommand command) |
| Executes a NMT Command. More...
|
|
uint8_t | get_id () |
| Get the nodeid. More...
|
|
bool | wait_for_boot () |
| Wait for device to be booted. More...
|
|
void | set_sync_function (std::function< void()> on_sync_function) |
|
void | unset_sync_function () |
|
void | Boot () |
| Request master to boot device. More...
|
|
bool | is_booted () |
| Indicates if Device is booted. More...
|
|
template<typename T > |
void | submit_write (COData data) |
|
template<typename T > |
void | submit_read (COData data) |
|
template<typename T > |
const T | universal_get_value (uint16_t index, uint8_t subindex) |
|
template<typename T > |
void | universal_set_value (uint16_t index, uint8_t subindex, T value) |
|
|
void | OnSync (uint8_t cnt, const time_point &t) noexcept override |
|
void | OnState (canopen::NmtState state) noexcept override |
| OnState Callback. More...
|
|
virtual void | OnBoot (canopen::NmtState st, char es, const ::std::string &what) noexcept override |
| OnBoot Callback This callback is called when the Boot process of the slave that was initiated by the master has been success fully finished. More...
|
|
void | OnRpdoWrite (uint16_t idx, uint8_t subidx) noexcept override |
| OnRpdoWrite Callback. More...
|
|
void | OnEmcy (uint16_t eec, uint8_t er, uint8_t msef[5]) noexcept override |
|
Lely Driver Bridge.
This class provides functionalities for bridging between Lelycore drivers and standard C++ functions. This means it provides async and sync functions for interacting with CANopen devices using synchronisation functionalities from C++ standard library.
◆ LelyDriverBridge()
ros2_canopen::LelyDriverBridge::LelyDriverBridge |
( |
ev_exec_t * |
exec, |
|
|
canopen::AsyncMaster & |
master, |
|
|
uint8_t |
id, |
|
|
std::string |
name, |
|
|
std::string |
eds, |
|
|
std::string |
bin, |
|
|
std::chrono::milliseconds |
timeout = 20ms |
|
) |
| |
|
inline |
Construct a new Lely Bridge object.
- Parameters
-
[in] | exec | Executor to use |
[in] | master | Master to use |
[in] | id | NodeId to connect to |
[in] | eds | EDS file |
[in] | bin | BIN file (concise dcf) |
[in] | timeout | Timeout in milliseconds for SDO reads/writes |
◆ OnSync()
void ros2_canopen::LelyDriverBridge::OnSync |
( |
uint8_t |
cnt, |
|
|
const time_point & |
t |
|
) |
| |
|
inlineoverrideprotectednoexcept |
◆ OnState()
void ros2_canopen::LelyDriverBridge::OnState |
( |
canopen::NmtState |
state | ) |
|
|
overrideprotectednoexcept |
OnState Callback.
This callback function is called when an Nmt state change is detected on the connected device.
- Parameters
-
◆ OnBoot()
virtual void ros2_canopen::LelyDriverBridge::OnBoot |
( |
canopen::NmtState |
st, |
|
|
char |
es, |
|
|
const ::std::string & |
what |
|
) |
| |
|
overrideprotectedvirtualnoexcept |
OnBoot Callback This callback is called when the Boot process of the slave that was initiated by the master has been success fully finished.
- Parameters
-
◆ OnRpdoWrite()
void ros2_canopen::LelyDriverBridge::OnRpdoWrite |
( |
uint16_t |
idx, |
|
|
uint8_t |
subidx |
|
) |
| |
|
overrideprotectednoexcept |
OnRpdoWrite Callback.
This callback function is called when an RPDO write request is received from the connected device.
- Todo:
- This function should use a threadsafe queue not the icky implementation we have now.
- Parameters
-
[in] | idx | Object Index |
[in] | subidx | Object Subindex |
◆ OnEmcy()
void ros2_canopen::LelyDriverBridge::OnEmcy |
( |
uint16_t |
eec, |
|
|
uint8_t |
er, |
|
|
uint8_t |
msef[5] |
|
) |
| |
|
overrideprotectednoexcept |
The function invoked when an EMCY message is received from the remote node.
- Todo:
- This function should use a threadsafe queue not the icky implementation we have now.
- Parameters
-
eec | the emergency error code. |
er | the error register. |
msef | the manufacturer-specific error code. |
◆ async_sdo_write()
std::future<bool> ros2_canopen::LelyDriverBridge::async_sdo_write |
( |
COData |
data | ) |
|
Asynchronous SDO Write.
Writes the data passed to the function via SDO to the connected device.
- Parameters
-
- Returns
- std::future<bool> Returns an std::future<bool> that is fulfilled when the write request was done. An error is stored when the write request was unsuccessful.
◆ async_sdo_write_typed()
template<typename T >
std::future<bool> ros2_canopen::LelyDriverBridge::async_sdo_write_typed |
( |
uint16_t |
idx, |
|
|
uint8_t |
subidx, |
|
|
T |
value |
|
) |
| |
|
inline |
◆ sync_sdo_write_typed()
template<typename T >
bool ros2_canopen::LelyDriverBridge::sync_sdo_write_typed |
( |
uint16_t |
idx, |
|
|
uint8_t |
subidx, |
|
|
T |
value, |
|
|
std::chrono::milliseconds |
timeout |
|
) |
| |
|
inline |
◆ async_sdo_read()
std::future<COData> ros2_canopen::LelyDriverBridge::async_sdo_read |
( |
COData |
data | ) |
|
Aynchronous SDO Read.
Reads the indicated SDO object from the connected device.
- Parameters
-
[in] | data | Data to be read, the data entry is not used. |
- Returns
- std::future<COData> Returns an std::future<COData> that is fulfilled when the read request was done. The result of the request is stored in the future. An error is stored when the read request was unsuccessful.
◆ async_sdo_read_typed()
template<typename T >
std::future<T> ros2_canopen::LelyDriverBridge::async_sdo_read_typed |
( |
uint16_t |
idx, |
|
|
uint8_t |
subidx |
|
) |
| |
|
inline |
◆ sync_sdo_read_typed()
template<typename T >
bool ros2_canopen::LelyDriverBridge::sync_sdo_read_typed |
( |
uint16_t |
idx, |
|
|
uint8_t |
subidx, |
|
|
T & |
value, |
|
|
std::chrono::milliseconds |
timeout |
|
) |
| |
|
inline |
◆ async_request_nmt()
std::future<canopen::NmtState> ros2_canopen::LelyDriverBridge::async_request_nmt |
( |
| ) |
|
Asynchronous request for NMT.
Waits for an NMT state change to occur. The new state is stored in the future returned by the function.
- Returns
- std::future<canopen::NmtState> The returned future is set when NMT State changes.
◆ get_rpdo_queue()
std::shared_ptr<SafeQueue<COData> > ros2_canopen::LelyDriverBridge::get_rpdo_queue |
( |
| ) |
|
Asynchronous request for RPDO.
Waits for an RPDO write request to be received from the slave. The content of the request are stored in the returned future.
- Todo:
- This function should use a threadsafe queue not the icky implementation we have now.
- Returns
- std::future<COData> The returned future is set when an RPDO event is detected.
◆ get_emcy_queue()
std::shared_ptr<SafeQueue<COEmcy> > ros2_canopen::LelyDriverBridge::get_emcy_queue |
( |
| ) |
|
Asynchronous request for EMCY.
- Todo:
- This function should use a threadsafe queue not the icky implementation we have now.
- Returns
- std::future<COEmcy> The returned future is set when an EMCY event is detected.
◆ tpdo_transmit()
void ros2_canopen::LelyDriverBridge::tpdo_transmit |
( |
COData |
data | ) |
|
Executes a TPDO transmission.
This function executes a TPDO transmission. The{false, true} object specified in the input data is sent if it is registered as a TPDO with the master.
- Parameters
-
[in] | data | Object and data to be written |
◆ nmt_command()
void ros2_canopen::LelyDriverBridge::nmt_command |
( |
canopen::NmtCommand |
command | ) |
|
Executes a NMT Command.
This function sends the NMT command specified as parameter.
- Parameters
-
[in] | command | NMT Command to execute |
◆ get_id()
uint8_t ros2_canopen::LelyDriverBridge::get_id |
( |
| ) |
|
Get the nodeid.
- Returns
- uint8_t
◆ wait_for_boot()
bool ros2_canopen::LelyDriverBridge::wait_for_boot |
( |
| ) |
|
|
inline |
Wait for device to be booted.
- Returns
- true
-
false
◆ set_sync_function()
void ros2_canopen::LelyDriverBridge::set_sync_function |
( |
std::function< void()> |
on_sync_function | ) |
|
|
inline |
◆ unset_sync_function()
void ros2_canopen::LelyDriverBridge::unset_sync_function |
( |
| ) |
|
|
inline |
◆ Boot()
void ros2_canopen::LelyDriverBridge::Boot |
( |
| ) |
|
|
inline |
Request master to boot device.
◆ is_booted()
bool ros2_canopen::LelyDriverBridge::is_booted |
( |
| ) |
|
|
inline |
Indicates if Device is booted.
- Returns
- true
-
false
◆ submit_write()
template<typename T >
void ros2_canopen::LelyDriverBridge::submit_write |
( |
COData |
data | ) |
|
|
inline |
◆ submit_read()
template<typename T >
void ros2_canopen::LelyDriverBridge::submit_read |
( |
COData |
data | ) |
|
|
inline |
◆ universal_get_value()
template<typename T >
const T ros2_canopen::LelyDriverBridge::universal_get_value |
( |
uint16_t |
index, |
|
|
uint8_t |
subindex |
|
) |
| |
|
inline |
◆ universal_set_value()
template<typename T >
void ros2_canopen::LelyDriverBridge::universal_set_value |
( |
uint16_t |
index, |
|
|
uint8_t |
subindex, |
|
|
T |
value |
|
) |
| |
|
inline |
◆ dictionary_
◆ dictionary_mutex_
std::mutex ros2_canopen::LelyDriverBridge::dictionary_mutex_ |
|
protected |
◆ pdo_map_
std::shared_ptr<PDOMap> ros2_canopen::LelyDriverBridge::pdo_map_ |
|
protected |
◆ sdo_read_data_promise
std::shared_ptr<std::promise<COData> > ros2_canopen::LelyDriverBridge::sdo_read_data_promise |
|
protected |
◆ sdo_write_data_promise
std::shared_ptr<std::promise<bool> > ros2_canopen::LelyDriverBridge::sdo_write_data_promise |
|
protected |
◆ sdo_mutex
std::mutex ros2_canopen::LelyDriverBridge::sdo_mutex |
|
protected |
◆ running
bool ros2_canopen::LelyDriverBridge::running |
|
protected |
◆ sdo_cond
std::condition_variable ros2_canopen::LelyDriverBridge::sdo_cond |
|
protected |
◆ nmt_state_promise
std::promise<canopen::NmtState> ros2_canopen::LelyDriverBridge::nmt_state_promise |
|
protected |
◆ nmt_state_is_set
std::atomic<bool> ros2_canopen::LelyDriverBridge::nmt_state_is_set |
|
protected |
◆ nmt_mtex
std::mutex ros2_canopen::LelyDriverBridge::nmt_mtex |
|
protected |
◆ rpdo_promise
std::promise<COData> ros2_canopen::LelyDriverBridge::rpdo_promise |
|
protected |
◆ rpdo_is_set
std::atomic<bool> ros2_canopen::LelyDriverBridge::rpdo_is_set |
|
protected |
◆ pdo_mtex
std::mutex ros2_canopen::LelyDriverBridge::pdo_mtex |
|
protected |
◆ rpdo_queue
std::shared_ptr<SafeQueue<COData> > ros2_canopen::LelyDriverBridge::rpdo_queue |
|
protected |
◆ emcy_promise
std::promise<COEmcy> ros2_canopen::LelyDriverBridge::emcy_promise |
|
protected |
◆ emcy_is_set
std::atomic<bool> ros2_canopen::LelyDriverBridge::emcy_is_set |
|
protected |
◆ emcy_mtex
std::mutex ros2_canopen::LelyDriverBridge::emcy_mtex |
|
protected |
◆ emcy_queue
std::shared_ptr<SafeQueue<COEmcy> > ros2_canopen::LelyDriverBridge::emcy_queue |
|
protected |
◆ booted
std::atomic<bool> ros2_canopen::LelyDriverBridge::booted |
|
protected |
◆ boot_status
char ros2_canopen::LelyDriverBridge::boot_status |
|
protected |
◆ boot_what
std::string ros2_canopen::LelyDriverBridge::boot_what |
|
protected |
◆ boot_state
canopen::NmtState ros2_canopen::LelyDriverBridge::boot_state |
|
protected |
◆ boot_cond
std::condition_variable ros2_canopen::LelyDriverBridge::boot_cond |
|
protected |
◆ boot_mtex
std::mutex ros2_canopen::LelyDriverBridge::boot_mtex |
|
protected |
◆ nodeid
uint8_t ros2_canopen::LelyDriverBridge::nodeid |
|
protected |
◆ name_
std::string ros2_canopen::LelyDriverBridge::name_ |
|
protected |
◆ sdo_timeout
std::chrono::milliseconds ros2_canopen::LelyDriverBridge::sdo_timeout |
|
protected |
◆ on_sync_function_
std::function<void()> ros2_canopen::LelyDriverBridge::on_sync_function_ |
|
protected |
The documentation for this class was generated from the following file:
- /home/runner/work/ros2_canopen/ros2_canopen/canopen_base_driver/include/canopen_base_driver/lely_driver_bridge.hpp