mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_HAL: added thread_info() API
This commit is contained in:
parent
67fc23d01b
commit
164022ca12
@ -182,6 +182,9 @@ public:
|
|||||||
// attempt to trap the processor, presumably to enter an attached debugger
|
// attempt to trap the processor, presumably to enter an attached debugger
|
||||||
virtual bool trap() const { return false; }
|
virtual bool trap() const { return false; }
|
||||||
|
|
||||||
|
// request information on running threads
|
||||||
|
virtual size_t thread_info(char *buf, size_t bufsize) { return 0; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// we start soft_armed false, so that actuators don't send any
|
// we start soft_armed false, so that actuators don't send any
|
||||||
// values until the vehicle code has fully started
|
// values until the vehicle code has fully started
|
||||||
|
Loading…
Reference in New Issue
Block a user