Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow scripts to get modes #13213

Merged
merged 8 commits into from
Jan 14, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions APMrover2/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,7 @@ class Rover : public AP_Vehicle {
void update_ahrs_flyforward();
bool set_mode(Mode &new_mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
bool mavlink_set_mode(uint8_t mode);
void startup_INS_ground(void);
void notify_mode(const Mode *new_mode);
Expand Down
1 change: 1 addition & 0 deletions AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,7 @@ class Tracker : public AP_Vehicle {
void prepare_servos();
void set_mode(Mode &newmode, ModeReason reason);
bool set_mode(uint8_t new_mode, ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)mode->number(); }
bool should_log(uint32_t mask);
bool start_command_callback(const AP_Mission::Mission_Command& cmd) { return false; }
void exit_mission_callback() { return; }
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -796,6 +796,7 @@ class Copter : public AP_Vehicle {
// mode.cpp
bool set_mode(Mode::Number mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)control_mode; }
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we discussed on the call that we should probably make this use the control->mode_number() like the other vehicles (if possible).

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm done. #13431

void update_flight_mode();
void notify_flight_mode();

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -901,6 +901,7 @@ class Plane : public AP_Vehicle {
bool set_mode(Mode& new_mode, const ModeReason reason);
bool set_mode(const uint8_t mode, const ModeReason reason) override;
bool set_mode_by_number(const Mode::Number new_mode_number, const ModeReason reason);
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
Mode *mode_from_mode_num(const enum Mode::Number num);
void check_long_failsafe();
void check_short_failsafe();
Expand Down
1 change: 1 addition & 0 deletions ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -540,6 +540,7 @@ class Sub : public AP_Vehicle {
void fence_check();
bool set_mode(control_mode_t mode, ModeReason reason);
bool set_mode(const uint8_t mode, const ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)control_mode; }
void update_flight_mode();
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
bool mode_requires_GPS(control_mode_t mode);
Expand Down
1 change: 1 addition & 0 deletions Tools/Replay/Replay.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ class ReplayVehicle : public AP_Vehicle {
void load_parameters(void);

virtual bool set_mode(const uint8_t new_mode, const ModeReason reason) override { return true; }
virtual uint8_t get_mode() const override { return 0; }

AP_Vehicle::FixedWing aparm;
AP_Airspeed airspeed;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,7 @@ singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM
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
singleton AP_Vehicle method get_mode uint8_t

include AP_SerialLED/AP_SerialLED.h
singleton AP_SerialLED alias serialLED
Expand Down
16 changes: 15 additions & 1 deletion libraries/AP_Scripting/lua_generated_bindings.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// auto generated bindings, don't manually edit
// auto generated bindings, don't manually edit. See README.md for details.
#include "lua_generated_bindings.h"
#include "lua_boxed_numerics.h"
#include <RC_Channel/RC_Channel.h>
Expand Down Expand Up @@ -625,6 +625,19 @@ static int AP_SerialLED_set_num_LEDs(lua_State *L) {
return 1;
}

static int AP_Vehicle_get_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, 1);
const uint8_t data = ud->get_mode();

lua_pushinteger(L, data);
return 1;
}

static int AP_Vehicle_set_mode(lua_State *L) {
AP_Vehicle * ud = AP_Vehicle::get_singleton();
if (ud == nullptr) {
Expand Down Expand Up @@ -1782,6 +1795,7 @@ const luaL_Reg AP_SerialLED_meta[] = {
};

const luaL_Reg AP_Vehicle_meta[] = {
{"get_mode", AP_Vehicle_get_mode},
{"set_mode", AP_Vehicle_set_mode},
{NULL, NULL}
};
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/lua_generated_bindings.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#pragma once
// auto generated bindings, don't manually edit
// auto generated bindings, don't manually edit. See README.md for details.
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_SerialLED/AP_SerialLED.h>
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
static AP_Vehicle *get_singleton();

bool virtual set_mode(const uint8_t new_mode, const ModeReason reason) = 0;
uint8_t virtual get_mode() const = 0;

/*
common parameters for fixed wing aircraft
Expand Down