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

systemcmds/reboot: Fix reboot command for kernel mode #434

Merged
merged 2 commits into from
Aug 17, 2023
Merged

Conversation

pussuw
Copy link

@pussuw pussuw commented Jun 9, 2023

Fixes reboot command by:

  • Start user workqueue thread in kernel mode by "lazy init"
  • Provide hartid in a0 for __start() as required

@@ -36,6 +36,11 @@
* Implementation of the API declared in px4_shutdown.h.
*/

#ifdef __PX4_NUTTX
// Make sure this is defined, this is a kernel module
#define __KERNEL__

Choose a reason for hiding this comment

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

why not just add something like "target_compile_options(mmymodule.... PRIVATE -D__KERNEL__)" into CMakeLists.txt for the module, which compiles this and goes into kernel? This is fine as well, don't really care :)

Copy link
Author

Choose a reason for hiding this comment

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

Yes this is the preferred way but in this particular case, the library that takes shutdown.cpp is px4_platform and it is unambiguous where it goes. It is still not obvious / clear to me how that library should be handled. It is still just a massive mess in my head.

Copy link
Author

Choose a reason for hiding this comment

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

I separated shutdown into its own target, now its compile time flags can be adjusted

@pussuw pussuw force-pushed the reboot_fix_kernel branch 2 times, most recently from 7c3d6dc to a259ef0 Compare July 28, 2023 07:29
@pussuw
Copy link
Author

pussuw commented Aug 9, 2023

Hmm now that I look at this removing reboot/shutdown from user should be unnecessary. I think the problem is like with mavlink cdcacm checker, i.e. the user work queue is not running in kernel mode:

void cdcacm_init(void)
{
#ifdef CONFIG_BUILD_KERNEL
	// Must start the worker as it is not automatically started by the system
	work_usrstart();
#endif
	work_queue(LPWORK, &usb_serial_work, mavlink_usb_check, nullptr, 0);
}

@pussuw
Copy link
Author

pussuw commented Aug 9, 2023

What I was wondering is what the shutdown hooks in shutdown.cpp are for. Only reference I can find is this:

px4_register_shutdown_hook(&Logger::request_stop_static);

Must provide hartid to __start() as per SBI spec. In flat mode this is
not strictly necessary as it is obtained during the start process, but
for kernel mode this is mandatory.
The userspace work queue is not started automatically by the system,
so start it when dispatching the shutdown command.

It would be best if there was an init function for shutdown.cpp but this
"lazy" init is just fine too.
Copy link

@jlaitine jlaitine left a comment

Choose a reason for hiding this comment

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

LGTM

@pussuw pussuw merged commit af1a62f into main Aug 17, 2023
19 checks passed
@pussuw pussuw deleted the reboot_fix_kernel branch August 17, 2023 08:32
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.

2 participants