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

AP_Scripting: add missing defines to build on Periph #25183

Merged
merged 9 commits into from
Oct 16, 2023
33 changes: 33 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -351,3 +351,36 @@
#ifndef AP_HAL_CHIBIOS_IN_EXPECTED_DELAY_WHEN_NOT_INITIALISED
#define AP_HAL_CHIBIOS_IN_EXPECTED_DELAY_WHEN_NOT_INITIALISED 0
#endif

#ifndef AP_SERIALLED_ENABLED
#define AP_SERIALLED_ENABLED 0
#endif

#ifndef AP_OPTICALFLOW_ENABLED
#define AP_OPTICALFLOW_ENABLED 0
#endif

#ifndef HAL_BUTTON_ENABLED
#define HAL_BUTTON_ENABLED 0
#endif

#ifndef AP_NOTIFY_SCRIPTING_LED_ENABLED
#define AP_NOTIFY_SCRIPTING_LED_ENABLED 0
#endif

#ifndef AP_PARAM_DYNAMIC_ENABLED
#define AP_PARAM_DYNAMIC_ENABLED 0
#endif

#ifndef HAL_MOUNT_ENABLED
#define HAL_MOUNT_ENABLED 0
#endif

#ifndef AP_CAMERA_ENABLED
#define AP_CAMERA_ENABLED 0
#endif

#ifndef AP_TERRAIN_AVAILABLE
#define AP_TERRAIN_AVAILABLE 0
#endif

2 changes: 2 additions & 0 deletions libraries/AP_Param/AP_Param.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,9 @@
#endif

// allow for dynamically added tables when scripting enabled
#ifndef AP_PARAM_DYNAMIC_ENABLED
#define AP_PARAM_DYNAMIC_ENABLED AP_SCRIPTING_ENABLED
#endif

// maximum number of dynamically created tables (from scripts)
#ifndef AP_PARAM_MAX_DYNAMIC
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Scripting/AP_Scripting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,6 +304,7 @@ void AP_Scripting::thread(void) {

void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd_in)
{
#if AP_MISSION_ENABLED
if (!_enable) {
return;
}
Expand All @@ -328,6 +329,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd
AP_HAL::millis()};

mission_data->push(cmd);
#endif
}

bool AP_Scripting::arming_checks(size_t buflen, char *buffer) const
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_Scripting/AP_Scripting.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,12 +84,13 @@ class AP_Scripting
uint8_t num_i2c_devices;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> *_i2c_dev[SCRIPTING_MAX_NUM_I2C_DEVICE];

#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if AP_SCRIPTING_CAN_SENSOR_ENABLED
// Scripting CAN sensor
ScriptingCANSensor *_CAN_dev;
ScriptingCANSensor *_CAN_dev2;
#endif

#if AP_MISSION_ENABLED
// mission item buffer
static const int mission_cmd_queue_size = 5;
struct scripting_mission_cmd {
Expand All @@ -100,6 +101,7 @@ class AP_Scripting
uint32_t time_ms;
};
ObjectBuffer<struct scripting_mission_cmd> * mission_data;
#endif

// PWMSource storage
uint8_t num_pwm_source;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Scripting/AP_Scripting_CANSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
*/
#include "AP_Scripting_CANSensor.h"

#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if AP_SCRIPTING_CAN_SENSOR_ENABLED

// handler for outgoing frames, using uint32
bool ScriptingCANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
Expand Down Expand Up @@ -79,4 +79,4 @@ void ScriptingCANBuffer::add_buffer(ScriptingCANBuffer* new_buff) {
next->add_buffer(new_buff);
}

#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
#endif // AP_SCRIPTING_CAN_SENSOR_ENABLED
14 changes: 12 additions & 2 deletions libraries/AP_Scripting/AP_Scripting_CANSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,19 @@

#pragma once

#include <AP_HAL/AP_HAL.h>

#if defined(HAL_BUILD_AP_PERIPH)
// Must have at least two CAN ports on Periph
#define AP_SCRIPTING_CAN_SENSOR_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS > 1)
#else
#define AP_SCRIPTING_CAN_SENSOR_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS
#endif

#if AP_SCRIPTING_CAN_SENSOR_ENABLED

#include <AP_CANManager/AP_CANSensor.h>

