ESC feedback
-
Question from customer - the modalai esc is working fine when commanded, but the RPM and voltage feedback is not available. I have attached a screenshot of the modalai_esc status which shows the feedback isn't coming in. I checked the connections, they seem fine.
-
Hello, thanks for reporting. Good news is we already have a fix in for via this commit:
https://github.com/modalai/px4-firmware/commit/577fec3b9a843b709086fc07b913b2c194367e10It's slated to release in our next platform release (platform release 0.9), I can't mention the release date, as the release gods will then delay it... but we are getting close!!!!!
There are pre-release channels available for developers, captured here: https://docs.modalai.com/configure-pkg-manager/#dev
-
Hey, thanks for that. I was able to pull the voxl-dev branch and got it working on the VOXL2, I can see the feedback of the RPM on the mavlink topic SERVO_OUTPUT_RAW. But the frequency is at 10Hz.
When I try to use the following commandmavlink stream -u "port_number" -s SERVO_OUTPUT_RAW -r 100
I get an error stream SERVO_OUTPUT_RAW not found
From the uart_esc code in px4-firmware I see that the uorb topic thats being used for RPM information is ESC_STATUS. And doing the following commands yields no result. The frequency is still 10Hz
mavlink stream -u "port_number" -s ESC_STATUS -r 100
mavlink stream -u "port_number" -s ESC_INFO -r 100
Is there anything I can do to increase the frequency of the message ?
-
Sorry for the lag, what if you use
px4-listener esc_status
?If it's showing up there, likely we need to modify something to get this offboard....
-
So when i try px4-listener it says command not found.
The command that works is
listener esc_status
This produces the following resutls
never publishedBut after some investigation, the uorb topic with the rpm information is
actuator_outputsI can read the output
This topic is being published at 500Hz
I tried to increase the rate of the following mavlink topics
mavlink stream -u 15446 -s actuator_output -r 100
mavlink stream -u 15446 -s ACTUATOR_OUTPUT -r 100
mavlink stream -u 15446 -s actuator_outputs -r 100
mavlink stream -u 15446 -s ACTUATOR_OUTPUTS -r 100Which results in the following error message
ERROR [mavlink] stream ACTUATOR_OUTPUTS not found (same for all other) -
Fixed the problem, the mavlink stream name is SERVO_OUTPUT_RAW_0.
changing that to 200Hz gives us the RPM feedback at 200Hz on mavros