mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Allow scripts to set the mode
This commit is contained in:
parent
b0f66237de
commit
38c71f875d
|
@ -135,3 +135,7 @@ include GCS_MAVLink/GCS.h
|
||||||
singleton GCS alias gcs
|
singleton GCS alias gcs
|
||||||
singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string
|
singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string
|
||||||
singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t 0U UINT32_MAX int32_t -1 INT32_MAX
|
singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t 0U UINT32_MAX int32_t -1 INT32_MAX
|
||||||
|
|
||||||
|
include AP_Vehicle/AP_Vehicle.h
|
||||||
|
singleton AP_Vehicle alias vehicle
|
||||||
|
singleton AP_Vehicle method set_mode boolean uint8_t 0 UINT8_MAX ModeReason::SCRIPTING'literal
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
// auto generated bindings, don't manually edit
|
// auto generated bindings, don't manually edit
|
||||||
#include "lua_generated_bindings.h"
|
#include "lua_generated_bindings.h"
|
||||||
#include "lua_boxed_numerics.h"
|
#include "lua_boxed_numerics.h"
|
||||||
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Relay/AP_Relay.h>
|
#include <AP_Relay/AP_Relay.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
|
@ -472,6 +473,24 @@ const luaL_Reg Location_meta[] = {
|
||||||
{NULL, NULL}
|
{NULL, NULL}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static int AP_Vehicle_set_mode(lua_State *L) {
|
||||||
|
AP_Vehicle * ud = AP_Vehicle::get_singleton();
|
||||||
|
if (ud == nullptr) {
|
||||||
|
return luaL_argerror(L, 1, "vehicle not supported on this firmware");
|
||||||
|
}
|
||||||
|
|
||||||
|
binding_argcheck(L, 2);
|
||||||
|
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
|
||||||
|
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(UINT8_MAX, UINT8_MAX))), 2, "argument out of range");
|
||||||
|
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||||
|
const bool data = ud->set_mode(
|
||||||
|
data_2,
|
||||||
|
ModeReason::SCRIPTING);
|
||||||
|
|
||||||
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
static int GCS_set_message_interval(lua_State *L) {
|
static int GCS_set_message_interval(lua_State *L) {
|
||||||
GCS * ud = GCS::get_singleton();
|
GCS * ud = GCS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
|
@ -1542,6 +1561,11 @@ static int AP_AHRS_get_roll(lua_State *L) {
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const luaL_Reg AP_Vehicle_meta[] = {
|
||||||
|
{"set_mode", AP_Vehicle_set_mode},
|
||||||
|
{NULL, NULL}
|
||||||
|
};
|
||||||
|
|
||||||
const luaL_Reg GCS_meta[] = {
|
const luaL_Reg GCS_meta[] = {
|
||||||
{"set_message_interval", GCS_set_message_interval},
|
{"set_message_interval", GCS_set_message_interval},
|
||||||
{"send_text", GCS_send_text},
|
{"send_text", GCS_send_text},
|
||||||
|
@ -1673,6 +1697,7 @@ const struct userdata_meta userdata_fun[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
const struct userdata_meta singleton_fun[] = {
|
const struct userdata_meta singleton_fun[] = {
|
||||||
|
{"vehicle", AP_Vehicle_meta, NULL},
|
||||||
{"gcs", GCS_meta, NULL},
|
{"gcs", GCS_meta, NULL},
|
||||||
{"relay", AP_Relay_meta, NULL},
|
{"relay", AP_Relay_meta, NULL},
|
||||||
{"terrain", AP_Terrain_meta, AP_Terrain_enums},
|
{"terrain", AP_Terrain_meta, AP_Terrain_enums},
|
||||||
|
@ -1723,6 +1748,7 @@ void load_generated_bindings(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
const char *singletons[] = {
|
const char *singletons[] = {
|
||||||
|
"vehicle",
|
||||||
"gcs",
|
"gcs",
|
||||||
"relay",
|
"relay",
|
||||||
"terrain",
|
"terrain",
|
||||||
|
|
|
@ -1,5 +1,6 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
// auto generated bindings, don't manually edit
|
// auto generated bindings, don't manually edit
|
||||||
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Relay/AP_Relay.h>
|
#include <AP_Relay/AP_Relay.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
|
|
Loading…
Reference in New Issue