15#ifndef CANOPEN_BASE_DRIVER__LELY_BRIDGE_HPP_
16#define CANOPEN_BASE_DRIVER__LELY_BRIDGE_HPP_
20#include <lely/co/dcf.hpp>
21#include <lely/co/dev.hpp>
22#include <lely/co/obj.hpp>
23#include <lely/coapp/fiber_driver.hpp>
24#include <lely/coapp/master.hpp>
25#include <lely/coapp/sdo_error.hpp>
26#include <lely/ev/co_task.hpp>
27#include <lely/ev/future.hpp>
30#include <condition_variable>
34#include <rclcpp/rclcpp.hpp>
36#include <system_error>
40#include <boost/lockfree/queue.hpp>
41#include <boost/optional.hpp>
42#include <boost/thread.hpp>
46using namespace std::chrono_literals;
57typedef std::map<uint16_t, std::map<uint8_t, pdo_mapping>>
PDOMap;
69 std::shared_ptr<PDOMap> pdo_map = std::make_shared<PDOMap>();
113 for (
int index = 0; index < 256; index++)
115 for (
int subindex = 1; subindex < 9; subindex++)
117 auto obj = find(0x1600 + index, subindex);
124 data = obj->getVal<CO_DEFTYPE_UNSIGNED32>();
126 uint8_t tmps = (data >> 8) & 0xFF;
127 uint16_t tmpi = (data >> 16) & 0xFFFF;
135 (*map)[tmpi][tmps] = mapping;
136 std::cout <<
"Found rpdo mapped object: index=" << std::hex << (int)tmpi
137 <<
" subindex=" << (
int)tmps << std::endl;
143 for (
int index = 0; index < 256; index++)
145 for (
int subindex = 1; subindex < 9; subindex++)
147 auto obj = find(0x1A00 + index, subindex);
154 data = obj->getVal<CO_DEFTYPE_UNSIGNED32>();
156 uint8_t tmps = (data >> 8) & 0xFF;
157 uint16_t tmpi = (data >> 16) & 0xFFFF;
166 (*map)[tmpi][tmps] = mapping;
167 std::cout <<
"Found tpdo mapped object: index=" << std::hex << (int)tmpi
168 <<
" subindex=" << (
int)tmps << std::endl;
177 for (
int i = 0; i < 256; i++)
191 for (
int i = 0; i < 256; i++)
201 bool checkObjInPDO(uint8_t pdo, uint16_t mapping_idx, uint16_t idx, uint8_t subindex)
203 for (
int i = 1; i < 9; i++)
205 auto obj = find(mapping_idx + pdo, i);
212 data = obj->getVal<CO_DEFTYPE_UNSIGNED32>();
214 uint8_t tmps = (data >> 8) & 0xFF;
215 uint16_t tmpi = (data >> 16) & 0xFFFF;
217 if (tmps == subindex && tmpi == idx)
219 std::cout <<
"Found object in pdo: " << (int)pdo << std::endl;
250 const char *
name() const noexcept override;
334 void OnSync(uint8_t cnt,
const time_point & t)
noexcept override
336 if (on_sync_function_ !=
nullptr)
356 void OnState(canopen::NmtState state)
noexcept override;
368 virtual void OnBoot(canopen::NmtState st,
char es, const ::std::string & what)
noexcept override;
390 void OnEmcy(uint16_t eec, uint8_t er, uint8_t msef[5])
noexcept override;
395 using FiberDriver::FiberDriver;
409 ev_exec_t * exec, canopen::AsyncMaster & master, uint8_t
id, std::string name, std::string eds,
410 std::string bin, std::chrono::milliseconds timeout = 20ms,
411 std::chrono::milliseconds boot_timeout = 20ms)
412 : FiberDriver(exec, master, id),
419 dictionary_ = std::make_unique<DriverDictionary>(eds.c_str());
421 if (stat(bin.c_str(), &buffer) == 0)
423 co_unsigned16_t * a = NULL;
424 co_unsigned16_t * b = NULL;
425 dictionary_->readDCF(a, b, bin.c_str());
427 pdo_map_ = dictionary_->createPDOMapping();
428 sdo_timeout = timeout;
429 boot_timeout_ = boot_timeout;
447 template <
typename T>
450 std::unique_lock<std::mutex> lck(sdo_mutex);
457 auto prom = std::make_shared<std::promise<bool>>();
458 lely::COSub * sub = this->dictionary_->find(idx, subidx);
461 std::cout <<
"async_sdo_write_typed: id=" << (
unsigned int)this->get_id() <<
" index=0x"
462 << std::hex << (
unsigned int)idx <<
" subindex=" << (
unsigned int)subidx
463 <<
" object does not exist" << std::endl;
464 prom->set_value(
false);
465 this->running =
false;
466 this->sdo_cond.notify_one();
467 return prom->get_future();
472 [
this, value, prom](uint8_t
id, uint16_t idx, uint8_t subidx, ::std::error_code ec)
mutable
477 lely::canopen::make_sdo_exception_ptr(
id, idx, subidx, ec,
"AsyncDownload"));
481 std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);
482 this->dictionary_->setVal<T>(idx, subidx, value);
483 prom->set_value(
true);
485 std::unique_lock<std::mutex> lck(this->sdo_mutex);
486 this->running =
false;
487 this->sdo_cond.notify_one();
490 return prom->get_future();
493 template <
typename T>
495 uint16_t idx, uint8_t subidx, T value, std::chrono::milliseconds timeout)
497 auto fut = async_sdo_write_typed(idx, subidx, value);
498 auto wait_res = fut.wait_for(timeout);
499 if (wait_res == std::future_status::timeout)
501 std::cout <<
"sync_sdo_write_typed: id=" << (
unsigned int)this->get_id() <<
" index=0x"
502 << std::hex << (
unsigned int)idx <<
" subindex=" << (
unsigned int)subidx
503 <<
" timed out." << std::endl;
511 catch (std::exception & e)
513 RCLCPP_ERROR(rclcpp::get_logger(name_), e.what());
533 template <
typename T>
536 std::unique_lock<std::mutex> lck(sdo_mutex);
543 auto prom = std::make_shared<std::promise<T>>();
544 lely::COSub * sub = this->dictionary_->find(idx, subidx);
547 std::cout <<
"async_sdo_read: id=" << (
unsigned int)this->get_id() <<
" index=0x" << std::hex
548 << (
unsigned int)idx <<
" subindex=" << (
unsigned int)subidx
549 <<
" object does not exist" << std::endl;
552 throw lely::canopen::SdoError(this->get_id(), idx, subidx, lely::canopen::SdoErrc::NO_OBJ);
556 prom->set_exception(std::current_exception());
558 this->running =
false;
559 this->sdo_cond.notify_one();
560 return prom->get_future();
564 [
this, prom](uint8_t
id, uint16_t idx, uint8_t subidx, ::std::error_code ec, T value)
mutable
569 lely::canopen::make_sdo_exception_ptr(
id, idx, subidx, ec,
"AsyncUpload"));
573 std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);
574 this->dictionary_->setVal<T>(idx, subidx, value);
575 prom->set_value(value);
577 std::unique_lock<std::mutex> lck(this->sdo_mutex);
578 this->running =
false;
579 this->sdo_cond.notify_one();
582 return prom->get_future();
585 template <
typename T>
587 uint16_t idx, uint8_t subidx, T & value, std::chrono::milliseconds timeout)
589 auto fut = async_sdo_read_typed<T>(idx, subidx);
590 auto wait_res = fut.wait_for(timeout);
591 if (wait_res == std::future_status::timeout)
593 std::cout <<
"sync_sdo_read_typed: id=" << (
unsigned int)this->get_id() <<
" index=0x"
594 << std::hex << (
unsigned int)idx <<
" subindex=" << (
unsigned int)subidx
595 <<
" timed out." << std::endl;
604 catch (std::exception & e)
606 RCLCPP_ERROR(rclcpp::get_logger(name_), e.what());
681 if (booted.load())
return true;
683 std::unique_lock<std::mutex> lck(boot_mtex);
684 auto status = boot_cond.wait_for(lck, boot_timeout_);
686 if (status == std::cv_status::timeout)
688 throw std::system_error(
692 if ((boot_status != 0) && (boot_status !=
'L'))
703 on_sync_function_ = on_sync_function;
726 template <
typename T>
730 std::memcpy(&value, &data.
data_,
sizeof(value));
734 [
this, value](uint8_t
id, uint16_t idx, uint8_t subidx, ::std::error_code ec)
mutable
738 this->sdo_write_data_promise->set_exception(
739 lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec,
"AsyncDownload"));
743 std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);
744 this->dictionary_->setVal<T>(idx, subidx, value);
745 this->sdo_write_data_promise->set_value(true);
747 std::unique_lock<std::mutex> lck(this->sdo_mutex);
748 this->running =
false;
749 this->sdo_cond.notify_one();
754 template <
typename T>
759 [
this](uint8_t
id, uint16_t idx, uint8_t subidx, ::std::error_code ec, T value)
mutable
763 this->sdo_read_data_promise->set_exception(
764 lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec,
"AsyncUpload"));
768 std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);
769 this->dictionary_->setVal<T>(idx, subidx, value);
770 COData d = {idx, subidx, 0};
771 std::memcpy(&d.data_, &value,
sizeof(T));
772 this->sdo_read_data_promise->set_value(d);
774 std::unique_lock<std::mutex> lck(this->sdo_mutex);
775 this->running =
false;
776 this->sdo_cond.notify_one();
781 template <
typename T>
785 bool is_tpdo =
false;
786 if (this->pdo_map_->find(index) != this->pdo_map_->end())
788 auto object = this->pdo_map_->at(index);
789 if (
object.find(subindex) !=
object.end())
791 auto entry =
object.at(subindex);
792 is_tpdo = entry.is_tpdo;
797 if (sync_sdo_read_typed<T>(index, subindex, value, this->sdo_timeout))
803 std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);
804 if (
typeid(T) ==
typeid(uint8_t))
806 value = this->dictionary_->getVal<CO_DEFTYPE_UNSIGNED8>(index, subindex);
808 if (
typeid(T) ==
typeid(uint16_t))
810 value = this->dictionary_->getVal<CO_DEFTYPE_UNSIGNED16>(index, subindex);
812 if (
typeid(T) ==
typeid(uint32_t))
814 value = this->dictionary_->getVal<CO_DEFTYPE_UNSIGNED32>(index, subindex);
816 if (
typeid(T) ==
typeid(int8_t))
818 value = this->dictionary_->getVal<CO_DEFTYPE_INTEGER8>(index, subindex);
820 if (
typeid(T) ==
typeid(int16_t))
822 value = this->dictionary_->getVal<CO_DEFTYPE_INTEGER16>(index, subindex);
824 if (
typeid(T) ==
typeid(int32_t))
826 value = this->dictionary_->getVal<CO_DEFTYPE_INTEGER32>(index, subindex);
832 template <
typename T>
835 bool is_rpdo =
false;
836 if (this->pdo_map_->find(index) != this->pdo_map_->end())
838 auto object = this->pdo_map_->at(index);
839 if (
object.find(subindex) !=
object.end())
841 auto entry =
object.at(subindex);
842 is_rpdo = entry.is_rpdo;
847 std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);
848 this->dictionary_->setVal<T>(index, subindex, value);
849 this->tpdo_mapped[index][subindex] = value;
850 this->tpdo_mapped[index][subindex].WriteEvent();
854 sync_sdo_write_typed(index, subindex, value, this->sdo_timeout);
Definition lely_driver_bridge.hpp:59
~DriverDictionary()
Definition lely_driver_bridge.hpp:62
DriverDictionary(std::string eds_file)
Definition lely_driver_bridge.hpp:61
bool checkObjTPDO(uint16_t idx, uint8_t subidx)
Definition lely_driver_bridge.hpp:187
bool checkObjInPDO(uint8_t pdo, uint16_t mapping_idx, uint16_t idx, uint8_t subindex)
Definition lely_driver_bridge.hpp:201
std::shared_ptr< PDOMap > createPDOMapping()
Definition lely_driver_bridge.hpp:67
void fetchTPDO(std::shared_ptr< PDOMap > map)
Definition lely_driver_bridge.hpp:141
void fetchRPDO(std::shared_ptr< PDOMap > map)
Definition lely_driver_bridge.hpp:111
bool checkObjRPDO(uint16_t idx, uint8_t subidx)
Definition lely_driver_bridge.hpp:173
Lely Driver Bridge.
Definition lely_driver_bridge.hpp:277
std::shared_ptr< SafeQueue< COEmcy > > get_emcy_queue()
Asynchronous request for EMCY.
std::atomic< bool > emcy_is_set
Definition lely_driver_bridge.hpp:304
std::mutex sdo_mutex
Definition lely_driver_bridge.hpp:287
void universal_set_value(uint16_t index, uint8_t subindex, T value)
Definition lely_driver_bridge.hpp:833
bool is_booted()
Indicates if Device is booted.
Definition lely_driver_bridge.hpp:724
std::mutex boot_mtex
Definition lely_driver_bridge.hpp:314
bool sync_sdo_write_typed(uint16_t idx, uint8_t subidx, T value, std::chrono::milliseconds timeout)
Definition lely_driver_bridge.hpp:494
std::promise< COData > rpdo_promise
Definition lely_driver_bridge.hpp:297
bool running
Definition lely_driver_bridge.hpp:288
bool sync_sdo_read_typed(uint16_t idx, uint8_t subidx, T &value, std::chrono::milliseconds timeout)
Definition lely_driver_bridge.hpp:586
std::shared_ptr< std::promise< bool > > sdo_write_data_promise
Definition lely_driver_bridge.hpp:286
std::shared_ptr< PDOMap > pdo_map_
Definition lely_driver_bridge.hpp:282
std::unique_ptr< DriverDictionary > dictionary_
Definition lely_driver_bridge.hpp:280
std::atomic< bool > rpdo_is_set
Definition lely_driver_bridge.hpp:298
std::condition_variable sdo_cond
Definition lely_driver_bridge.hpp:289
void unset_sync_function()
Definition lely_driver_bridge.hpp:706
std::mutex emcy_mtex
Definition lely_driver_bridge.hpp:305
void OnRpdoWrite(uint16_t idx, uint8_t subidx) noexcept override
OnRpdoWrite Callback.
std::future< T > async_sdo_read_typed(uint16_t idx, uint8_t subidx)
Definition lely_driver_bridge.hpp:534
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 ...
void nmt_command(canopen::NmtCommand command)
Executes a NMT Command.
void set_sync_function(std::function< void()> on_sync_function)
Definition lely_driver_bridge.hpp:701
std::string boot_what
Definition lely_driver_bridge.hpp:311
std::mutex nmt_mtex
Definition lely_driver_bridge.hpp:294
std::future< canopen::NmtState > async_request_nmt()
Asynchronous request for NMT.
std::promise< canopen::NmtState > nmt_state_promise
Definition lely_driver_bridge.hpp:292
std::chrono::milliseconds sdo_timeout
Definition lely_driver_bridge.hpp:320
std::future< bool > async_sdo_write_typed(uint16_t idx, uint8_t subidx, T value)
Definition lely_driver_bridge.hpp:448
std::shared_ptr< SafeQueue< COData > > get_rpdo_queue()
Asynchronous request for RPDO.
std::future< COData > async_sdo_read(COData data)
Aynchronous SDO Read.
void submit_read(COData data)
Definition lely_driver_bridge.hpp:755
std::atomic< bool > nmt_state_is_set
Definition lely_driver_bridge.hpp:293
std::function< void()> on_sync_function_
Definition lely_driver_bridge.hpp:322
uint8_t get_id()
Get the nodeid.
void OnEmcy(uint16_t eec, uint8_t er, uint8_t msef[5]) noexcept override
void submit_write(COData data)
Definition lely_driver_bridge.hpp:727
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, std::chrono::milliseconds boot_timeout=20ms)
Construct a new Lely Bridge object.
Definition lely_driver_bridge.hpp:408
const T universal_get_value(uint16_t index, uint8_t subindex)
Definition lely_driver_bridge.hpp:782
std::shared_ptr< SafeQueue< COData > > rpdo_queue
Definition lely_driver_bridge.hpp:300
std::mutex pdo_mtex
Definition lely_driver_bridge.hpp:299
void Boot()
Request master to boot device.
Definition lely_driver_bridge.hpp:712
bool wait_for_boot()
Wait for device to be booted.
Definition lely_driver_bridge.hpp:679
std::atomic< bool > booted
Definition lely_driver_bridge.hpp:309
std::shared_ptr< std::promise< COData > > sdo_read_data_promise
Definition lely_driver_bridge.hpp:285
std::chrono::milliseconds boot_timeout_
Definition lely_driver_bridge.hpp:315
std::promise< COEmcy > emcy_promise
Definition lely_driver_bridge.hpp:303
std::condition_variable boot_cond
Definition lely_driver_bridge.hpp:313
std::future< bool > async_sdo_write(COData data)
Asynchronous SDO Write.
void tpdo_transmit(COData data)
Executes a TPDO transmission.
char boot_status
Definition lely_driver_bridge.hpp:310
std::shared_ptr< SafeQueue< COEmcy > > emcy_queue
Definition lely_driver_bridge.hpp:306
void OnSync(uint8_t cnt, const time_point &t) noexcept override
Definition lely_driver_bridge.hpp:334
std::mutex dictionary_mutex_
Definition lely_driver_bridge.hpp:281
canopen::NmtState boot_state
Definition lely_driver_bridge.hpp:312
uint8_t nodeid
Definition lely_driver_bridge.hpp:317
std::string name_
Definition lely_driver_bridge.hpp:318
void OnState(canopen::NmtState state) noexcept override
OnState Callback.
Thread Safe Queue for CANOpen Data Exchange.
Definition exchange.hpp:49
Definition configuration_manager.hpp:28
std::map< uint16_t, std::map< uint8_t, pdo_mapping > > PDOMap
Definition lely_driver_bridge.hpp:57
LelyBridgeErrc
Definition lely_driver_bridge.hpp:229
@ InconsistentProgramDownload
@ ConfigurationDownloadFailed
@ StartErrorControlFailed
@ NmtSlaveInitiallyOperational
Definition lely_driver_bridge.hpp:256
std::error_code make_error_code(ros2_canopen::LelyBridgeErrc)
Definition exchange.hpp:26
uint32_t data_
Definition exchange.hpp:30
uint8_t subindex_
Definition exchange.hpp:29
uint16_t index_
Definition exchange.hpp:28
Definition exchange.hpp:34
Definition lely_driver_bridge.hpp:249
const char * name() const noexcept override
std::string message(int ev) const override
Definition lely_driver_bridge.hpp:52
bool is_rpdo
Definition lely_driver_bridge.hpp:54
bool is_tpdo
Definition lely_driver_bridge.hpp:53