Lua Script¶
Command Reference¶
The following commands are made available to Lua scripts by the TaskHandler module.
Commands denoted void
return true
or false
depending on whether the
command succeeded. Commands with a return type either return a value of that
type or nil
if the command failed.
See https://en.wikipedia.org/wiki/Lua_(programming_language) for more information regarding the Lua script language itself.
Movement¶
The commands in this section take an optional parameter of type pilot.goal_options_t. If not given, the default values are used.
-
void
move_to_station
(string name, goal_options_t options)¶ Moves the platform to the station named
name
.
-
void
move_to_position
(Pose2D position, goal_options_t options)¶ Moves the platform to the given position. See pilot.Pose2D.
-
void
move_to
(MapStation station, goal_options_t options)¶ Moves the platform to the place described by
station
. It may or may not be a station of the Road Map. See pilot.MapStation.
-
void
move
(double dx, double dy, double dr, goal_options_t options)¶ Moves the platform in the given direction, as seen from the platform’s point of view (relative to
base_link
). See Coordinate Systems.
-
void
cancel_goal
()¶ Cancels the current goal (if any) which causes the platform to stop moving and the corresponding move command to fail. This command can be useful in an event handler.
User Input¶
-
int
wait_for_joystick
()¶ Waits until any button on the active joystick is pressed and returns the ID of the button.
Waits until the button with ID
button
is pressed on the active joystick.
-
void
wait_for_digital_input
(int channel, bool state)¶ Waits until the digital input
channel
reaches statestate
. The digital inputs are enumerated from 0 to 15.
-
void
wait_ms
(int period)¶ Pauses for
period
milliseconds.
-
void
wait_sec
(int period)¶ Pauses for
period
seconds.
-
void
wait_min
(int period)¶ Pauses for
period
minutes.
-
void
wait_hours
(int period)¶ Pauses for
period
hours.
Hardware¶
-
void
set_relay
(int channel, bool state)¶ Sets the relay with id
channel
to statestate
.
-
void
set_digital_output
(int channel, bool state)¶ Sets the digital output with id
channel
to statestate
. The digital outputs are enumerated from 0 to 15.
-
void
set_display_text
(string text)¶ Prints
text
on the first line of the LCD display. There is enough space for 20 characters.
-
void
charge
()¶ Starts the charging process. Fails immediately if no charger is detected. Otherwise blocks until the charging is either finished or aborted.
-
void
start_charging
()¶ Starts the charging process, i.e. activates the corresponding relay.
-
void
stop_charging
()¶ Stops the charging process, i.e. deactivates the corresponding relay.
Information Requests¶
-
Pose2D
get_position
()¶ Returns the current position on the map. See pilot.Pose2D.
-
MapNode
find_station
(string name)¶ Finds and returns the node / station called
name
. See pilot.MapStation and See pilot.MapNode.
Log¶
-
void
log_info
(string message)¶ Generates a log message with priority INFO.
-
void
log_warn
(string message)¶ Generates a log message with priority WARN.
-
void
log_error
(string message)¶ Generates a log message with priority ERROR.
Control Flow¶
-
void
block
()¶ Pauses execution of the main thread.
Warning
Only use in event handlers!
-
void
unblock
()¶ Resumes execution of the main thread.
Warning
Only use in event handlers!
Builtin Functions¶
-
bool
auto_charge
(string pre_stage1, string pre_stage2, string charge_station, float undock_distance, float max_velocity)¶ Automatically docks at a specified charging station, charges the batteries until full and then undocks from the station.
pre_stage1
is a map station somewhere close (less than 1 m) to the charging station with an orientation close to the final docking pose. There should still be enough space to rotate fully without hitting the charging station.pre_stage2
is a map station from where to start the docking process without having to rotate anymore. There should be about 10 to 20 cm of space between the contacts at this position.charge_station
is a map station where the platform makes contact with the charging station. It should be specified very precisely, within a few mm of accuracy.undock_distance
is the amount of distance to move backwards after finishing the charging process. The default is 0.25 m. Make sure the robot is allowed to move this much backwards, in case of a differential platform without a second laser scanner.max_velocity
is the maximum velocity in [m/s] with which to dock and undock. The default is 0.05 m/s.Returns true if successful, false otherwise.
A
require 'neobotix'
is needed to access this function in Lua script. PermissionsMOVE
andCHARGE
are required, see pilot.permission_e.
OPC-UA Functions¶
UA node ids are specified in Lua via an array of two values.
Numeric and string node ids are supported as follows: {0, 1337}
or {1, "MyObject"}
.
A require 'neobotix'
is needed to access these functions in Lua script.
-
Variant
opc_ua_call
(string proxy, pair<ushort, Variant> object, string method, vector<Variant> args)¶ Performs an OPC-UA call via the specified
proxy
and returns the result of it.proxy
is the name of a running vnx.opc_ua.Proxy module, see opcua_proxy_map.object
is an optional UA node id of the object for which to call the method.method
is the method name.args
is an array of function parameters.In case of failure
nil
orfalse
is returned, depending on if the method has a return value (nil) or not (false). In case of multiple return values an array is returned.
-
Variant
opc_ua_read
(string proxy, pair<ushort, Variant> object, string variable)¶ Reads an OPC-UA variable via the specified
proxy
.proxy
is the name of a running vnx.opc_ua.Proxy module, see opcua_proxy_map.object
is a UA node id of the object containing the variable.variable
is the variable name.Returns the value read, or
nil
in case of failure.
-
Variant
opc_ua_read_global
(string proxy, pair<ushort, Variant> variable)¶ Reads a global OPC-UA variable via the specified
proxy
.proxy
is the name of a running vnx.opc_ua.Proxy module, see opcua_proxy_map.variable
is a UA node id of a global variable.Returns the value read, or
nil
in case of failure.
Advanced¶
-
Variant
execute
(string module, string method, Object params)¶ Executes a function
method
of the modulemodule
. The parameters are specified as key-value pairs inparams
.If
method
does not have a return type, the command returnstrue
orfalse
, depending on whether it succeeded. Ifmethod
does have a return type, either a value of that type is returned ornil
on failure.See vnx.Variant and vnx.Object.
Warning
This command allows almost unlimited access to the functionality of PlatformPilot. However, it also allows you to leave the boundaries of safe operation and must therefore be considered dangerous.
Event Handlers¶
The following functions, if defined in your script, will be called upon specific events. Events are queued and the next event handler will only be called after the current one finished.
Be aware that the calls happen asynchronously to the main thread.
The two executions run in parallel while abiding to Lua’s
cooperative multithreading
model.
You can use the block()
and unblock()
functions to
avoid multithreading issues.
-
void
on_em_stop
()¶ Is executed when the emergency stop button is pushed.
-
void
on_scanner_stop
()¶ Is executed when the scanner emergency stop is triggered.
-
void
on_em_reset
()¶ Is executed when a previous emergency situation (button and/or scanner) is resolved and the platform can move again.
Is executed when the joystick button with ID
button
changes its state from not pressed to pressed.
Is executed when the joystick button with ID
button
canges its state from pressed to not pressed.
-
void
on_digital_input_on
(int channel)¶ Is executed when the digital input
channel
changes its state from off to on.
-
void
on_digital_input_off
(int channel)¶ Is executed when the digital input
channel
changes its state from on to off.
-
void
on_battery_low
()¶ Is executed when the battery drops below a low level.
-
void
on_battery_critical
()¶ Is executed when the battery drops below a critical level.
Examples¶
Move to stations in the Road Map in a loop:
function main()
while true do
move_to_station("Station4");
move_to_station("Station9");
move_to_station("Station11");
wait_ms(1000);
end
end
Move randomly to any of the specified stations in a loop, abort in case of failure:
function odyssey(stations)
repeat
wait_ms(1000);
index = math.random(1, #stations)
until not move_to_station(stations[index])
end
function main()
odyssey({"Station20", "Station10", "Station12", "Station14", "Station1"})
end
Dock to a charging station using special parameters:
move_to_station("ChargeStation", {
max_velocity = 0.1,
drive_flags = {"IGNORE_FOOTPRINT", "DISABLE_ROTATION"}
})
Undock from a charging station using a relative move command with special parameters:
move(-0.25, 0, 0, {
max_velocity = 0.1,
drive_flags = {"IGNORE_FOOTPRINT", "DISABLE_ROTATION"}
})
Using the built-in auto_charge(...)
function to dock, charge and undock:
require 'neobotix'
function main()
auto_charge("PreStage1", "PreStage2", "ChargeStation", 0.25, 0.05);
end
Calling an OPC-UA method:
require 'neobotix'
function main()
ret = opc_ua_call("OPC_UA_Proxy", {1, "vnx.process"}, "get_name")
log_warn(ret) --> "pilot_main"
ret = opc_ua_call("OPC_UA_Proxy", {1, "HybridPlanner"}, "set_goal_stations", {
{"Station4", "Station3", "Station2"}
})
end
With opcua_proxy_map
set to [["OPC_UA_Proxy", "opc.tcp://127.0.0.1:4840"]]
and enable_opcua_server
set to true
.
Reading an OPC-UA variable:
require 'neobotix'
function main()
ret = opc_ua_read("OPC_UA_Proxy", {0, 2253}, "ServerArray")
log_warn(ret) --> ["urn:open62541.server.application"]
end
With opcua_proxy_map
set to [["OPC_UA_Proxy", "opc.tcp://127.0.0.1:4840"]]
and enable_opcua_server
set to true
.