Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

added NodeCapabilities message #4

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

tridge
Copy link
Member

@tridge tridge commented Feb 5, 2022

this will allow for dynamic detection of node capabilities, and
upgrade to FDCAN

uint32 FLAG_AUTHORITATIVE = 1
# the PUBLISHER_ONLY bit should be set if this node only publishes data, most sensor
# nodes should set this bit
uint32 FLAG_PUBLISHER_ONLY = 2
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What's the purpose of FLAG_PUBLISHER_ONLY? Does it mean literally only publishes and doesn't subscribe to anything or is there some nuance (parameters, etc)?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the idea is to distinguish between a node publishing sensor data and nodes that consume sensor data. The reason this matters is for thinks like the old GNSS Fix message. We'd like to stop sending that message to save bandwidth, but we can't do that unless we know that all nodes that consume GNSS messages understand Fix2. We don't care if (for example) a baro/compass sensor node is at the level that understands Fix2, as it doesn't consume any GNSS messages, but we do care if all the consumer nodes (flight controllers, loggers, cameras etc) understand Fix2.
So this is a deliberately broad category to classify nodes as either "publish only" or "publish and consume". That reflects the reality of how DroneCAN networks are actually used, and will allow us to push out replacement messages much more easily.
Note that while I'm using GNSS Fix/Fix2 as an example, the same principle applies to other messages, and the same distinction between nodes can be used

# the PUBLISHER_ONLY bit should be set if this node only publishes data, most sensor
# nodes should set this bit
uint32 FLAG_PUBLISHER_ONLY = 2
uint32 FLAG_FDCAN_4M_SUPPORT = 4
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are you seeing 4Mbit as a natural boundary somewhere? I'm seeing a lot of parts capable of 2M and 5M, but it's not like I've done a survey.

Another idea could be to separate the CAN version (2.0B, CAN FD 1.0, maybe CAN XL later) and the max bit rate?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bugobliterator what do you think? should we support 5M? I think keeping the number of options small is good

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

discussed with @bugobliterator, we think we should do 2M, 5M and 8M, with arbitration at 1M for all 3

# the PUBLISHER_ONLY bit should be set if this node only publishes data, most sensor
# nodes should set this bit
uint32 FLAG_PUBLISHER_ONLY = 2
uint32 FLAG_FDCAN_4M_SUPPORT = 4

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what about 2M, 5M? 8M is not common and requires special SIC transceivers to utilize this datarate.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Missing BRS support. CAN-FD can be used without setting the BRS or having a different data rate.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

that is a question for @bugobliterator
note that we don't really want to support all possible combinations

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wouldn't lack of BRS support be implicit in the bitrate flags with the supported bitrate being limited to 1M (FLAG_FDCAN_1M_SUPPORT)?

Copy link

@thirtytwobits thirtytwobits Feb 11, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

After some discussions on Discord (my kids are laughing at me for using Discord BTW. Thanks for that) I think the best design here is to define a set of abstract, Level-1 standards and given them names. For example:

  1. DRONECAN_COMPAT
  2. DRONECAN_RELIABLE
  3. DRONECAN_FAST
  4. DRONECAN_FAST_SI

where each is defined with a separate specification for your L1 bus. This would include all of the considerations like arbitration rate, data rate, sample point, etc. My example here would optimize these settings for:

  1. compatibility with existing systems
  2. using FD (with the improved checksum) at a slow data rate and without BRS to minimize SI issues.
  3. using FD at a single, fixed datarate that is faster than the arbitration rate.
  4. using FD with Signal Improvement transceivers (CiA601-4 2.0.0) to achieve 8Mb data rates.

That said, it may introduce some complexity into firmwares to require runtime reconfiguration to a minimum supported standard. You might allow this process to simply report to the user that "node x is not compatible with this system" and provide a link to the manufacturer's reported help URL. That URL can then instruct the user on how to reconfigure the LRU into one of the four modes. This suggests you need a "can dynamically reconfigure" flag in the message.

@@ -0,0 +1,59 @@
# NodeCapabilities messages

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's not clear when nodes, other than the central server, should emit this message. Also, as a protocol, there's no discussion of what to do if more than one nodeID sends different capabilities with the authoritative bit set.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

different capabilities with authoritative set would have to be either a transient condition or a bug in the implementation. All the authoritative servers have the same information to work with so should come to the same result

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think logging an error in the authoritative server if it sees persistent (more than 5s?) conflicting information would be the way to go

@thirtytwobits
Copy link

One other thing I just realized, some hardware might be able to support different FD clock rates but cannot change them at runtime (i.e. needs new firmware or needs to be configured manually). If you are on a device that is, for example, using a 4M datarate and the minimum capability negotiated is 2M what does the node do to say "I can't do that"?

@tridge
Copy link
Member Author

tridge commented Feb 11, 2022

If you are on a device that is, for example, using a 4M datarate and the minimum capability negotiated is 2M what does the node do to say "I can't do that"?

it is assumed that devices can do 1M bxCAN, as all existing devices doing DroneCAN and v0 UAVCAN must be able to do

@davidbuzz
Copy link
Member

nudge

this will allow for dynamic detection of node capabilities, and
upgrade to FDCAN
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants