mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_HAL: minor format fixes to CAN
This commit is contained in:
parent
368fd4b8db
commit
06bb02fab7
@ -55,7 +55,7 @@ public:
|
||||
bitrate Selects the speed that the port will be configured to. If zero, the port speed is left unchanged.
|
||||
|
||||
return false - CAN port open failed
|
||||
true - CAN port open succeeded
|
||||
true - CAN port open succeeded
|
||||
*/
|
||||
virtual bool begin(uint32_t bitrate) = 0;
|
||||
|
||||
@ -76,7 +76,7 @@ public:
|
||||
Test if CAN port is opened and initialized
|
||||
|
||||
return false - CAN port not initialized
|
||||
true - CAN port is initialized
|
||||
true - CAN port is initialized
|
||||
*/
|
||||
virtual bool is_initialized() = 0;
|
||||
|
||||
@ -84,17 +84,17 @@ public:
|
||||
Return if CAN port has some untransmitted pending messages
|
||||
|
||||
return -1 - CAN port is not opened or initialized
|
||||
0 - no messages are pending
|
||||
positive - number of pending messages
|
||||
0 - no messages are pending
|
||||
positive - number of pending messages
|
||||
*/
|
||||
virtual int32_t tx_pending() = 0;
|
||||
|
||||
/*
|
||||
Return if CAN port has received but yet read messages
|
||||
Return if CAN port has received but not yet read messages
|
||||
|
||||
return -1 - CAN port is not opened or initialized
|
||||
0 - no messages are pending for read
|
||||
positive - number of pending messages for read
|
||||
0 - no messages are pending for read
|
||||
positive - number of pending messages for read
|
||||
*/
|
||||
virtual int32_t available() = 0;
|
||||
|
||||
@ -114,7 +114,7 @@ public:
|
||||
can_number - the index of can interface to be opened
|
||||
|
||||
return false - CAN port open failed
|
||||
true - CAN port open succeeded
|
||||
true - CAN port open succeeded
|
||||
*/
|
||||
virtual bool begin(uint32_t bitrate, uint8_t can_number) = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user