#if HAL_MAX_CAN_PROTOCOL_DRIVERS
class ScriptingCANBuffer;
class ScriptingCANSensor : public CANSensor {
public:
Expand Down Expand Up @@ -76,4 +86,4 @@ class ScriptingCANBuffer {

};

#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
#endif // AP_SCRIPTING_CAN_SENSOR_ENABLED
9 changes: 8 additions & 1 deletion libraries/AP_Scripting/AP_Scripting_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,5 +3,12 @@
#include <AP_HAL/AP_HAL_Boards.h>

#ifndef AP_SCRIPTING_ENABLED
#define AP_SCRIPTING_ENABLED BOARD_FLASH_SIZE > 1024
#define AP_SCRIPTING_ENABLED (BOARD_FLASH_SIZE > 1024)
#endif

#if AP_SCRIPTING_ENABLED
#include <AP_Filesystem/AP_Filesystem_config.h>
#if !AP_FILESYSTEM_FILE_READING_ENABLED
#error "Scripting requires a filesystem"
#endif
#endif
38 changes: 31 additions & 7 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ userdata Location method offset void float'skip_check float'skip_check
userdata Location method offset_bearing void float'skip_check float'skip_check
userdata Location method offset_bearing_and_pitch void float'skip_check float'skip_check float'skip_check
userdata Location method get_vector_from_origin_NEU boolean Vector3f'Null
userdata Location method get_vector_from_origin_NEU depends AP_AHRS_ENABLED
userdata Location method get_bearing float Location
userdata Location method get_distance_NED Vector3f Location
userdata Location method get_distance_NE Vector2f Location
Expand All @@ -25,6 +26,7 @@ userdata Location method copy Location
include AP_AHRS/AP_AHRS.h

singleton AP_AHRS rename ahrs
singleton AP_AHRS depends AP_AHRS_ENABLED
singleton AP_AHRS semaphore
singleton AP_AHRS method get_roll float
singleton AP_AHRS method get_pitch float
Expand Down Expand Up @@ -61,6 +63,7 @@ singleton AP_AHRS method get_quaternion boolean Quaternion'Null
include AP_Arming/AP_Arming.h

singleton AP_Arming rename arming
singleton AP_Arming depends (!defined(HAL_BUILD_AP_PERIPH))
singleton AP_Arming method disarm boolean AP_Arming::Method::SCRIPTING'literal
singleton AP_Arming method is_armed boolean
singleton AP_Arming method pre_arm_checks boolean false'literal
Expand All @@ -72,6 +75,7 @@ singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string
include AP_BattMonitor/AP_BattMonitor.h

singleton AP_BattMonitor rename battery
singleton AP_BattMonitor depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY))
singleton AP_BattMonitor method num_instances uint8_t
singleton AP_BattMonitor method healthy boolean uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method voltage float uint8_t 0 ud->num_instances()
Expand All @@ -89,6 +93,7 @@ singleton AP_BattMonitor method reset_remaining boolean uint8_t 0 ud->num_instan

include AP_GPS/AP_GPS.h

singleton AP_GPS depends (AP_GPS_ENABLED && (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_GPS)))
singleton AP_GPS rename gps
singleton AP_GPS enum NO_GPS NO_FIX GPS_OK_FIX_2D GPS_OK_FIX_3D GPS_OK_FIX_3D_DGPS GPS_OK_FIX_3D_RTK_FLOAT GPS_OK_FIX_3D_RTK_FIXED
singleton AP_GPS method num_sensors uint8_t
Expand Down Expand Up @@ -145,6 +150,7 @@ userdata Vector2f operator +
userdata Vector2f operator -
userdata Vector2f method copy Vector2f

userdata Quaternion depends AP_AHRS_ENABLED
userdata Quaternion field q1 float'skip_check read write
userdata Quaternion field q2 float'skip_check read write
userdata Quaternion field q3 float'skip_check read write
Expand All @@ -164,6 +170,7 @@ userdata Quaternion method from_angular_velocity void Vector3f float'skip_check

include AP_Notify/AP_Notify.h
singleton AP_Notify rename notify
singleton AP_Notify depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_NOTIFY))
singleton AP_Notify method play_tune void string
singleton AP_Notify method handle_rgb void uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
singleton AP_Notify method handle_rgb_id void uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
Expand All @@ -190,12 +197,14 @@ singleton AP_Proximity method get_backend AP_Proximity_Backend uint8_t'skip_chec
include AP_RangeFinder/AP_RangeFinder.h
include AP_RangeFinder/AP_RangeFinder_Backend.h

ap_object AP_RangeFinder_Backend depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER))
ap_object AP_RangeFinder_Backend method distance float
ap_object AP_RangeFinder_Backend method orientation Rotation'enum
ap_object AP_RangeFinder_Backend method type uint8_t
ap_object AP_RangeFinder_Backend method status uint8_t
ap_object AP_RangeFinder_Backend method handle_script_msg boolean float'skip_check

singleton RangeFinder depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER))
singleton RangeFinder rename rangefinder
singleton RangeFinder method num_sensors uint8_t
singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
Expand Down Expand Up @@ -254,6 +263,7 @@ singleton AP_ONVIF method get_pan_tilt_limit_min Vector2f
singleton AP_ONVIF method get_pan_tilt_limit_max Vector2f

