I am tying to interface Feetech’s sts3032 servos and since it is not supported directly by ardupilot I try to utilize lua scripting and maybe later I ll try to integrate it into the code as well.
The servos communicate with UART and they use a custom protocol to parse the data. So as a first step I try just to send a “ping” message which is a 6 byte message. The problem is that I can not make my Flight controller output not even a single byte. Tested with oscilloscope and the Tx line does nothing. Below you can see my setup.
Flight Controller: Pixhawk 4 with latest Arduplane (1 week ago)
I tried serial 4 with the pinout seen here (I also tried serial 1 just in case)
I made the appropriate configurations and run successfully a hello world lua script.
Configured serial4_protocol to 28 (scripting).
Very simple script to just send a byte every 100 ms. The port “opens” successfully (no nil error)
local port = serial:find_serial(0)
if not port then
gcs:send_text(0, "No Scripting Serial Port")
return
end
port:begin(1000000) -- also tried 115200 without success
port:set_flow_control(0)
function update ()
gcs:send_text(0, "Sending byte!")
message = tonumber(0xA4)
port:write(message)
gcs:send_text(0, "Exiting!")
return update, 100
end
return update, 100
Am I missing anything, perhaps any SERIALx_… configuration?
I tried a valid baud rate (115200), with no success. In any case the servos need 1000000 baud rate. Wouldn’t that be feasible?
Made sure that no other UART is using 28.
Not quite sure what do you mean by “Confirm the GCS messages are displayed (and flood the messages screen)?”. I can see regular messages (“Sending byte”, "exiting’), nothing weird is happening.
I just had a look at the source code, and it does appear that a custom baud rate should be possible.
Make sure you’re measuring the correct pin with a proper ground reference. Make sure you’re using the correct physical port, as well (sometimes the numbering is confusing).
Also, tonumber(0xA4) is doing exactly nothing for you. 0xA4 is already a number in hexadecimal notation.
I just wrote a fairly complex serial driver for a ModBus sensor entirely in ArduPilot Lua, and all works fine, so there should be no issues with the firmware or scripting engine.
EDIT:
I also just tested an exact copy/paste of your script, and it works fine on a Cube Orange+ (to include the fast baud rate).
In fact, I found that a reboot isn’t even required when changing the baud rate using port:begin() (just use Mission Planner’s Action tab to restart the scripting engine after uploading an updated script).
While we’re at it…
Your first two lines probably ought to look like this:
local port = serial:find_serial(0)
assert(port, 'No scripting serial port found!')
Which will cause your script to fail rather than continue if a serial port is not configured (likely the desired behavior).
The issue is resolved. It turned out to be a wrong pin as you mentioned. The misunderstanding occurred while referencing here to find the pin numbering. This is for the pixhawk 6c. There it states that pin number 1 is on the right side.