What do you mean by showing up? If its in ROMFS it is hard coded with the firmware, the only way to change is to flash firmware. However it should certainty not be running if scripting and the ROMFS directory is disabled.
Originally on the Script tab of MP I loaded mission-edit-demo.lua. At the time a python error popped up and I just cancelled it and went back to loading my own scripts directly with MAVftp. When I run a mission, I am getting messages that originate from the mission-edit-demo script. This script is not anywhere in my ftp directories, so I presume it is in ROFMS.
I flash the firmware, load my saved configuration and the mission edit messages reappear even with the ROFMS sub-directory disabled. Very puzzling.
Is there anywhere in MP where this script could be hiding?
Mission planner scripting is unrelated to ArduPilot scripting except by name. Mission planner uses python AP uses lua. Sounds like you have loaded a AP lua script into Mission planner and it is giving the error.
One final question Peter. If I load a mission file using the LOAD FILE button in mission planner, the coordinates come in perfectly with 8 decimal accuracy. When I use Lua scripts I get the rounding errors.Is it because Mission Panner is loading from a python module?
I’ve written a Python script that creates very precise coordinates for my missions using the Vincenty Formula and writes them to a txt (or waypoints) file in the Mission Planner format. So far the only way I can load them accurately is manually with the Load Files button. Would like to automate this somehow.
I would guess its due to the way your script works, lua is only 32 bit float, you have to be quite careful to keep the value as a int for as long as possible. I would have to see your script to try and spot the issue.
Hello Pete, to add to the above discussion …
After lengthy testing of every Lua string/math function (string.format, string.pack/unpack, math.whatever, simple mathematical division/multiplication) the results are very clear. The Lua math interpreter needs fixing. Currently ANY math function will yield a result with exactly 7 digits (integer or float). Any attempt to work with larger numbers results in an error " number has no integer representation". Even if something seems to work, the results end up being randomly rounded as noted by Yuri. Working with RTK GPS, anything less than 8 decimal accuracy is unacceptable. There have been many other situations where this Lua math issue has created challenges.
Just bringing this to your attention. The issue isn’t the Type. A 32-bit float value should easily provide 8 decimal results.
Is this something that could/should be reviewed by the Ardupilot development team?
Thanks in advance, for your consideration of this question.
Can you provide a basic script that shows this issue.
My apologies, hat in hand.
Re-reading Yuri’s comments above, I now understand the uint32_t solution. I’ve seen the code in various Lua script examples but didn’t grasp the significance/application.
Always learning
Here’s a sample to show how the Lua math works.
Lau_math.lua (1.1 KB)
This topic may be somewhat outdated but it resurfaced for me when I tested the “mission-save.lua” from the lua script examples. Starting with a mission plan in the AP memory, I use the script to save it to the SD file, however the written plan is only accurate to 5 decimal points corrupting the mission plan where less than 1m spatial precision is expected
Now with the intent to use Yury’s solution, I need to access the latitude and longitude values in memory as strings so that I can avoid the floating point truncation. Is this even possible, as the data is already in memory? Any suggestions?
tostring(item:x())
I already tried this and numbers are converted to string after they are truncated. Here is a small test code and the output:
CODE:
gcs:send_text(0,string.format(“>>>%s”,tostring(-42.123456789)))
OUTPUT:
-42.12346
Inside the actual program to save the mission,
CODE:
file:write(string.format(‘%i\t0\t%i\t%i\t%0.12f\t%.12f\t%.12f\t%.12f\t%s\t%s\t%s\t1\n’,item:seq(),item:frame(),item:command(),item:param1(),item:param2(),item:param3(),item:param4(),tostring(item:x()),tostring(item:y()),tostring(item:z())))
OUTPUT (just outputting the first waypoint):
2 0 3 16 0.000000000000 0.000000000000 0.000000000000 0.000000000000 -199842757 -466592987 8.0 1
vs the original input values for the waypoint:
2 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -19.98430870 -46.65925200 8.0 1
The round-off / truncation is apparent at the 5th digit after the decimal point - back to square one.
By the way, these are outputs of the SITL in Mission Planner. I read some points about some kind of Python wrapper causing the truncation before numbers arrive at LUA. Would things look different, if I ran the codes inside Pixhawk?
Mission item coordinates are stored as integers.
Convert the integer to a string. Use string manipulation to insert a decimal point as desired. That’s the whole point of this topic.
Thanks Yury!
I got the issue resolved and there are 2 sides of the coin:
- Loading a mission
- Saving a mission
-
For the mission load, your function “strf_to_stri” works like a charm. As for usage, the following replacements were made:
local ret, _, seq, curr, frame, cmd, p1, p2, p3, p4, x, y, z, autocont = string.find(line, “^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)”) --OLD
…
item:x(math.floor(tonumber(x)*10^7)) --OLD
item:y(math.floor(tonumber(y)*10^7)) --OLDlocal ret, _, seq, curr, frame, cmd, p1, p2, p3, p4, x_s, y_s, z, autocont = string.find(line, “^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%S+)%s+(%S+)%s+(%d+)”) --NEW
…
item:x(strf_to_stri(x_s)) --NEW
item:y(strf_to_stri(y_s)) --NEW
[@tridge and @iampete, I recommend the above changes to ardupilot/libraries/AP_Scripting/examples/mission-load.lua at master · ArduPilot/ardupilot · GitHub, lines 31,48,49 along with Yury’s “strf_to_stri” function inclusion]
- For the mission save, I created a function that does the opposite of your function:
function stri_to_strf(x)
str=tostring(x)
decimloc=string.len(str)-7
return str:sub(1, decimloc)…“.”…str:sub(decimloc+1, string.len(x))
end
As for usage, the following replacement was made:
file:write(string.format(‘%i\t0\t%i\t%i\t%.8f\t%.8f\t%.8f\t%.8f\t%.8f\t%.8f\t%.8f\t1\n’,item:seq(),item:frame(),item:command(),item:param1(),item:param2(),item:param3(),item:param4(),item:x()*10^-7,item:y()*10^-7,item:z())) --OLD
file:write(string.format(‘%i\t0\t%i\t%i\t%.8f\t%.8f\t%.8f\t%.8f\t%s\t%s\t%.8f\t1\n’,item:seq(),item:frame(),item:command(),item:param1(),item:param2(),item:param3(),item:param4(),stri_to_strf(tostring(item:x())),stri_to_strf(tostring(item:y())),item:z())) --NEW
[@tridge and @iampete, I recommend the above changes to ardupilot/libraries/AP_Scripting/examples/mission-save.lua at master · ArduPilot/ardupilot · GitHub, line 37 along with the inclusion of the “stri_to_strf” function]
With the above changes, we can make the best of GPS-RTK precision during LUA script manipulations…
Regards
Cem