include AP_Vehicle/AP_Vehicle.h
singleton AP_Vehicle depends (!defined(HAL_BUILD_AP_PERIPH))
singleton AP_Vehicle rename vehicle
singleton AP_Vehicle scheduler-semaphore
singleton AP_Vehicle method set_mode boolean uint8_t'skip_check ModeReason::SCRIPTING'literal
Expand Down Expand Up @@ -304,11 +314,13 @@ singleton AP_SerialLED method set_RGB void uint8_t 1 16 int8_t -1 INT8_MAX uint8
singleton AP_SerialLED method send void uint8_t 1 16

include SRV_Channel/SRV_Channel.h
singleton SRV_Channels depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RC_OUT))
singleton SRV_Channels rename SRV_Channels
singleton SRV_Channels method find_channel boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint8_t'Null
singleton SRV_Channels method set_output_pwm void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
singleton SRV_Channels method set_output_pwm_chan void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t'skip_check
singleton SRV_Channels method set_output_pwm_chan_timeout void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t'skip_check uint16_t'skip_check
singleton SRV_Channels method set_output_pwm_chan_timeout depends (!defined(HAL_BUILD_AP_PERIPH))
singleton SRV_Channels method set_output_scaled void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 float'skip_check
singleton SRV_Channels method get_output_pwm boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'Null
singleton SRV_Channels method get_output_scaled float SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1
Expand Down Expand Up @@ -339,16 +351,19 @@ singleton RC_Channels method get_aux_cached boolean RC_Channel::AUX_FUNC'enum 0

include AP_SerialManager/AP_SerialManager.h

ap_object AP_HAL::UARTDriver depends HAL_GCS_ENABLED
ap_object AP_HAL::UARTDriver method begin void uint32_t 1U UINT32_MAX
ap_object AP_HAL::UARTDriver method read int16_t
ap_object AP_HAL::UARTDriver method write uint32_t uint8_t'skip_check
ap_object AP_HAL::UARTDriver method available uint32_t
ap_object AP_HAL::UARTDriver method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_AUTO

singleton AP_SerialManager rename serial
singleton AP_SerialManager depends HAL_GCS_ENABLED
singleton AP_SerialManager method find_serial AP_HAL::UARTDriver AP_SerialManager::SerialProtocol_Scripting'literal uint8_t'skip_check

include AP_Baro/AP_Baro.h
singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO))
singleton AP_Baro rename baro
singleton AP_Baro method get_pressure float
singleton AP_Baro method get_temperature float
Expand Down Expand Up @@ -386,7 +401,9 @@ singleton AP_Param method set_and_save_by_name rename set_and_save
singleton AP_Param method set_default_by_name boolean string float'skip_check
singleton AP_Param method set_default_by_name rename set_default
singleton AP_Param method add_table boolean uint8_t 0 200 string uint8_t 1 63
singleton AP_Param method add_table depends AP_PARAM_DYNAMIC_ENABLED
singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string float'skip_check
singleton AP_Param method add_param depends AP_PARAM_DYNAMIC_ENABLED

include AP_Scripting/AP_Scripting_helpers.h
userdata Parameter creation lua_new_Parameter 1
Expand All @@ -403,6 +420,7 @@ singleton AP_Scripting rename scripting
singleton AP_Scripting method restart_all void

include AP_Mission/AP_Mission.h
singleton AP_Mission depends AP_MISSION_ENABLED
singleton AP_Mission rename mission
singleton AP_Mission scheduler-semaphore
singleton AP_Mission enum MISSION_STOPPED MISSION_RUNNING MISSION_COMPLETE
Expand All @@ -422,6 +440,7 @@ singleton AP_Mission method get_index_of_jump_tag uint16_t uint16_t 0 UINT16_MAX
singleton AP_Mission method get_last_jump_tag boolean uint16_t'Null uint16_t'Null


userdata mavlink_mission_item_int_t depends AP_MISSION_ENABLED
userdata mavlink_mission_item_int_t field param1 float'skip_check read write
userdata mavlink_mission_item_int_t field param2 float'skip_check read write
userdata mavlink_mission_item_int_t field param3 float'skip_check read write
Expand Down Expand Up @@ -505,6 +524,7 @@ ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registe
ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check


ap_object AP_HAL::AnalogSource depends !defined(HAL_DISABLE_ADC_DRIVER)
ap_object AP_HAL::AnalogSource method set_pin boolean uint8_t'skip_check
ap_object AP_HAL::AnalogSource method voltage_average float
ap_object AP_HAL::AnalogSource method voltage_latest float
Expand All @@ -523,6 +543,7 @@ singleton hal.gpio method write void uint8_t'skip_check uint8_t 0 1
singleton hal.gpio method toggle void uint8_t'skip_check
singleton hal.gpio method pinMode void uint8_t'skip_check uint8_t 0 1

