2018-09-27 19:30:55 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
# pragma once
2021-11-15 01:08:31 -04:00
# if AP_SCRIPTING_ENABLED
2018-09-27 19:30:55 -03:00
2023-09-21 22:24:30 -03:00
# include <GCS_MAVLink/GCS_config.h>
2018-09-27 20:04:37 -03:00
# include <AP_Common/AP_Common.h>
# include <AP_Param/AP_Param.h>
2022-02-25 01:09:06 -04:00
# include <GCS_MAVLink/GCS_MAVLink.h>
# include <AP_Mission/AP_Mission.h>
2020-02-05 18:58:33 -04:00
# include <AP_Filesystem/AP_Filesystem.h>
2021-03-03 03:43:45 -04:00
# include <AP_HAL/I2CDevice.h>
2021-07-23 08:15:21 -03:00
# include "AP_Scripting_CANSensor.h"
2023-12-03 01:43:29 -04:00
# include <AP_Networking/AP_Networking_Config.h>
2021-03-03 03:43:45 -04:00
# ifndef SCRIPTING_MAX_NUM_I2C_DEVICE
# define SCRIPTING_MAX_NUM_I2C_DEVICE 4
# endif
2018-09-27 19:30:55 -03:00
2023-02-20 09:59:22 -04:00
# define SCRIPTING_MAX_NUM_PWM_SOURCE 4
2023-12-03 01:43:29 -04:00
# if AP_NETWORKING_ENABLED
# ifndef SCRIPTING_MAX_NUM_NET_SOCKET
# define SCRIPTING_MAX_NUM_NET_SOCKET 50
# endif
class SocketAPM ;
# endif
2018-09-27 19:30:55 -03:00
class AP_Scripting
{
public :
AP_Scripting ( ) ;
/* Do not allow copies */
2022-09-30 06:50:43 -03:00
CLASS_NO_COPY ( AP_Scripting ) ;
2018-09-27 19:30:55 -03:00
2019-11-26 01:39:17 -04:00
void init ( void ) ;
2018-09-27 20:04:37 -03:00
2023-11-25 13:18:37 -04:00
void update ( ) ;
2019-10-15 04:02:08 -03:00
bool enabled ( void ) const { return _enable ! = 0 ; } ;
2021-08-04 13:49:17 -03:00
bool should_run ( void ) const { return enabled ( ) & & ! _stop ; }
2019-10-15 04:02:08 -03:00
2023-09-21 22:24:30 -03:00
# if HAL_GCS_ENABLED
2020-02-24 20:22:10 -04:00
void handle_message ( const mavlink_message_t & msg , const mavlink_channel_t chan ) ;
2023-06-18 09:59:45 -03:00
// Check if command ID is blocked
bool is_handling_command ( uint16_t cmd_id ) ;
2023-09-21 22:24:30 -03:00
# endif
2023-06-18 09:59:45 -03:00
2018-09-27 20:04:37 -03:00
static AP_Scripting * get_singleton ( void ) { return _singleton ; }
static const struct AP_Param : : GroupInfo var_info [ ] ;
2018-09-27 19:30:55 -03:00
2023-09-21 22:24:30 -03:00
# if HAL_GCS_ENABLED
2020-02-05 18:58:33 -04:00
MAV_RESULT handle_command_int_packet ( const mavlink_command_int_t & packet ) ;
2023-09-21 22:24:30 -03:00
# endif
2020-02-05 18:58:33 -04:00
2022-02-25 01:09:06 -04:00
void handle_mission_command ( const class AP_Mission : : Mission_Command & cmd ) ;
2021-02-25 21:09:17 -04:00
2022-08-28 16:24:21 -03:00
bool arming_checks ( size_t buflen , char * buffer ) const ;
2022-12-18 20:58:35 -04:00
2022-12-21 17:41:15 -04:00
void restart_all ( void ) ;
2022-08-28 16:24:21 -03:00
2020-07-09 09:36:45 -03:00
// User parameters for inputs into scripts
2021-11-30 02:09:20 -04:00
AP_Float _user [ 6 ] ;
2020-07-09 09:36:45 -03:00
2020-02-05 18:58:33 -04:00
struct terminal_s {
int output_fd ;
off_t input_offset ;
bool session ;
} terminal ;
2020-10-26 22:08:14 -03:00
enum class SCR_DIR {
ROMFS = 1 < < 0 ,
SCRIPTS = 1 < < 1 ,
} ;
uint16_t get_disabled_dir ( ) { return uint16_t ( _dir_disable . get ( ) ) ; }
2021-03-03 03:43:45 -04:00
// the number of and storage for i2c devices
uint8_t num_i2c_devices ;
AP_HAL : : OwnPtr < AP_HAL : : I2CDevice > * _i2c_dev [ SCRIPTING_MAX_NUM_I2C_DEVICE ] ;
2023-10-04 13:27:54 -03:00
# if AP_SCRIPTING_CAN_SENSOR_ENABLED
2021-07-23 08:15:21 -03:00
// Scripting CAN sensor
ScriptingCANSensor * _CAN_dev ;
2022-07-01 23:23:58 -03:00
ScriptingCANSensor * _CAN_dev2 ;
2021-07-23 08:15:21 -03:00
# endif
2023-10-04 14:01:20 -03:00
# if AP_MISSION_ENABLED
2021-02-25 21:09:17 -04:00
// mission item buffer
static const int mission_cmd_queue_size = 5 ;
struct scripting_mission_cmd {
uint16_t p1 ;
float content_p1 ;
float content_p2 ;
float content_p3 ;
uint32_t time_ms ;
} ;
ObjectBuffer < struct scripting_mission_cmd > * mission_data ;
2023-10-04 14:01:20 -03:00
# endif
2021-02-25 21:09:17 -04:00
2023-02-20 09:59:22 -04:00
// PWMSource storage
uint8_t num_pwm_source ;
AP_HAL : : PWMSource * _pwm_source [ SCRIPTING_MAX_NUM_PWM_SOURCE ] ;
2023-03-09 00:47:50 -04:00
int get_current_ref ( ) { return current_ref ; }
void set_current_ref ( int ref ) { current_ref = ref ; }
2023-02-20 09:59:22 -04:00
2023-12-03 01:43:29 -04:00
# if AP_NETWORKING_ENABLED
// SocketAPM storage
SocketAPM * _net_sockets [ SCRIPTING_MAX_NUM_NET_SOCKET ] ;
# endif
2020-02-24 20:22:10 -04:00
struct mavlink_msg {
mavlink_message_t msg ;
mavlink_channel_t chan ;
2023-05-03 06:45:13 -03:00
uint32_t timestamp_ms ;
2020-02-24 20:22:10 -04:00
} ;
struct mavlink {
2023-03-09 18:45:30 -04:00
ObjectBuffer < struct mavlink_msg > * rx_buffer ;
2023-05-15 20:42:39 -03:00
uint32_t * accept_msg_ids ;
2023-03-09 18:45:30 -04:00
uint16_t accept_msg_ids_size ;
2020-02-24 20:22:10 -04:00
HAL_Semaphore sem ;
} mavlink_data ;
2023-06-18 09:59:45 -03:00
struct command_block_list {
uint16_t id ;
command_block_list * next ;
} ;
command_block_list * mavlink_command_block_list ;
HAL_Semaphore mavlink_command_block_list_sem ;
2018-09-27 19:30:55 -03:00
private :
2020-02-05 18:58:33 -04:00
bool repl_start ( void ) ;
void repl_stop ( void ) ;
2018-10-31 19:43:23 -03:00
void thread ( void ) ; // main script execution thread
2018-09-27 20:04:37 -03:00
2023-11-25 13:18:37 -04:00
// Check if DEBUG_OPTS bit has been set to save current checksum values to params
void save_checksum ( ) ;
// Mask down to 23 bits for comparison with parameters, this the length of the a float mantissa, to deal with the float transport of parameters over MAVLink
// The full range of uint32 integers cannot be represented by a float.
const uint32_t checksum_param_mask = 0x007FFFFF ;
2023-12-02 20:36:18 -04:00
enum class ThreadPriority : uint8_t {
NORMAL = 0 ,
IO = 1 ,
STORAGE = 2 ,
UART = 3 ,
I2C = 4 ,
SPI = 5 ,
TIMER = 6 ,
MAIN = 7 ,
BOOST = 8
} ;
2018-09-27 20:04:37 -03:00
AP_Int8 _enable ;
2018-10-30 23:06:32 -03:00
AP_Int32 _script_vm_exec_count ;
2018-12-08 22:35:08 -04:00
AP_Int32 _script_heap_size ;
2021-11-13 13:09:09 -04:00
AP_Int8 _debug_options ;
2020-10-26 22:08:14 -03:00
AP_Int16 _dir_disable ;
2023-11-25 13:18:37 -04:00
AP_Int32 _required_loaded_checksum ;
AP_Int32 _required_running_checksum ;
2023-12-02 20:36:18 -04:00
AP_Enum < ThreadPriority > _thd_priority ;
2018-09-27 20:04:37 -03:00
2022-08-28 16:24:21 -03:00
bool _thread_failed ; // thread allocation failed
2019-11-26 01:33:14 -04:00
bool _init_failed ; // true if memory allocation failed
2021-08-04 13:49:17 -03:00
bool _restart ; // true if scripts should be restarted
bool _stop ; // true if scripts should be stopped
2019-11-26 01:33:14 -04:00
2018-09-27 19:30:55 -03:00
static AP_Scripting * _singleton ;
2023-03-09 00:47:50 -04:00
int current_ref ;
2018-09-27 19:30:55 -03:00
} ;
namespace AP {
2018-09-27 20:04:37 -03:00
AP_Scripting * scripting ( void ) ;
2018-09-27 19:30:55 -03:00
} ;
2021-11-15 01:08:31 -04:00
# endif // AP_SCRIPTING_ENABLED