Closed ashwinsushil closed 3 months ago
Hi, usually we expect that you use sync mode. PDOs are sent on SYNC signal from master. You set the sync period in master setting in bus.yml. The values you write via /tpdo are cached and then send at sync. You need to make sure you write all values via /tpdo during sync period you need on next sync. Sadly we currently do not have a mechanism in place for that.
@hellantos That's quite interesting to hear because I'm sending the tpdo as shown in the image below (proxy_setup example). There is no sync message but still I can see the CAN messages using candump
. Is that normal ?
Looking into the code, what is stopping us from sending a whole PDO? Is the lely library itself?
template <class NODETYPE>
bool NodeCanopenProxyDriver<NODETYPE>::tpdo_transmit(ros2_canopen::COData & data)
{
if (this->activated_.load())
{
RCLCPP_INFO(
this->node_->get_logger(), "Node ID 0x%X: Transmit PDO index %x, subindex %hhu, data %d",
this->lely_driver_->get_id(), data.index_, data.subindex_,
data.data_); // ToDo: Remove or make debug
this->lely_driver_->tpdo_transmit(data);
return true;
}
return false
}
If the library allows to send a full PDO, maybe I can try to make a PR to enable this. Or maybe you have a work around? :)
Problem here is, that the eds in that example has pdos configured as async. You can achieve the behavior you want, by either setting an Inhibit Time or by making the pdos sync by setting transmission mode to 1-253. The number 1-253 indicates the nth sync signal the pdo is sent on.
@hellantos Just to come back to the original question, the fact that we are not able to send a whole PDO, is the problem lely itself ?
As mentioned this line of code to me looks like we lely is only able to set the value of one object dictionary.
this->lely_driver_->tpdo_transmit(data);
One of the upsides of CAN is that we can send 8 bytes of information over PDO in one message. So trying to understand if the underlying library is our problem here.
Lely uses the object dictionary approach. Application stores values in a dictionary. Lely master sends them on a trigger (either sync or writeEvent). If you want to have an async pdo that is sent only if all objects have been updated, you would need to write all those objects to the dictionary and then trigger write event. It should work. Check in canopen_base/lely_driver_bridge.
It is important, that the pdo is set to async, otherwise pdo gets sent on SYNC.
To implement this behavior in this library you would need to change lely_driver_bridge and potentially add a service for each pdo that triggers sending.
@hellantos That would would work, I guess. Thanks.
As you mentioned before, It should also be possible to just sent PDO from the master by setting an Event(ms) and then changing the value of the object in the master.
For example, I am trying something like this.
I was thinking I can change the value at the index (0x2200, 0x01) using the /master/sdo_write
. However, it seems that it is not possible to change the value of the objects of the master. Is that normal ? Or am I missing something here?
@hellantos A little more insight of what I was trying to achieve.
According to the CANopen, I defined TPDO mapping from master to a device like this.
The master dcf/eds look like this
Of course the default value at 0x2200 is being sent to the device periodically and my aim was to trying to change the value at 0x2200 in the master.
Following your instructions, I was searching for the dictionary of the master to do this. But it looks like master doesn't really have the dictionary in the LelyMasterBridge
. So I am a bit confused how do I update the value of the dictionary in the master.
@hellantos I solved this issue by doing the following:
On the master dcf, I added a timer for 3000ms
Create a subscriber that sets the values of the dictionary of the device (master doesn't seems to have an dictionary object).
Make sure you dont call a WriteEvent()
.
On the next PDO event (after 3000ms), the full PDO can be sent to a device.
Ps: make sure you have proper mapping in your eds files.
I am closing this question because it is solved.
Describe the bug Hello there,
I am trying to understand the
ros2_canopen
a bit more. I am currently running theproxy_setup
example. I see that I have the/tpdo
from the devices. I can send the PDO to a single object index (with sub index) of the device by publishing to that topic.For example, in the mapping given below from simple.eds I am able to just publish with index: 0x4000 and sub-index: 0x01 and data. Everything works well.
But if I have mapping like this
I am wondering how would I go about sending a whole PDO message? I could not find any example either in any other Drivers where a whole PDO is packaged and sent. Do you have any thoughts on this?
Setup:
Additional context Add any other context about the problem here.