singleton hal.analogin depends !defined(HAL_DISABLE_ADC_DRIVER)
singleton hal.analogin rename analog
singleton hal.analogin literal
singleton hal.analogin method channel AP_HAL::AnalogSource ANALOG_INPUT_NONE'literal
Expand All @@ -542,19 +563,20 @@ userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field yaw'array AP_MOTO
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field throttle'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write

include AP_InertialSensor/AP_InertialSensor.h
singleton AP_InertialSensor depends AP_INERTIALSENSOR_ENABLED
singleton AP_InertialSensor rename ins
singleton AP_InertialSensor method get_temperature float uint8_t 0 INS_MAX_INSTANCES
singleton AP_InertialSensor method get_gyro_health boolean uint8_t'skip_check
singleton AP_InertialSensor method get_accel_health boolean uint8_t'skip_check

singleton CAN manual get_device lua_get_CAN_device 1
singleton CAN manual get_device2 lua_get_CAN_device2 1
singleton CAN depends HAL_MAX_CAN_PROTOCOL_DRIVERS
singleton CAN depends AP_SCRIPTING_CAN_SENSOR_ENABLED

include AP_Scripting/AP_Scripting_CANSensor.h depends HAL_MAX_CAN_PROTOCOL_DRIVERS
include AP_Scripting/AP_Scripting_CANSensor.h
include AP_HAL/AP_HAL.h

userdata AP_HAL::CANFrame depends HAL_MAX_CAN_PROTOCOL_DRIVERS
userdata AP_HAL::CANFrame depends AP_SCRIPTING_CAN_SENSOR_ENABLED
userdata AP_HAL::CANFrame rename CANFrame
userdata AP_HAL::CANFrame field id uint32_t'skip_check read write
userdata AP_HAL::CANFrame field data'array int(ARRAY_SIZE(ud->data)) uint8_t'skip_check read write
Expand All @@ -564,7 +586,7 @@ userdata AP_HAL::CANFrame method isExtended boolean
userdata AP_HAL::CANFrame method isRemoteTransmissionRequest boolean
userdata AP_HAL::CANFrame method isErrorFrame boolean

ap_object ScriptingCANBuffer depends HAL_MAX_CAN_PROTOCOL_DRIVERS
ap_object ScriptingCANBuffer depends AP_SCRIPTING_CAN_SENSOR_ENABLED
ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_t'skip_check
ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null

Expand Down Expand Up @@ -645,13 +667,13 @@ singleton AP_Mount method get_location_target boolean uint8_t'skip_check Locatio
singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check

include AP_Camera/AP_Camera.h
singleton AP_Camera depends AP_CAMERA_SCRIPTING_ENABLED == 1
singleton AP_Camera depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1)
singleton AP_Camera rename camera
singleton AP_Camera semaphore
singleton AP_Camera method take_picture void uint8_t'skip_check
singleton AP_Camera method record_video boolean uint8_t'skip_check boolean
singleton AP_Camera method set_trigger_distance void uint8_t'skip_check float'skip_check
userdata AP_Camera::camera_state_t depends (AP_CAMERA_SCRIPTING_ENABLED == 1)
userdata AP_Camera::camera_state_t depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1)
userdata AP_Camera::camera_state_t field take_pic_incr uint16_t'skip_check read
userdata AP_Camera::camera_state_t field recording_video boolean read
userdata AP_Camera::camera_state_t field zoom_type uint8_t'skip_check read
Expand Down Expand Up @@ -679,6 +701,7 @@ singleton AP_IOMCU method healthy boolean

include AP_Compass/AP_Compass.h
singleton Compass rename compass
singleton Compass depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_MAG))
singleton Compass method healthy boolean uint8_t'skip_check

-- ----EFI Library----
Expand Down Expand Up @@ -731,12 +754,13 @@ singleton AP_Logger depends HAL_LOGGING_ENABLED
singleton AP_Logger rename logger
singleton AP_Logger manual write AP_Logger_Write 7
singleton AP_Logger method log_file_content void string
singleton AP_Logger method log_file_content depends HAL_LOGGER_FILE_CONTENTS_ENABLED

singleton i2c manual get_device lua_get_i2c_device 4

global manual millis lua_millis 0
global manual micros lua_micros 0
global manual mission_receive lua_mission_receive 0
global manual mission_receive lua_mission_receive 0 depends AP_MISSION_ENABLED

userdata uint32_t creation lua_new_uint32_t 1
userdata uint32_t manual_operator __add uint32_t___add
Expand Down
Loading