├── .gitmodules ├── CMakeLists.txt └── src ├── ADRC.cpp ├── ADRC.h ├── Accelerometer.cpp ├── Accelerometer.h ├── ESO.cpp ├── ESO.h ├── Encoders.cpp ├── Encoders.h ├── Gyroscope.cpp ├── Gyroscope.h ├── Motor.cpp ├── Motor.h ├── PID.cpp ├── PID.h ├── TWIP.cpp ├── TWIP.h ├── bytecodes.h ├── lms2012.h ├── lmstypes.h └── main.cpp /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "KalmanFilter"] 2 | path = KalmanFilter 3 | url = https://github.com/psiorx/KalmanFilter.git 4 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | project(adrc_balance) 2 | 3 | cmake_minimum_required(VERSION 2.8) 4 | 5 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) 6 | 7 | set(CMAKE_CXX_COMPILER arm-none-linux-gnueabi-g++) 8 | 9 | set(CMAKE_CXX_FLAGS "-std=c++0x -static -O3 -Wall") 10 | 11 | find_package(Eigen3 REQUIRED) 12 | 13 | include_directories(KalmanFilter) 14 | include_directories(${EIGEN3_INCLUDE_DIR}) 15 | 16 | file(GLOB adrc_balance_SRC "src/*.cpp") 17 | 18 | add_executable(balance 19 | ${adrc_balance_SRC} 20 | KalmanFilter/Kalman.cpp 21 | ) 22 | -------------------------------------------------------------------------------- /src/ADRC.cpp: -------------------------------------------------------------------------------- 1 | #include "ADRC.h" 2 | 3 | using namespace Eigen; 4 | 5 | ADRC::ADRC(float wo, float wc, float b0, float dt) 6 | : m_observer(wo, b0, dt), m_b(b0) { 7 | m_kp = wc * wc; 8 | m_kd = wc + wc; 9 | } 10 | 11 | float ADRC::Controller(Vector3f const & xhat, float y_desired) { 12 | float u0 = m_kp * (y_desired - xhat[0]) - m_kd * xhat[1]; 13 | return (u0 - xhat[2]) / m_b; 14 | } 15 | 16 | float ADRC::Update(float u, float y, float y_desired) { 17 | Vector3f xhat = m_observer.Update(u, y); 18 | return Controller(xhat, y_desired); 19 | } -------------------------------------------------------------------------------- /src/ADRC.h: -------------------------------------------------------------------------------- 1 | #ifndef ADRC_H 2 | #define ADRC_H 3 | 4 | #include 5 | #include "ESO.h" 6 | 7 | class ADRC { 8 | ESO m_observer; 9 | float m_kp; 10 | float m_kd; 11 | float m_b; 12 | 13 | float Controller(Eigen::Vector3f const & xhat, float y_desired); 14 | public: 15 | ADRC(float wo, float wc, float b0, float dt); 16 | virtual ~ADRC() { }; 17 | float Update(float u, float y, float y_desired); 18 | }; 19 | 20 | #endif -------------------------------------------------------------------------------- /src/Accelerometer.cpp: -------------------------------------------------------------------------------- 1 | #include "Accelerometer.h" 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | using namespace Eigen; 10 | using namespace std; 11 | 12 | Accelerometer::Accelerometer(const unsigned int port) { 13 | if(port == 0 || port > 4) { 14 | cout << "Error: accelerometer port must be an integer in the range [1, 4]" << endl; 15 | return; 16 | } 17 | 18 | m_port = port - 1; 19 | 20 | m_file = open(IIC_DEVICE_NAME, O_RDWR | O_SYNC); 21 | 22 | if(m_file == -1) { 23 | cout << "Error: couldn't open the i2c device." << endl; 24 | return; 25 | } 26 | 27 | m_p_device = (IIC*)mmap(0, sizeof(IIC), 28 | PROT_READ | PROT_WRITE, 29 | MAP_FILE | MAP_SHARED, m_file, 0); 30 | 31 | if(m_p_device == MAP_FAILED) { 32 | cout << "Error: failed to map the i2c device." << endl; 33 | } 34 | 35 | m_iic_dat.Port = m_port; 36 | m_iic_dat.Time = 0; 37 | m_iic_dat.Repeat = 0; 38 | m_iic_dat.RdLng = 6; 39 | m_iic_dat.WrLng = 2; 40 | m_iic_dat.WrData[0] = 0x01; 41 | m_iic_dat.WrData[1] = 0x42; 42 | ioctl(m_file, IIC_SETUP, &m_iic_dat); 43 | } 44 | 45 | Accelerometer::~Accelerometer() { 46 | if(m_file != -1) { 47 | close(m_file); 48 | } 49 | } 50 | 51 | float Accelerometer::ReadAxis(const unsigned int axis) { 52 | int accel = m_p_device->Raw[m_port][m_p_device->Actual[m_port]][axis+3]; 53 | accel <<= 2; 54 | accel |= m_p_device->Raw[m_port][m_p_device->Actual[m_port]][axis]; 55 | return accel/200.0f; 56 | } 57 | 58 | Vector3f Accelerometer::Read() { 59 | Vector3f acceleration; 60 | acceleration << ReadAxis(2), ReadAxis(1), ReadAxis(0); 61 | return acceleration; 62 | } 63 | 64 | float Accelerometer::ComputePitchFast(Eigen::Vector3f const & accel) { 65 | return atan2(accel[1], accel[0]); 66 | } 67 | 68 | float Accelerometer::ComputePitch(Eigen::Vector3f const & accel) { 69 | return atan2(accel[1], sqrt(accel[0] * accel[0] + accel[2] * accel[2])); 70 | } 71 | 72 | float Accelerometer::ComputeRoll(Eigen::Vector3f const & accel) { 73 | return atan2(-accel[0], accel[2])*(180/M_PI); 74 | } -------------------------------------------------------------------------------- /src/Accelerometer.h: -------------------------------------------------------------------------------- 1 | #ifndef ACCELEROMETER_H 2 | #define ACCELEROMETER_H 3 | 4 | #include "lms2012.h" 5 | #include 6 | 7 | class Accelerometer { 8 | int m_file; 9 | unsigned int m_port; 10 | IIC *m_p_device; 11 | IICDAT m_iic_dat; 12 | 13 | public: 14 | Accelerometer(const unsigned int port); 15 | ~Accelerometer(); 16 | float ReadAxis(const unsigned int axis); 17 | 18 | //returns accelerations in g's 19 | Eigen::Vector3f Read(); 20 | 21 | //angles in radians 22 | static float ComputePitchFast(Eigen::Vector3f const & accel); 23 | static float ComputePitch(Eigen::Vector3f const & accel); 24 | static float ComputeRoll(Eigen::Vector3f const & accel); 25 | }; 26 | 27 | #endif -------------------------------------------------------------------------------- /src/ESO.cpp: -------------------------------------------------------------------------------- 1 | #include "ESO.h" 2 | #include 3 | 4 | using namespace Eigen; 5 | 6 | ESO::ESO(float wo, float b0, float dt) { 7 | SetParameters(wo, b0, dt); 8 | } 9 | 10 | void ESO::SetParameters(float wo, float b0, float dt) { 11 | Matrix3f A; 12 | Vector3f B; 13 | Vector3f L; 14 | Matrix C; 15 | Matrix B_obs_ct; 16 | Matrix3f A_obs_ct; 17 | 18 | A << 0, 1, 0, 19 | 0, 0, 1, 20 | 0, 0, 0; 21 | 22 | B << 0, b0, 0; 23 | 24 | C << 1, 0, 0; 25 | 26 | L << 3*wo, 3*wo*wo, wo*wo*wo; 27 | 28 | A_obs_ct = A - L * C; 29 | B_obs_ct << B, L; 30 | 31 | Discretize(A_obs_ct, B_obs_ct, dt); 32 | 33 | } 34 | 35 | void ESO::Discretize(Matrix3f const & A_obs_ct, 36 | Matrix const & B_obs_ct, float dt) { 37 | Matrix discretization, discretization_exp; 38 | 39 | discretization << A_obs_ct, B_obs_ct, MatrixXf::Zero(2, 5); 40 | discretization_exp = (discretization * dt).exp(); 41 | 42 | m_A_obs_dt = discretization_exp.block<3, 3>(0, 0); 43 | m_B_obs_dt = discretization_exp.block<3, 2>(0, 3); 44 | } 45 | 46 | void ESO::SetState(Eigen::Vector3f const & xhat) { 47 | m_xhat = xhat; 48 | } 49 | 50 | 51 | Vector3f ESO::Update(float u, float y) { 52 | Vector2f u_obs; 53 | u_obs << u, y; 54 | m_xhat = m_A_obs_dt * m_xhat + m_B_obs_dt * u_obs; 55 | return m_xhat; 56 | } 57 | -------------------------------------------------------------------------------- /src/ESO.h: -------------------------------------------------------------------------------- 1 | #ifndef ESO_H 2 | #define ESO_H 3 | 4 | #include 5 | 6 | class ESO { 7 | Eigen::Vector3f m_xhat; 8 | Eigen::Matrix3f m_A_obs_dt; 9 | Eigen::Matrix m_B_obs_dt; 10 | 11 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 12 | 13 | void Discretize(Eigen::Matrix3f const & A_obs_ct, 14 | Eigen::Matrix const & B_obs_ct, float dt); 15 | public: 16 | ESO(float wo, float b0, float dt); 17 | virtual ~ESO() { }; 18 | void SetState(Eigen::Vector3f const & xhat); 19 | void SetParameters(float wo, float b, float dt); 20 | Eigen::Vector3f Update(float u, float y); 21 | }; 22 | 23 | #endif -------------------------------------------------------------------------------- /src/Encoders.cpp: -------------------------------------------------------------------------------- 1 | #include "Encoders.h" 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | using namespace std; 8 | 9 | Encoders::Encoders() { 10 | 11 | m_file = open(MOTOR_DEVICE_NAME, O_RDWR | O_SYNC); 12 | 13 | if(m_file == -1) { 14 | cout << "Error: couldn't open the analog device." << endl; 15 | return; 16 | } 17 | 18 | m_p_device = (MOTORDATA*)mmap(0, sizeof(MOTORDATA)*vmOUTPUTS, 19 | PROT_READ | PROT_WRITE, 20 | MAP_FILE | MAP_SHARED, m_file, 0); 21 | 22 | if(m_p_device == MAP_FAILED) { 23 | cout << "Error: failed to map the analog device." << endl; 24 | } 25 | } 26 | 27 | Encoders::~Encoders() { 28 | if(m_file != -1) { 29 | close(m_file); 30 | } 31 | } 32 | 33 | int Encoders::ReadCount(const unsigned int port) const { 34 | return m_p_device[port].TachoSensor; 35 | } 36 | 37 | int Encoders::ReadSpeed(const unsigned int port) const { 38 | return m_p_device[port].Speed; 39 | } 40 | -------------------------------------------------------------------------------- /src/Encoders.h: -------------------------------------------------------------------------------- 1 | #ifndef ENCODERS_H 2 | #define ENCODERS_H 3 | 4 | #include "lms2012.h" 5 | 6 | class Encoders { 7 | int m_file; 8 | MOTORDATA *m_p_device; 9 | public: 10 | Encoders(); 11 | ~Encoders(); 12 | int ReadCount(const unsigned int port) const; 13 | int ReadSpeed(const unsigned int port) const; 14 | }; 15 | 16 | #endif -------------------------------------------------------------------------------- /src/Gyroscope.cpp: -------------------------------------------------------------------------------- 1 | #include "Gyroscope.h" 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | using namespace std; 8 | 9 | Gyroscope::Gyroscope(const unsigned int port) { 10 | if(port ==0 || port > 4) { 11 | cout << "Error: gyroscope port must be an integer in the range [1, 4]" << endl; 12 | return; 13 | } 14 | 15 | m_port = port - 1; 16 | 17 | m_file = open(ANALOG_DEVICE_NAME, O_RDWR | O_SYNC); 18 | 19 | if(m_file == -1) { 20 | cout << "Error: couldn't open the analog device." << endl; 21 | return; 22 | } 23 | 24 | m_p_device = (ANALOG*)mmap(0, sizeof(ANALOG), 25 | PROT_READ | PROT_WRITE, 26 | MAP_FILE | MAP_SHARED, m_file, 0); 27 | 28 | if(m_p_device == MAP_FAILED) { 29 | cout << "Error: failed to map the analog device." << endl; 30 | } 31 | } 32 | 33 | Gyroscope::~Gyroscope() { 34 | if(m_file != -1) { 35 | close(m_file); 36 | } 37 | } 38 | 39 | float Gyroscope::Read() { 40 | DATA16 raw = m_p_device->Pin1[m_port][m_p_device->Actual[m_port]]; 41 | return ((float) raw) / 10.0f; 42 | } 43 | 44 | float Gyroscope::Calibrate(const unsigned int samples) { 45 | if(samples == 0) { 46 | cout << "Error: calibration requires at least one sample." << endl; 47 | return 0.0f; 48 | } 49 | 50 | float sum = 0.0f; 51 | 52 | for(unsigned int i = 0; i < samples; i++) { 53 | sum += Read(); 54 | } 55 | 56 | return sum / samples; 57 | } -------------------------------------------------------------------------------- /src/Gyroscope.h: -------------------------------------------------------------------------------- 1 | #ifndef GYROSCOPE_H 2 | #define GYROSCOPE_H 3 | 4 | #include "lms2012.h" 5 | 6 | class Gyroscope { 7 | int m_file; 8 | unsigned int m_port; 9 | ANALOG *m_p_device; 10 | public: 11 | Gyroscope(const unsigned int port); 12 | ~Gyroscope(); 13 | float Read(); 14 | //returns gyro bias 15 | float Calibrate(const unsigned int samples); 16 | }; 17 | 18 | #endif -------------------------------------------------------------------------------- /src/Motor.cpp: -------------------------------------------------------------------------------- 1 | #include "Motor.h" 2 | #include 3 | #include 4 | #include 5 | 6 | using namespace std; 7 | 8 | Motor::Motor(const unsigned char port) : m_port(port) { 9 | 10 | m_file = open(PWM_DEVICE_NAME, O_WRONLY); 11 | 12 | if(m_file == -1) { 13 | cout << "Error: couldn't open the pwm device." << endl; 14 | return; 15 | } 16 | 17 | m_motor_command[1] = port; 18 | } 19 | 20 | Motor::~Motor() { 21 | if(m_file != -1) { 22 | close(m_file); 23 | } 24 | } 25 | 26 | void Motor::Start() { 27 | m_motor_command[0] = opOUTPUT_START; 28 | WriteCommand(2); 29 | } 30 | 31 | void Motor::Stop() { 32 | m_motor_command[0] = opOUTPUT_STOP; 33 | WriteCommand(2); 34 | } 35 | 36 | void Motor::Reset() { 37 | m_motor_command[0] = opOUTPUT_RESET; 38 | WriteCommand(2); 39 | } 40 | 41 | void Motor::WriteCommand(const unsigned int bytes) { 42 | write(m_file, m_motor_command, bytes); 43 | } 44 | 45 | void Motor::SetPower(int power) { 46 | m_motor_command[0] = opOUTPUT_POWER; 47 | m_motor_command[2] = static_cast(power); 48 | WriteCommand(3); 49 | } 50 | -------------------------------------------------------------------------------- /src/Motor.h: -------------------------------------------------------------------------------- 1 | #ifndef MOTOR_H 2 | #define MOTOR_H 3 | 4 | #include "lms2012.h" 5 | 6 | class Motor { 7 | int m_file; 8 | char m_port; 9 | char m_motor_command[3]; 10 | void WriteCommand(const unsigned int bytes); 11 | public: 12 | Motor(const unsigned char port); 13 | ~Motor(); 14 | void SetPower(int power); 15 | void Start(); 16 | void Stop(); 17 | void Reset(); 18 | }; 19 | 20 | #endif -------------------------------------------------------------------------------- /src/PID.cpp: -------------------------------------------------------------------------------- 1 | #include "PID.h" 2 | 3 | PID::PID(float kp, float ki, float kd, float dt) 4 | : m_kp(kp), m_ki(ki), m_kd(kd), m_dt(dt) { 5 | m_last_err = 0.0f; 6 | m_integrator = 0.0f; 7 | } 8 | 9 | float PID::Update(float err) { 10 | float dedt = (err - m_last_err) / m_dt; 11 | m_integrator += err * m_dt; 12 | m_last_err = err; 13 | 14 | return m_kp * err + m_kd * dedt + m_ki * m_integrator; 15 | } 16 | -------------------------------------------------------------------------------- /src/PID.h: -------------------------------------------------------------------------------- 1 | #ifndef PID_H 2 | #define PID_H 3 | 4 | class PID { 5 | float m_kp; 6 | float m_ki; 7 | float m_kd; 8 | float m_dt; 9 | 10 | float m_integrator; 11 | float m_last_err; 12 | 13 | public: 14 | PID(float kp, float ki, float kd, float dt); 15 | float Update(float err); 16 | }; 17 | 18 | #endif -------------------------------------------------------------------------------- /src/TWIP.cpp: -------------------------------------------------------------------------------- 1 | #include "TWIP.h" 2 | 3 | using namespace Eigen; 4 | 5 | TWIP::TWIP(const unsigned int gyro_port, 6 | const unsigned int accel_port, 7 | const unsigned int motor_left, 8 | const unsigned int motor_right, 9 | float dt) : 10 | m_gyroscope(gyro_port), 11 | m_kalman_filter(90.0f, m_gyroscope.Calibrate(100), dt), 12 | m_accelerometer(accel_port), 13 | m_motors((1 << (motor_left - 1)) | (1 << (motor_right - 1))) { 14 | 15 | m_motor_ports[0] = motor_left - 1; 16 | m_motor_ports[1] = motor_right - 1; 17 | 18 | m_motors.Start(); 19 | m_motors.Reset(); 20 | 21 | m_encoder_offset[0] = m_encoders.ReadCount(m_motor_ports[0]); 22 | m_encoder_offset[1] = m_encoders.ReadCount(m_motor_ports[1]); 23 | } 24 | 25 | Vector2f TWIP::output(float u) { 26 | 27 | Vector2f y; 28 | 29 | m_motors.SetPower(u); 30 | 31 | float accel_pitch = Accelerometer::ComputePitchFast(m_accelerometer.Read()) * 180.0f / M_PI; 32 | 33 | float fused_pitch = m_kalman_filter.getAngle(accel_pitch, m_gyroscope.Read()); 34 | 35 | int encoder_left = m_encoders.ReadCount(m_motor_ports[0]) - m_encoder_offset[0]; 36 | int encoder_right = m_encoders.ReadCount(m_motor_ports[1]) - m_encoder_offset[1]; 37 | 38 | float wheel_position = (encoder_left + encoder_right) * 0.5f; 39 | 40 | y << fused_pitch, 41 | wheel_position; 42 | 43 | return y; 44 | } 45 | -------------------------------------------------------------------------------- /src/TWIP.h: -------------------------------------------------------------------------------- 1 | #ifndef TWIP_H 2 | #define TWIP_H 3 | 4 | #include "Gyroscope.h" 5 | #include "Accelerometer.h" 6 | #include "Motor.h" 7 | #include "Encoders.h" 8 | #include "Kalman.h" 9 | 10 | // TWIP: Two Wheeled Inverted Pendulum 11 | 12 | class TWIP { 13 | Gyroscope m_gyroscope; 14 | Kalman m_kalman_filter; 15 | Accelerometer m_accelerometer; 16 | Motor m_motors; 17 | Encoders m_encoders; 18 | int m_motor_ports[2]; 19 | int m_encoder_offset[2]; 20 | 21 | public: 22 | 23 | TWIP(const unsigned int gyro_port, 24 | const unsigned int accel_port, 25 | const unsigned int motor_left, 26 | const unsigned int motor_right, 27 | float dt); 28 | 29 | virtual ~TWIP() {}; 30 | 31 | Eigen::Vector2f output(float u); 32 | }; 33 | 34 | #endif -------------------------------------------------------------------------------- /src/bytecodes.h: -------------------------------------------------------------------------------- 1 | /* 2 | * LEGO® MINDSTORMS EV3 3 | * 4 | * Copyright (C) 2010-2013 The LEGO Group 5 | * 6 | * This program is free software; you can redistribute it and/or modify 7 | * it under the terms of the GNU General Public License as published by 8 | * the Free Software Foundation; either version 2 of the License, or 9 | * (at your option) any later version. 10 | * 11 | * This program is distributed in the hope that it will be useful, 12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 14 | * GNU General Public License for more details. 15 | * 16 | * You should have received a copy of the GNU General Public License 17 | * along with this program; if not, write to the Free Software 18 | * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 19 | */ 20 | 21 | 22 | #ifndef BYTECODES_H_ 23 | #define BYTECODES_H_ 24 | 25 | #define BYTECODE_VERSION 1.04 26 | 27 | /*! \page system System Configuration 28 | * 29 | *
30 | * 31 | * Following defines sets the system configuration and limitations.\n 32 | * Defines with preceding "vm" is visible for the byte code assembler\n 33 | * 34 | * \verbatim 35 | */ 36 | 37 | // HARDWARE 38 | 39 | #define vmOUTPUTS 4 //!< Number of output ports in the system 40 | #define vmINPUTS 4 //!< Number of input ports in the system 41 | #define vmBUTTONS 6 //!< Number of buttons in the system 42 | #define vmLEDS 4 //!< Number of LEDs in the system 43 | 44 | #define vmLCD_WIDTH 178 //!< LCD horizontal pixels 45 | #define vmLCD_HEIGHT 128 //!< LCD vertical pixels 46 | #define vmTOPLINE_HEIGHT 10 //!< Top line vertical pixels 47 | #define vmLCD_STORE_LEVELS 3 //!< Store levels 48 | 49 | #define vmDEFAULT_VOLUME 100 50 | #define vmDEFAULT_SLEEPMINUTES 30 51 | 52 | // SOFTWARE 53 | 54 | #define vmFG_COLOR 1 //!< Forground color 55 | #define vmBG_COLOR 0 //!< Background color 56 | 57 | #define vmCHAIN_DEPT 4 //!< Number of bricks in the USB daisy chain (master + slaves) 58 | 59 | #define FILEPERMISSIONS (S_IRUSR | S_IWUSR | S_IRGRP | S_IWGRP | S_IROTH | S_IWOTH) 60 | #define DIRPERMISSIONS (S_IRWXU | S_IRWXG | S_IRWXO) 61 | #define SYSPERMISSIONS (S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH) 62 | 63 | #define vmPATHSIZE 84 //!< Max path size excluding trailing forward slash including zero termination 64 | #define vmNAMESIZE 32 //!< Max name size including zero termination (must be divideable by 4) 65 | #define vmEXTSIZE 5 //!< Max extension size including dot and zero termination 66 | #define vmFILENAMESIZE 120 //!< Max filename size including path, name, extension and termination (must be divideable by 4) 67 | #define vmMACSIZE 18 //!< Max WIFI MAC size including zero termination 68 | #define vmIPSIZE 16 //!< Max WIFI IP size including zero termination 69 | #define vmBTADRSIZE 13 //!< Max bluetooth address size including zero termination 70 | 71 | #define vmERR_STRING_SIZE 32 // Inclusive zero termination 72 | 73 | #define vmEVENT_BT_PIN 1 74 | #define vmEVENT_BT_REQ_CONF 2 75 | 76 | #define vmMAX_VALID_TYPE 101 //!< Highest valid device type 77 | 78 | // FOLDERS 79 | 80 | #define vmMEMORY_FOLDER "/mnt/ramdisk" //!< Folder for non volatile user programs/data 81 | #define vmPROGRAM_FOLDER "../prjs/BrkProg_SAVE" //!< Folder for On Brick Programming programs 82 | #define vmDATALOG_FOLDER "../prjs/BrkDL_SAVE" //!< Folder for On Brick Data log files 83 | #define vmSDCARD_FOLDER "../prjs/SD_Card" //!< Folder for SD card mount 84 | #define vmUSBSTICK_FOLDER "../prjs/USB_Stick" //!< Folder for USB stick mount 85 | 86 | #define vmPRJS_DIR "../prjs" //!< Project folder 87 | #define vmAPPS_DIR "../apps" //!< Apps folder 88 | #define vmTOOLS_DIR "../tools" //!< Tools folder 89 | #define vmTMP_DIR "../tmp" //!< Temporary folder 90 | 91 | #define vmSETTINGS_DIR "../sys/settings" //!< Folder for non volatile settings 92 | 93 | #define vmDIR_DEEPT 127 //!< Max directory items allocated including "." and ".." 94 | 95 | // FILES USED IN APPLICATION 96 | 97 | #define vmLASTRUN_FILE_NAME "lastrun" //!< Last run filename 98 | #define vmCALDATA_FILE_NAME "caldata" //!< Calibration data filename 99 | 100 | // FILES USED IN APPS 101 | 102 | #define vmSLEEP_FILE_NAME "Sleep" //!< File used in "Sleep" app to save status 103 | #define vmVOLUME_FILE_NAME "Volume" //!< File used in "Volume" app to save status 104 | #define vmWIFI_FILE_NAME "WiFi" //!< File used in "WiFi" app to save status 105 | #define vmBLUETOOTH_FILE_NAME "Bluetooth" //!< File used in "Bluetooth" app to save status 106 | 107 | // EXTENSIONS 108 | 109 | #define vmEXT_SOUND ".rsf" //!< Robot Sound File 110 | #define vmEXT_GRAPHICS ".rgf" //!< Robot Graphics File 111 | #define vmEXT_BYTECODE ".rbf" //!< Robot Byte code File 112 | #define vmEXT_TEXT ".rtf" //!< Robot Text File 113 | #define vmEXT_DATALOG ".rdf" //!< Robot Datalog File 114 | #define vmEXT_PROGRAM ".rpf" //!< Robot Program File 115 | #define vmEXT_CONFIG ".rcf" //!< Robot Configuration File 116 | #define vmEXT_ARCHIVE ".raf" //!< Robot Archive File 117 | 118 | // NAME LENGTHs 119 | 120 | #define vmBRICKNAMESIZE 120 //!< Brick name maximal size (including zero termination) 121 | #define vmBTPASSKEYSIZE 7 //!< Bluetooth pass key size (including zero termination) 122 | #define vmWIFIPASSKEYSIZE 33 //!< WiFi pass key size (including zero termination) 123 | 124 | // VALID CHARACTERS 125 | 126 | #define vmCHARSET_NAME 0x01 //!< Character set allowed in brick name and raw filenames 127 | #define vmCHARSET_FILENAME 0x02 //!< Character set allowed in file names 128 | #define vmCHARSET_BTPASSKEY 0x04 //!< Character set allowed in bluetooth pass key 129 | #define vmCHARSET_WIFIPASSKEY 0x08 //!< Character set allowed in WiFi pass key 130 | #define vmCHARSET_WIFISSID 0x10 //!< Character set allowed in WiFi ssid 131 | 132 | 133 | /* \endverbatim */ 134 | 135 | 136 | /*! \page bytecodedef Byte Code Defines 137 | * 138 | * \verbatim 139 | */ 140 | typedef enum 141 | { 142 | // \endverbatim \ref VM \verbatim 143 | // 0000.... 144 | opERROR = 0x00, // 0000 145 | opNOP = 0x01, // 0001 146 | opPROGRAM_STOP = 0x02, // 0010 147 | opPROGRAM_START = 0x03, // 0011 148 | opOBJECT_STOP = 0x04, // 0100 149 | opOBJECT_START = 0x05, // 0101 150 | opOBJECT_TRIG = 0x06, // 0110 151 | opOBJECT_WAIT = 0x07, // 0111 152 | opRETURN = 0x08, // 1000 153 | opCALL = 0x09, // 1001 154 | opOBJECT_END = 0x0A, // 1010 155 | opSLEEP = 0x0B, // 1011 156 | opPROGRAM_INFO = 0x0C, // 1100 157 | opLABEL = 0x0D, // 1101 158 | opPROBE = 0x0E, // 1110 159 | opDO = 0x0F, // 1111 160 | 161 | // \endverbatim \ref cMath "MATH" \verbatim 162 | // 0001.... 163 | // ADD 00.. 164 | opADD8 = 0x10, // 00 165 | opADD16 = 0x11, // 01 166 | opADD32 = 0x12, // 10 167 | opADDF = 0x13, // 11 168 | // SUB 01.. 169 | opSUB8 = 0x14, // 00 170 | opSUB16 = 0x15, // 01 171 | opSUB32 = 0x16, // 10 172 | opSUBF = 0x17, // 11 173 | // MUL 10.. 174 | opMUL8 = 0x18, // 00 175 | opMUL16 = 0x19, // 01 176 | opMUL32 = 0x1A, // 10 177 | opMULF = 0x1B, // 11 178 | // DIV 11.. 179 | opDIV8 = 0x1C, // 00 180 | opDIV16 = 0x1D, // 01 181 | opDIV32 = 0x1E, // 10 182 | opDIVF = 0x1F, // 11 183 | 184 | // \endverbatim \ref Logic "LOGIC" \verbatim 185 | // LOGIC 0010.... 186 | // OR 00.. 187 | opOR8 = 0x20, // 00 188 | opOR16 = 0x21, // 01 189 | opOR32 = 0x22, // 10 190 | 191 | // AND 01.. 192 | opAND8 = 0x24, // 00 193 | opAND16 = 0x25, // 01 194 | opAND32 = 0x26, // 10 195 | 196 | // XOR 10.. 197 | opXOR8 = 0x28, // 00 198 | opXOR16 = 0x29, // 01 199 | opXOR32 = 0x2A, // 10 200 | 201 | // RL 11.. 202 | opRL8 = 0x2C, // 00 203 | opRL16 = 0x2D, // 01 204 | opRL32 = 0x2E, // 10 205 | 206 | // \endverbatim \ref cMove "MOVE" \verbatim 207 | opINIT_BYTES = 0x2F, // 1111 208 | // MOVE 0011.... 209 | // MOVE8_ 00.. 210 | opMOVE8_8 = 0x30, // 00 211 | opMOVE8_16 = 0x31, // 01 212 | opMOVE8_32 = 0x32, // 10 213 | opMOVE8_F = 0x33, // 11 214 | // MOVE16_ 01.. 215 | opMOVE16_8 = 0x34, // 00 216 | opMOVE16_16 = 0x35, // 01 217 | opMOVE16_32 = 0x36, // 10 218 | opMOVE16_F = 0x37, // 11 219 | // MOVE32_ 10.. 220 | opMOVE32_8 = 0x38, // 00 221 | opMOVE32_16 = 0x39, // 01 222 | opMOVE32_32 = 0x3A, // 10 223 | opMOVE32_F = 0x3B, // 11 224 | // MOVEF_ 11.. 225 | opMOVEF_8 = 0x3C, // 00 226 | opMOVEF_16 = 0x3D, // 01 227 | opMOVEF_32 = 0x3E, // 10 228 | opMOVEF_F = 0x3F, // 11 229 | 230 | // \endverbatim \ref cBranch "BRANCH" \verbatim 231 | // BRANCH 010000.. 232 | opJR = 0x40, // 00 233 | opJR_FALSE = 0x41, // 01 234 | opJR_TRUE = 0x42, // 10 235 | opJR_NAN = 0x43, // 11 236 | 237 | // \endverbatim \ref cCompare "COMPARE" \verbatim 238 | // COMPARE 010..... 239 | // CP_LT 001.. 240 | opCP_LT8 = 0x44, // 00 241 | opCP_LT16 = 0x45, // 01 242 | opCP_LT32 = 0x46, // 10 243 | opCP_LTF = 0x47, // 11 244 | // CP_GT 010.. 245 | opCP_GT8 = 0x48, // 00 246 | opCP_GT16 = 0x49, // 01 247 | opCP_GT32 = 0x4A, // 10 248 | opCP_GTF = 0x4B, // 11 249 | // CP_EQ 011.. 250 | opCP_EQ8 = 0x4C, // 00 251 | opCP_EQ16 = 0x4D, // 01 252 | opCP_EQ32 = 0x4E, // 10 253 | opCP_EQF = 0x4F, // 11 254 | // CP_NEQ 100.. 255 | opCP_NEQ8 = 0x50, // 00 256 | opCP_NEQ16 = 0x51, // 01 257 | opCP_NEQ32 = 0x52, // 10 258 | opCP_NEQF = 0x53, // 11 259 | // CP_LTEQ 101.. 260 | opCP_LTEQ8 = 0x54, // 00 261 | opCP_LTEQ16 = 0x55, // 01 262 | opCP_LTEQ32 = 0x56, // 10 263 | opCP_LTEQF = 0x57, // 11 264 | // CP_GTEQ 110.. 265 | opCP_GTEQ8 = 0x58, // 00 266 | opCP_GTEQ16 = 0x59, // 01 267 | opCP_GTEQ32 = 0x5A, // 10 268 | opCP_GTEQF = 0x5B, // 11 269 | 270 | // \endverbatim \ref Select "SELECT" \verbatim 271 | // SELECT 010111.. 272 | opSELECT8 = 0x5C, // 00 273 | opSELECT16 = 0x5D, // 01 274 | opSELECT32 = 0x5E, // 10 275 | opSELECTF = 0x5F, // 11 276 | 277 | 278 | // \endverbatim \ref VM \verbatim 279 | opSYSTEM = 0x60, 280 | opPORT_CNV_OUTPUT = 0x61, 281 | opPORT_CNV_INPUT = 0x62, 282 | opNOTE_TO_FREQ = 0x63, 283 | 284 | // \endverbatim \ref cBranch "BRANCH" \verbatim 285 | // BRANCH 011000.. 286 | //? 00 287 | //? 01 288 | //? 10 289 | //? 11 290 | // JR_LT 001.. 291 | opJR_LT8 = 0x64, // 00 292 | opJR_LT16 = 0x65, // 01 293 | opJR_LT32 = 0x66, // 10 294 | opJR_LTF = 0x67, // 11 295 | // JR_GT 010.. 296 | opJR_GT8 = 0x68, // 00 297 | opJR_GT16 = 0x69, // 01 298 | opJR_GT32 = 0x6A, // 10 299 | opJR_GTF = 0x6B, // 11 300 | // JR_EQ 011.. 301 | opJR_EQ8 = 0x6C, // 00 302 | opJR_EQ16 = 0x6D, // 01 303 | opJR_EQ32 = 0x6E, // 10 304 | opJR_EQF = 0x6F, // 11 305 | // JR_NEQ 100.. 306 | opJR_NEQ8 = 0x70, // 00 307 | opJR_NEQ16 = 0x71, // 01 308 | opJR_NEQ32 = 0x72, // 10 309 | opJR_NEQF = 0x73, // 11 310 | // JR_LTEQ 101.. 311 | opJR_LTEQ8 = 0x74, // 00 312 | opJR_LTEQ16 = 0x75, // 01 313 | opJR_LTEQ32 = 0x76, // 10 314 | opJR_LTEQF = 0x77, // 11 315 | // JR_GTEQ 110.. 316 | opJR_GTEQ8 = 0x78, // 00 317 | opJR_GTEQ16 = 0x79, // 01 318 | opJR_GTEQ32 = 0x7A, // 10 319 | opJR_GTEQF = 0x7B, // 11 320 | 321 | // \endverbatim \ref VM \verbatim 322 | opINFO = 0x7C, // 01111100 323 | opSTRINGS = 0x7D, // 01111101 324 | opMEMORY_WRITE = 0x7E, // 01111110 325 | opMEMORY_READ = 0x7F, // 01111111 326 | 327 | // SYSTEM 1....... 328 | 329 | // \endverbatim \ref cUi "UI" \verbatim 330 | // UI 100000.. 331 | opUI_FLUSH = 0x80, // 00 332 | opUI_READ = 0x81, // 01 333 | opUI_WRITE = 0x82, // 10 334 | opUI_BUTTON = 0x83, // 11 335 | opUI_DRAW = 0x84, // 10000100 336 | 337 | // \endverbatim \ref cTimer "TIMER" \verbatim 338 | opTIMER_WAIT = 0x85, // 10000101 339 | opTIMER_READY = 0x86, // 10000110 340 | opTIMER_READ = 0x87, // 10000111 341 | 342 | // \endverbatim \ref VM \verbatim 343 | // BREAKPOINT 10001... 344 | opBP0 = 0x88, // 000 345 | opBP1 = 0x89, // 001 346 | opBP2 = 0x8A, // 010 347 | opBP3 = 0x8B, // 011 348 | opBP_SET = 0x8C, // 10001100 349 | opMATH = 0x8D, // 10001101 350 | opRANDOM = 0x8E, // 10001110 351 | 352 | // \endverbatim \ref cTimer "TIMER" \verbatim 353 | opTIMER_READ_US = 0x8F, // 10001111 354 | 355 | // \endverbatim \ref cUi "UI" \verbatim 356 | opKEEP_ALIVE = 0x90, // 10010000 357 | 358 | // \endverbatim \ref cCom "COM" \verbatim 359 | // 100100 360 | opCOM_READ = 0x91, // 01 361 | opCOM_WRITE = 0x92, // 10 362 | 363 | // \endverbatim \ref cSound "SOUND" \verbatim 364 | // 100101 365 | opSOUND = 0x94, // 00 366 | opSOUND_TEST = 0x95, // 01 367 | opSOUND_READY = 0x96, // 10 368 | 369 | // \endverbatim \ref cInput "INPUT" \verbatim 370 | // 371 | opINPUT_SAMPLE = 0x97, // 10010111 372 | 373 | // 10011... 374 | opINPUT_DEVICE_LIST = 0x98, // 000 375 | opINPUT_DEVICE = 0x99, // 001 376 | opINPUT_READ = 0x9A, // 010 377 | opINPUT_TEST = 0x9B, // 011 378 | opINPUT_READY = 0x9C, // 100 379 | opINPUT_READSI = 0x9D, // 101 380 | opINPUT_READEXT = 0x9E, // 110 381 | opINPUT_WRITE = 0x9F, // 111 382 | // \endverbatim \ref cOutput "OUTPUT" \verbatim 383 | // 101..... 384 | opOUTPUT_GET_TYPE = 0xA0, // 00000 385 | opOUTPUT_SET_TYPE = 0xA1, // 00001 386 | opOUTPUT_RESET = 0xA2, // 00010 387 | opOUTPUT_STOP = 0xA3, // 00011 388 | opOUTPUT_POWER = 0xA4, // 00100 389 | opOUTPUT_SPEED = 0xA5, // 00101 390 | opOUTPUT_START = 0xA6, // 00110 391 | opOUTPUT_POLARITY = 0xA7, // 00111 392 | opOUTPUT_READ = 0xA8, // 01000 393 | opOUTPUT_TEST = 0xA9, // 01001 394 | opOUTPUT_READY = 0xAA, // 01010 395 | opOUTPUT_POSITION = 0xAB, // 01011 396 | opOUTPUT_STEP_POWER = 0xAC, // 01100 397 | opOUTPUT_TIME_POWER = 0xAD, // 01101 398 | opOUTPUT_STEP_SPEED = 0xAE, // 01110 399 | opOUTPUT_TIME_SPEED = 0xAF, // 01111 400 | 401 | opOUTPUT_STEP_SYNC = 0xB0, // 10000 402 | opOUTPUT_TIME_SYNC = 0xB1, // 10001 403 | opOUTPUT_CLR_COUNT = 0xB2, // 10010 404 | opOUTPUT_GET_COUNT = 0xB3, // 10011 405 | 406 | opOUTPUT_PRG_STOP = 0xB4, // 10100 407 | 408 | // \endverbatim \ref cMemory "MEMORY" \verbatim 409 | // 11000... 410 | opFILE = 0xC0, // 000 411 | opARRAY = 0xC1, // 001 412 | opARRAY_WRITE = 0xC2, // 010 413 | opARRAY_READ = 0xC3, // 011 414 | opARRAY_APPEND = 0xC4, // 100 415 | opMEMORY_USAGE = 0xC5, // 101 416 | opFILENAME = 0xC6, // 110 417 | 418 | // \endverbatim \ref cMove "READ" \verbatim 419 | // 110010.. 420 | opREAD8 = 0xC8, // 00 421 | opREAD16 = 0xC9, // 01 422 | opREAD32 = 0xCA, // 10 423 | opREADF = 0xCB, // 11 424 | 425 | // \endverbatim \ref cMove "WRITE" \verbatim 426 | // 110011.. 427 | opWRITE8 = 0xCC, // 00 428 | opWRITE16 = 0xCD, // 01 429 | opWRITE32 = 0xCE, // 10 430 | opWRITEF = 0xCF, // 11 431 | 432 | // \endverbatim \ref cCom "COM" \verbatim 433 | // 11010... 434 | opCOM_READY = 0xD0, // 000 435 | opCOM_READDATA = 0xD1, // 001 436 | opCOM_WRITEDATA = 0xD2, // 010 437 | opCOM_GET = 0xD3, // 011 438 | opCOM_SET = 0xD4, // 100 439 | opCOM_TEST = 0xD5, // 101 440 | opCOM_REMOVE = 0xD6, // 110 441 | opCOM_WRITEFILE = 0xD7, // 111 442 | 443 | // 11011... 444 | opMAILBOX_OPEN = 0xD8, // 000 445 | opMAILBOX_WRITE = 0xD9, // 001 446 | opMAILBOX_READ = 0xDA, // 010 447 | opMAILBOX_TEST = 0xDB, // 011 448 | opMAILBOX_READY = 0xDC, // 100 449 | opMAILBOX_CLOSE = 0xDD, // 101 450 | 451 | // SPARE 111..... 452 | 453 | // \endverbatim \ref TST \verbatim 454 | opTST = 0xFF // 11111111 455 | } 456 | OP; 457 | /* 458 | * \endverbatim 459 | */ 460 | 461 | 462 | //! \page uireadsubcode Specific command parameter 463 | //! 464 | //! 465 | //! \verbatim 466 | //! 467 | 468 | typedef enum 469 | { 470 | GET_VBATT = 1, 471 | GET_IBATT = 2, 472 | GET_OS_VERS = 3, 473 | GET_EVENT = 4, 474 | GET_TBATT = 5, 475 | GET_IINT = 6, 476 | GET_IMOTOR = 7, 477 | GET_STRING = 8, 478 | GET_HW_VERS = 9, 479 | GET_FW_VERS = 10, 480 | GET_FW_BUILD = 11, 481 | GET_OS_BUILD = 12, 482 | GET_ADDRESS = 13, 483 | GET_CODE = 14, 484 | KEY = 15, 485 | GET_SHUTDOWN = 16, 486 | GET_WARNING = 17, 487 | GET_LBATT = 18, 488 | TEXTBOX_READ = 21, 489 | GET_VERSION = 26, 490 | GET_IP = 27, 491 | GET_POWER = 29, 492 | GET_SDCARD = 30, 493 | GET_USBSTICK = 31, 494 | 495 | UI_READ_SUBCODES 496 | } 497 | UI_READ_SUBCODE; 498 | 499 | //! \endverbatim 500 | 501 | 502 | //! \page uiwritesubcode Specific command parameter 503 | //! 504 | //! 505 | //! \verbatim 506 | //! 507 | 508 | typedef enum 509 | { 510 | WRITE_FLUSH = 1, 511 | FLOATVALUE = 2, 512 | STAMP = 3, 513 | PUT_STRING = 8, 514 | VALUE8 = 9, 515 | VALUE16 = 10, 516 | VALUE32 = 11, 517 | VALUEF = 12, 518 | ADDRESS = 13, 519 | CODE = 14, 520 | DOWNLOAD_END = 15, 521 | SCREEN_BLOCK = 16, 522 | TEXTBOX_APPEND = 21, 523 | SET_BUSY = 22, 524 | SET_TESTPIN = 24, 525 | INIT_RUN = 25, 526 | UPDATE_RUN = 26, 527 | LED = 27, 528 | POWER = 29, 529 | GRAPH_SAMPLE = 30, 530 | TERMINAL = 31, 531 | 532 | UI_WRITE_SUBCODES 533 | } 534 | UI_WRITE_SUBCODE; 535 | 536 | //! \endverbatim 537 | 538 | 539 | //! \page uibuttonsubcode Specific command parameter 540 | //! 541 | //! 542 | //! \verbatim 543 | //! 544 | 545 | typedef enum 546 | { 547 | SHORTPRESS = 1, 548 | LONGPRESS = 2, 549 | WAIT_FOR_PRESS = 3, 550 | FLUSH = 4, 551 | PRESS = 5, 552 | RELEASE = 6, 553 | GET_HORZ = 7, 554 | GET_VERT = 8, 555 | PRESSED = 9, 556 | SET_BACK_BLOCK = 10, 557 | GET_BACK_BLOCK = 11, 558 | TESTSHORTPRESS = 12, 559 | TESTLONGPRESS = 13, 560 | GET_BUMBED = 14, 561 | GET_CLICK = 15, 562 | 563 | UI_BUTTON_SUBCODES 564 | } 565 | UI_BUTTON_SUBCODE; 566 | 567 | //! \endverbatim 568 | 569 | 570 | //! \page comreadsubcode Specific command parameter 571 | //! 572 | //! 573 | //! \verbatim 574 | //! 575 | 576 | typedef enum 577 | { 578 | COMMAND = 14, 579 | 580 | COM_READ_SUBCODES 581 | } 582 | COM_READ_SUBCODE; 583 | 584 | //! \endverbatim 585 | 586 | 587 | //! \page comwritesubcode Specific command parameter 588 | //! 589 | //! 590 | //! \verbatim 591 | //! 592 | 593 | typedef enum 594 | { 595 | REPLY = 14, 596 | 597 | COM_WRITE_SUBCODES 598 | } 599 | COM_WRITE_SUBCODE; 600 | 601 | //! \endverbatim 602 | 603 | 604 | //! \page comgetsubcode Specific command parameter 605 | //! 606 | //! \verbatim 607 | //! 608 | 609 | typedef enum 610 | { 611 | GET_ON_OFF = 1, //!< Set, Get 612 | GET_VISIBLE = 2, //!< Set, Get 613 | GET_RESULT = 4, //!< Get 614 | GET_PIN = 5, //!< Set, Get 615 | SEARCH_ITEMS = 8, //!< Get 616 | SEARCH_ITEM = 9, //!< Get 617 | FAVOUR_ITEMS = 10, //!< Get 618 | FAVOUR_ITEM = 11, //!< Get 619 | GET_ID = 12, 620 | GET_BRICKNAME = 13, 621 | GET_NETWORK = 14, 622 | GET_PRESENT = 15, 623 | GET_ENCRYPT = 16, 624 | CONNEC_ITEMS = 17, 625 | CONNEC_ITEM = 18, 626 | GET_INCOMING = 19, 627 | GET_MODE2 = 20, 628 | 629 | COM_GET_SUBCODES 630 | } 631 | COM_GET_SUBCODE; 632 | 633 | //! \endverbatim 634 | 635 | 636 | //! \page comsetsubcode Specific command parameter 637 | //! 638 | //! \verbatim 639 | //! 640 | 641 | typedef enum 642 | { 643 | SET_ON_OFF = 1, //!< Set, Get 644 | SET_VISIBLE = 2, //!< Set, Get 645 | SET_SEARCH = 3, //!< Set 646 | SET_PIN = 5, //!< Set, Get 647 | SET_PASSKEY = 6, //!< Set 648 | SET_CONNECTION = 7, //!< Set 649 | SET_BRICKNAME = 8, 650 | SET_MOVEUP = 9, 651 | SET_MOVEDOWN = 10, 652 | SET_ENCRYPT = 11, 653 | SET_SSID = 12, 654 | SET_MODE2 = 13, 655 | 656 | COM_SET_SUBCODES 657 | } 658 | COM_SET_SUBCODE; 659 | 660 | //! \endverbatim 661 | 662 | 663 | //! \page inputdevicesubcode Specific command parameter 664 | //! 665 | //! 666 | //! \verbatim 667 | //! 668 | 669 | typedef enum 670 | { 671 | GET_FORMAT = 2, 672 | CAL_MINMAX = 3, 673 | CAL_DEFAULT = 4, 674 | GET_TYPEMODE = 5, 675 | GET_SYMBOL = 6, 676 | CAL_MIN = 7, 677 | CAL_MAX = 8, 678 | SETUP = 9, 679 | CLR_ALL = 10, 680 | GET_RAW = 11, 681 | GET_CONNECTION = 12, 682 | STOP_ALL = 13, 683 | GET_NAME = 21, 684 | GET_MODENAME = 22, 685 | SET_RAW = 23, 686 | GET_FIGURES = 24, 687 | GET_CHANGES = 25, 688 | CLR_CHANGES = 26, 689 | READY_PCT = 27, 690 | READY_RAW = 28, 691 | READY_SI = 29, 692 | GET_MINMAX = 30, 693 | GET_BUMPS = 31, 694 | 695 | INPUT_DEVICESUBCODES 696 | } 697 | INPUT_DEVICE_SUBCODE; 698 | 699 | //! \endverbatim 700 | 701 | 702 | //! \page programinfosubcode Specific command parameter 703 | //! 704 | //! 705 | //! \verbatim 706 | //! 707 | 708 | typedef enum 709 | { 710 | OBJ_STOP = 0, // VM 711 | OBJ_START = 4, // VM 712 | GET_STATUS = 22, // VM 713 | GET_SPEED = 23, // VM 714 | GET_PRGRESULT = 24, // VM 715 | SET_INSTR = 25, // VM 716 | 717 | PROGRAM_INFO_SUBCODES, 718 | } 719 | PROGRAM_INFO_SUBCODE; 720 | 721 | //! \endverbatim 722 | 723 | 724 | //! \page uidrawsubcode Specific command parameter 725 | //! 726 | //! 727 | //! \verbatim 728 | //! 729 | 730 | typedef enum 731 | { 732 | UPDATE = 0, 733 | CLEAN = 1, 734 | PIXEL = 2, 735 | LINE = 3, 736 | CIRCLE = 4, 737 | TEXT = 5, 738 | ICON = 6, 739 | PICTURE = 7, 740 | VALUE = 8, 741 | FILLRECT = 9, 742 | RECT = 10, 743 | NOTIFICATION = 11, 744 | QUESTION = 12, 745 | KEYBOARD = 13, 746 | BROWSE = 14, 747 | VERTBAR = 15, 748 | INVERSERECT = 16, 749 | SELECT_FONT = 17, 750 | TOPLINE = 18, 751 | FILLWINDOW = 19, 752 | SCROLL = 20, 753 | DOTLINE = 21, 754 | VIEW_VALUE = 22, 755 | VIEW_UNIT = 23, 756 | FILLCIRCLE = 24, 757 | STORE = 25, 758 | RESTORE = 26, 759 | ICON_QUESTION = 27, 760 | BMPFILE = 28, 761 | POPUP = 29, 762 | GRAPH_SETUP = 30, 763 | GRAPH_DRAW = 31, 764 | TEXTBOX = 32, 765 | 766 | UI_DRAW_SUBCODES 767 | } 768 | UI_DRAW_SUBCODE; 769 | 770 | //! \endverbatim 771 | 772 | 773 | //! \page memoryfilesubcode Specific command parameter 774 | //! 775 | //! 776 | //! \verbatim 777 | //! 778 | 779 | typedef enum 780 | { 781 | OPEN_APPEND = 0, 782 | OPEN_READ = 1, 783 | OPEN_WRITE = 2, 784 | READ_VALUE = 3, 785 | WRITE_VALUE = 4, 786 | READ_TEXT = 5, 787 | WRITE_TEXT = 6, 788 | CLOSE = 7, 789 | LOAD_IMAGE = 8, 790 | GET_HANDLE = 9, 791 | MAKE_FOLDER = 10, 792 | GET_POOL = 11, 793 | SET_LOG_SYNC_TIME = 12, 794 | GET_FOLDERS = 13, 795 | GET_LOG_SYNC_TIME = 14, 796 | GET_SUBFOLDER_NAME = 15, 797 | WRITE_LOG = 16, 798 | CLOSE_LOG = 17, 799 | GET_IMAGE = 18, 800 | GET_ITEM = 19, 801 | GET_CACHE_FILES = 20, 802 | PUT_CACHE_FILE = 21, 803 | GET_CACHE_FILE = 22, 804 | DEL_CACHE_FILE = 23, 805 | DEL_SUBFOLDER = 24, 806 | GET_LOG_NAME = 25, 807 | 808 | OPEN_LOG = 27, 809 | READ_BYTES = 28, 810 | WRITE_BYTES = 29, 811 | REMOVE = 30, 812 | MOVE = 31, 813 | 814 | FILE_SUBCODES 815 | } 816 | FILE_SUBCODE; 817 | 818 | //! \endverbatim 819 | 820 | 821 | //! \page memoryarraysubcode Specific command parameter 822 | //! 823 | //! 824 | //! \verbatim 825 | //! 826 | 827 | typedef enum 828 | { 829 | DELETE = 0, 830 | CREATE8 = 1, 831 | CREATE16 = 2, 832 | CREATE32 = 3, 833 | CREATEF = 4, 834 | RESIZE = 5, 835 | FILL = 6, 836 | COPY = 7, 837 | INIT8 = 8, 838 | INIT16 = 9, 839 | INIT32 = 10, 840 | INITF = 11, 841 | SIZE = 12, 842 | READ_CONTENT = 13, 843 | WRITE_CONTENT = 14, 844 | READ_SIZE = 15, 845 | 846 | ARRAY_SUBCODES 847 | } 848 | ARRAY_SUBCODE; 849 | 850 | //! \endverbatim 851 | 852 | 853 | //! \page memoryfilenamesubcode Specific command parameter 854 | //! 855 | //! \verbatim 856 | //! 857 | 858 | typedef enum 859 | { 860 | EXIST = 16, //!< MUST BE GREATER OR EQUAL TO "ARRAY_SUBCODES" 861 | TOTALSIZE = 17, 862 | SPLIT = 18, 863 | MERGE = 19, 864 | CHECK = 20, 865 | PACK = 21, 866 | UNPACK = 22, 867 | GET_FOLDERNAME = 23, 868 | 869 | FILENAME_SUBCODES 870 | } 871 | FILENAME_SUBCODE; 872 | 873 | //! \endverbatim 874 | 875 | 876 | //! \page infosubcode Specific command parameter 877 | //! 878 | //! 879 | //! \verbatim 880 | //! 881 | 882 | typedef enum 883 | { 884 | SET_ERROR = 1, 885 | GET_ERROR = 2, 886 | ERRORTEXT = 3, 887 | 888 | GET_VOLUME = 4, 889 | SET_VOLUME = 5, 890 | GET_MINUTES = 6, 891 | SET_MINUTES = 7, 892 | 893 | INFO_SUBCODES 894 | } 895 | INFO_SUBCODE; 896 | 897 | //! \endverbatim 898 | 899 | 900 | //! \page soundsubcode Specific command parameter 901 | //! 902 | //! 903 | //! \verbatim 904 | //! 905 | 906 | typedef enum 907 | { 908 | BREAK = 0, 909 | TONE = 1, 910 | PLAY = 2, 911 | REPEAT = 3, 912 | SERVICE = 4, 913 | 914 | SOUND_SUBCODES 915 | } 916 | SOUND_SUBCODE; 917 | 918 | //! \endverbatim 919 | 920 | 921 | //! \page stringsubcode Specific command parameter 922 | //! 923 | //! 924 | //! \verbatim 925 | //! 926 | 927 | typedef enum 928 | { 929 | GET_SIZE = 1, // VM get string size 930 | ADD = 2, // VM add two strings 931 | COMPARE = 3, // VM compare two strings 932 | DUPLICATE = 5, // VM duplicate one string to another 933 | VALUE_TO_STRING = 6, 934 | STRING_TO_VALUE = 7, 935 | STRIP = 8, 936 | NUMBER_TO_STRING = 9, 937 | SUB = 10, 938 | VALUE_FORMATTED = 11, 939 | NUMBER_FORMATTED = 12, 940 | 941 | STRING_SUBCODES 942 | } 943 | STRING_SUBCODE; 944 | 945 | //! \endverbatim 946 | 947 | 948 | /*! \page programid Program ID's (Slots) 949 | 950 | \anchor prgid 951 | 952 | \verbatim */ 953 | 954 | typedef enum 955 | { 956 | GUI_SLOT = 0, //!< Program slot reserved for executing the user interface 957 | USER_SLOT = 1, //!< Program slot used to execute user projects, apps and tools 958 | CMD_SLOT = 2, //!< Program slot used for direct commands coming from c_com 959 | TERM_SLOT = 3, //!< Program slot used for direct commands coming from c_ui 960 | DEBUG_SLOT = 4, //!< Program slot used to run the debug ui 961 | 962 | SLOTS, //!< Maximum slots supported by the VM 963 | 964 | // ONLY VALID IN opPROGRAM_STOP 965 | CURRENT_SLOT = -1 966 | } 967 | SLOT; 968 | 969 | /* \endverbatim */ 970 | 971 | 972 | /*! \page buttons Button 973 | 974 | \verbatim */ 975 | 976 | typedef enum 977 | { 978 | NO_BUTTON = 0, 979 | UP_BUTTON = 1, 980 | ENTER_BUTTON = 2, 981 | DOWN_BUTTON = 3, 982 | RIGHT_BUTTON = 4, 983 | LEFT_BUTTON = 5, 984 | BACK_BUTTON = 6, 985 | ANY_BUTTON = 7, 986 | 987 | BUTTONTYPES = 8 988 | } 989 | BUTTONTYPE; 990 | 991 | /* \endverbatim */ 992 | 993 | 994 | /*! \page mathsubcode Specific command parameter 995 | 996 | \verbatim */ 997 | 998 | typedef enum 999 | { 1000 | EXP = 1, //!< e^x r = expf(x) 1001 | MOD = 2, //!< Modulo r = fmod(x,y) 1002 | FLOOR = 3, //!< Floor r = floor(x) 1003 | CEIL = 4, //!< Ceiling r = ceil(x) 1004 | ROUND = 5, //!< Round r = round(x) 1005 | ABS = 6, //!< Absolute r = fabs(x) 1006 | NEGATE = 7, //!< Negate r = 0.0 - x 1007 | SQRT = 8, //!< Squareroot r = sqrt(x) 1008 | LOG = 9, //!< Log r = log10(x) 1009 | LN = 10, //!< Ln r = log(x) 1010 | SIN = 11, //!< 1011 | COS = 12, //!< 1012 | TAN = 13, //!< 1013 | ASIN = 14, //!< 1014 | ACOS = 15, //!< 1015 | ATAN = 16, //!< 1016 | MOD8 = 17, //!< Modulo DATA8 r = x % y 1017 | MOD16 = 18, //!< Modulo DATA16 r = x % y 1018 | MOD32 = 19, //!< Modulo DATA32 r = x % y 1019 | POW = 20, //!< Exponent r = powf(x,y) 1020 | TRUNC = 21, //!< Truncate r = (float)((int)(x * pow(y))) / pow(y) 1021 | 1022 | MATHTYPES //!< Maximum number of math functions supported by the VM 1023 | } 1024 | MATHTYPE; 1025 | 1026 | /* \endverbatim */ 1027 | 1028 | 1029 | //! \page tstsubcode Specific command parameter 1030 | //! 1031 | //! \verbatim 1032 | //! 1033 | 1034 | typedef enum 1035 | { 1036 | TST_OPEN = 10, //!< MUST BE GREATER OR EQUAL TO "INFO_SUBCODES" 1037 | TST_CLOSE = 11, 1038 | TST_READ_PINS = 12, 1039 | TST_WRITE_PINS = 13, 1040 | TST_READ_ADC = 14, 1041 | TST_WRITE_UART = 15, 1042 | TST_READ_UART = 16, 1043 | TST_ENABLE_UART = 17, 1044 | TST_DISABLE_UART = 18, 1045 | TST_ACCU_SWITCH = 19, 1046 | TST_BOOT_MODE2 = 20, 1047 | TST_POLL_MODE2 = 21, 1048 | TST_CLOSE_MODE2 = 22, 1049 | TST_RAM_CHECK = 23, 1050 | 1051 | TST_SUBCODES 1052 | } 1053 | TST_SUBCODE; 1054 | 1055 | //! \endverbatim 1056 | 1057 | 1058 | /*! \page browsers Browser Types Avaliable 1059 | 1060 | \verbatim */ 1061 | 1062 | typedef enum 1063 | { 1064 | BROWSE_FOLDERS = 0, //!< Browser for folders 1065 | BROWSE_FOLDS_FILES = 1, //!< Browser for folders and files 1066 | BROWSE_CACHE = 2, //!< Browser for cached / recent files 1067 | BROWSE_FILES = 3, //!< Browser for files 1068 | 1069 | BROWSERTYPES //!< Maximum font types supported by the VM 1070 | } 1071 | BROWSERTYPE; 1072 | 1073 | /* \endverbatim */ 1074 | 1075 | 1076 | /*! \page fonts Font Types Avaliable 1077 | 1078 | \verbatim */ 1079 | 1080 | typedef enum 1081 | { 1082 | NORMAL_FONT = 0, 1083 | SMALL_FONT = 1, 1084 | LARGE_FONT = 2, 1085 | TINY_FONT = 3, 1086 | 1087 | FONTTYPES //!< Maximum font types supported by the VM 1088 | } 1089 | FONTTYPE; 1090 | 1091 | /* \endverbatim */ 1092 | 1093 | 1094 | /*! \page icons Icon Types Avaliable 1095 | 1096 | \verbatim */ 1097 | 1098 | typedef enum 1099 | { 1100 | NORMAL_ICON = 0, //!< "24x12_Files_Folders_Settings.bmp" 1101 | SMALL_ICON = 1, 1102 | LARGE_ICON = 2, //!< "24x22_Yes_No_OFF_FILEOps.bmp" 1103 | MENU_ICON = 3, 1104 | ARROW_ICON = 4, //!< "8x12_miniArrows.bmp" 1105 | 1106 | ICONTYPES //!< Maximum icon types supported by the VM 1107 | } 1108 | ICONTYPE; 1109 | 1110 | 1111 | typedef enum 1112 | { 1113 | SICON_CHARGING = 0, 1114 | SICON_BATT_4 = 1, 1115 | SICON_BATT_3 = 2, 1116 | SICON_BATT_2 = 3, 1117 | SICON_BATT_1 = 4, 1118 | SICON_BATT_0 = 5, 1119 | SICON_WAIT1 = 6, 1120 | SICON_WAIT2 = 7, 1121 | SICON_BT_ON = 8, 1122 | SICON_BT_VISIBLE = 9, 1123 | SICON_BT_CONNECTED = 10, 1124 | SICON_BT_CONNVISIB = 11, 1125 | SICON_WIFI_3 = 12, 1126 | SICON_WIFI_2 = 13, 1127 | SICON_WIFI_1 = 14, 1128 | SICON_WIFI_CONNECTED = 15, 1129 | 1130 | SICON_USB = 21, 1131 | 1132 | S_ICON_NOS 1133 | } 1134 | S_ICON_NO; 1135 | 1136 | 1137 | typedef enum 1138 | { 1139 | ICON_NONE = -1, 1140 | ICON_RUN = 0, 1141 | ICON_FOLDER = 1, 1142 | ICON_FOLDER2 = 2, 1143 | ICON_USB = 3, 1144 | ICON_SD = 4, 1145 | ICON_SOUND = 5, 1146 | ICON_IMAGE = 6, 1147 | ICON_SETTINGS = 7, 1148 | ICON_ONOFF = 8, 1149 | ICON_SEARCH = 9, 1150 | ICON_WIFI = 10, 1151 | ICON_CONNECTIONS = 11, 1152 | ICON_ADD_HIDDEN = 12, 1153 | ICON_TRASHBIN = 13, 1154 | ICON_VISIBILITY = 14, 1155 | ICON_KEY = 15, 1156 | ICON_CONNECT = 16, 1157 | ICON_DISCONNECT = 17, 1158 | ICON_UP = 18, 1159 | ICON_DOWN = 19, 1160 | ICON_WAIT1 = 20, 1161 | ICON_WAIT2 = 21, 1162 | ICON_BLUETOOTH = 22, 1163 | ICON_INFO = 23, 1164 | ICON_TEXT = 24, 1165 | 1166 | 1167 | ICON_QUESTIONMARK = 27, 1168 | ICON_INFO_FILE = 28, 1169 | ICON_DISC = 29, 1170 | ICON_CONNECTED = 30, 1171 | ICON_OBP = 31, 1172 | ICON_OBD = 32, 1173 | ICON_OPENFOLDER = 33, 1174 | ICON_BRICK1 = 34, 1175 | N_ICON_NOS 1176 | } 1177 | N_ICON_NO; 1178 | 1179 | 1180 | typedef enum 1181 | { 1182 | YES_NOTSEL = 0, 1183 | YES_SEL = 1, 1184 | NO_NOTSEL = 2, 1185 | NO_SEL = 3, 1186 | OFF = 4, 1187 | WAIT_VERT = 5, 1188 | WAIT_HORZ = 6, 1189 | TO_MANUAL = 7, 1190 | WARNSIGN = 8, 1191 | WARN_BATT = 9, 1192 | WARN_POWER = 10, 1193 | WARN_TEMP = 11, 1194 | NO_USBSTICK = 12, 1195 | TO_EXECUTE = 13, 1196 | TO_BRICK = 14, 1197 | TO_SDCARD = 15, 1198 | TO_USBSTICK = 16, 1199 | TO_BLUETOOTH = 17, 1200 | TO_WIFI = 18, 1201 | TO_TRASH = 19, 1202 | TO_COPY = 20, 1203 | TO_FILE = 21, 1204 | CHAR_ERROR = 22, 1205 | COPY_ERROR = 23, 1206 | PROGRAM_ERROR = 24, 1207 | 1208 | 1209 | WARN_MEMORY = 27, 1210 | L_ICON_NOS 1211 | } 1212 | L_ICON_NO; 1213 | 1214 | 1215 | typedef enum 1216 | { 1217 | ICON_STAR = 0, 1218 | ICON_LOCKSTAR = 1, 1219 | ICON_LOCK = 2, 1220 | ICON_PC = 3, //!< Bluetooth type PC 1221 | ICON_PHONE = 4, //!< Bluetooth type PHONE 1222 | ICON_BRICK = 5, //!< Bluetooth type BRICK 1223 | ICON_UNKNOWN = 6, //!< Bluetooth type UNKNOWN 1224 | ICON_FROM_FOLDER = 7, 1225 | ICON_CHECKBOX = 8, 1226 | ICON_CHECKED = 9, 1227 | ICON_XED = 10, 1228 | 1229 | M_ICON_NOS 1230 | } 1231 | M_ICON_NO; 1232 | 1233 | 1234 | typedef enum 1235 | { 1236 | 1237 | ICON_LEFT = 1, 1238 | ICON_RIGHT = 2, 1239 | 1240 | A_ICON_NOS 1241 | } 1242 | A_ICON_NO; 1243 | 1244 | 1245 | /* \endverbatim */ 1246 | 1247 | 1248 | /*! \page bttypes Bluetooth Device Types 1249 | 1250 | \verbatim */ 1251 | 1252 | typedef enum 1253 | { 1254 | BTTYPE_PC = 3, //!< Bluetooth type PC 1255 | BTTYPE_PHONE = 4, //!< Bluetooth type PHONE 1256 | BTTYPE_BRICK = 5, //!< Bluetooth type BRICK 1257 | BTTYPE_UNKNOWN = 6, //!< Bluetooth type UNKNOWN 1258 | 1259 | BTTYPES 1260 | } 1261 | BTTYPE; 1262 | 1263 | 1264 | /* \endverbatim */ 1265 | 1266 | 1267 | /*! \page ledpatterns LED Pattern 1268 | 1269 | \verbatim */ 1270 | 1271 | typedef enum 1272 | { 1273 | LED_BLACK = 0, 1274 | LED_GREEN = 1, 1275 | LED_RED = 2, 1276 | LED_ORANGE = 3, 1277 | LED_GREEN_FLASH = 4, 1278 | LED_RED_FLASH = 5, 1279 | LED_ORANGE_FLASH = 6, 1280 | LED_GREEN_PULSE = 7, 1281 | LED_RED_PULSE = 8, 1282 | LED_ORANGE_PULSE = 9, 1283 | 1284 | LEDPATTERNS 1285 | } 1286 | LEDPATTERN; 1287 | 1288 | 1289 | /* \endverbatim */ 1290 | 1291 | 1292 | typedef enum 1293 | { 1294 | LED_ALL = 0, //!< All LEDs 1295 | LED_RR = 1, //!< Right red 1296 | LED_RG = 2, //!< Right green 1297 | LED_LR = 3, //!< Left red 1298 | LED_LG = 4 //!< Left green 1299 | } 1300 | LEDTYPE; 1301 | 1302 | 1303 | /*! \page filetypes File Types Avaliable 1304 | 1305 | \verbatim */ 1306 | 1307 | 1308 | typedef enum 1309 | { 1310 | FILETYPE_UNKNOWN = 0x00, 1311 | TYPE_FOLDER = 0x01, 1312 | TYPE_SOUND = 0x02, 1313 | TYPE_BYTECODE = 0x03, 1314 | TYPE_GRAPHICS = 0x04, 1315 | TYPE_DATALOG = 0x05, 1316 | TYPE_PROGRAM = 0x06, 1317 | TYPE_TEXT = 0x07, 1318 | TYPE_SDCARD = 0x10, 1319 | TYPE_USBSTICK = 0x20, 1320 | 1321 | FILETYPES, //!< Maximum icon types supported by the VM 1322 | 1323 | TYPE_RESTART_BROWSER = -1, 1324 | TYPE_REFRESH_BROWSER = -2 1325 | } 1326 | FILETYPE; 1327 | 1328 | /* \endverbatim */ 1329 | 1330 | 1331 | /*! \page results Results 1332 | 1333 | Describes result from executing functions 1334 | 1335 | \verbatim */ 1336 | 1337 | 1338 | typedef enum 1339 | { 1340 | OK = 0, //!< No errors to report 1341 | BUSY = 1, //!< Busy - try again 1342 | FAIL = 2, //!< Something failed 1343 | STOP = 4 //!< Stopped 1344 | } 1345 | RESULT; 1346 | 1347 | /* \endverbatim */ 1348 | 1349 | 1350 | /*! \page formats 1351 | * 1352 | * Data formats used in device type formats 1353 | * \verbatim 1354 | */ 1355 | 1356 | typedef enum 1357 | { 1358 | DATA_8 = 0x00, //!< DATA8 (don't change) 1359 | DATA_16 = 0x01, //!< DATA16 (don't change) 1360 | DATA_32 = 0x02, //!< DATA32 (don't change) 1361 | DATA_F = 0x03, //!< DATAF (don't change) 1362 | DATA_S = 0x04, //!< Zero terminated string 1363 | DATA_A = 0x05, //!< Array handle 1364 | 1365 | DATA_V = 0x07, //!< Variable type 1366 | 1367 | DATA_PCT = 0x10, //!< Percent (used in opINPUT_READEXT) 1368 | DATA_RAW = 0x12, //!< Raw (used in opINPUT_READEXT) 1369 | DATA_SI = 0x13, //!< SI unit (used in opINPUT_READEXT) 1370 | 1371 | DATA_FORMATS 1372 | } 1373 | DATA_FORMAT; 1374 | 1375 | /*\endverbatim 1376 | * 1377 | * \n 1378 | */ 1379 | 1380 | 1381 | /*! \page delimiters 1382 | * 1383 | * Delimiter codes used to define how data is separated in files 1384 | * \verbatim 1385 | */ 1386 | 1387 | typedef enum 1388 | { 1389 | DEL_NONE = 0, //!< No delimiter at all 1390 | DEL_TAB = 1, //!< Use tab as delimiter 1391 | DEL_SPACE = 2, //!< Use space as delimiter 1392 | DEL_RETURN = 3, //!< Use return as delimiter 1393 | DEL_COLON = 4, //!< Use colon as delimiter 1394 | DEL_COMMA = 5, //!< Use comma as delimiter 1395 | DEL_LINEFEED = 6, //!< Use line feed as delimiter 1396 | DEL_CRLF = 7, //!< Use return+line feed as delimiter 1397 | 1398 | DELS 1399 | } 1400 | DEL; 1401 | 1402 | /*\endverbatim 1403 | * 1404 | * \n 1405 | */ 1406 | 1407 | 1408 | /*! \page transportlayers Hardware Transport Layer 1409 | 1410 | \verbatim */ 1411 | 1412 | typedef enum 1413 | { 1414 | HW_USB = 1, 1415 | HW_BT = 2, 1416 | HW_WIFI = 3, 1417 | 1418 | HWTYPES 1419 | } 1420 | HWTYPE; 1421 | 1422 | /* \endverbatim */ 1423 | 1424 | 1425 | /*! \page encryptions Encryption Types 1426 | 1427 | \verbatim */ 1428 | 1429 | typedef enum 1430 | { 1431 | ENCRYPT_NONE = 0, 1432 | ENCRYPT_WPA2 = 1, 1433 | 1434 | ENCRYPTS 1435 | } 1436 | ENCRYPT; 1437 | 1438 | /* \endverbatim */ 1439 | 1440 | 1441 | typedef enum 1442 | { 1443 | MODE_KEEP = -1, 1444 | TYPE_KEEP = 0, 1445 | 1446 | MIXS 1447 | } 1448 | MIX; 1449 | 1450 | 1451 | typedef enum 1452 | { 1453 | RED = 0, 1454 | GREEN = 1, 1455 | BLUE = 2, 1456 | BLANK = 3, 1457 | COLORS 1458 | } 1459 | COLOR; 1460 | 1461 | 1462 | /* Constants related to color sensor value using */ 1463 | /* Color sensor as color detector */ 1464 | typedef enum 1465 | { 1466 | BLACKCOLOR = 1, 1467 | BLUECOLOR = 2, 1468 | GREENCOLOR = 3, 1469 | YELLOWCOLOR = 4, 1470 | REDCOLOR = 5, 1471 | WHITECOLOR = 6 1472 | } 1473 | NXTCOLOR; 1474 | 1475 | 1476 | typedef enum 1477 | { 1478 | WARNING_TEMP = 0x01, 1479 | WARNING_CURRENT = 0x02, 1480 | WARNING_VOLTAGE = 0x04, 1481 | WARNING_MEMORY = 0x08, 1482 | WARNING_DSPSTAT = 0x10, 1483 | 1484 | WARNING_BATTLOW = 0x40, 1485 | WARNING_BUSY = 0x80, 1486 | 1487 | WARNINGS = 0x3F 1488 | } 1489 | WARNING; 1490 | 1491 | 1492 | #define DATA8_NAN ((DATA8)(-128)) 1493 | #define DATA16_NAN ((DATA16)(-32768)) 1494 | #define DATA32_NAN ((DATA32)(0x80000000)) 1495 | #define DATAF_NAN ((float)0 / (float)0) //(0x7FC00000) 1496 | 1497 | #define DATA8_MIN (-127) 1498 | #define DATA8_MAX (127) 1499 | #define DATA16_MIN (-32767) 1500 | #define DATA16_MAX (32767) 1501 | #define DATA32_MIN (-2147483647) 1502 | #define DATA32_MAX (2147483647) 1503 | #define DATAF_MIN (-2147483647) 1504 | #define DATAF_MAX (2147483647) 1505 | 1506 | 1507 | 1508 | 1509 | /*! \enum OBJSTAT 1510 | * 1511 | * Values used to describe an object's status 1512 | */ 1513 | typedef enum 1514 | { 1515 | RUNNING = 0x0010, //!< Object code is running 1516 | WAITING = 0x0020, //!< Object is waiting for final trigger 1517 | STOPPED = 0x0040, //!< Object is stopped or not triggered yet 1518 | HALTED = 0x0080, //!< Object is halted because a call is in progress 1519 | } 1520 | OBJSTAT; 1521 | 1522 | 1523 | /*! \page devicecommands 1524 | * 1525 | * Device commands used to control (UART sensors) devices 1526 | * \verbatim 1527 | */ 1528 | 1529 | typedef enum 1530 | { 1531 | DEVCMD_RESET = 0x11, //!< UART device reset 1532 | DEVCMD_FIRE = 0x11, //!< UART device fire (ultrasonic) 1533 | DEVCMD_CHANNEL = 0x12, //!< UART device channel (IR seeker) 1534 | 1535 | DEVCMDS 1536 | } 1537 | DEVCMD; 1538 | 1539 | /*\endverbatim 1540 | * 1541 | * \n 1542 | */ 1543 | 1544 | 1545 | // GRAPHICS 1546 | 1547 | #define vmPOP3_ABS_X 16 // 1548 | #define vmPOP3_ABS_Y 50 // 1549 | 1550 | #define vmPOP3_ABS_WARN_ICON_X 64 1551 | #define vmPOP3_ABS_WARN_ICON_X1 40 1552 | #define vmPOP3_ABS_WARN_ICON_X2 72 1553 | #define vmPOP3_ABS_WARN_ICON_X3 104 1554 | #define vmPOP3_ABS_WARN_ICON_Y 60 1555 | #define vmPOP3_ABS_WARN_SPEC_ICON_X 88 1556 | #define vmPOP3_ABS_WARN_SPEC_ICON_Y 60 1557 | #define vmPOP3_ABS_WARN_TEXT_X 80 1558 | #define vmPOP3_ABS_WARN_TEXT_Y 68 1559 | #define vmPOP3_ABS_WARN_YES_X 72 1560 | #define vmPOP3_ABS_WARN_YES_Y 90 1561 | #define vmPOP3_ABS_WARN_LINE_X 21 1562 | #define vmPOP3_ABS_WARN_LINE_Y 89 1563 | #define vmPOP3_ABS_WARN_LINE_ENDX 155 1564 | 1565 | 1566 | #define LONGToBytes(_x) (UBYTE)((_x) & 0xFF),(UBYTE)((_x >> 8) & 0xFF),(UBYTE)((_x >> 16) & 0xFF),(UBYTE)((_x >> 24) & 0xFF) 1567 | #define WORDToBytes(_x) (UBYTE)((_x) & 0xFF),(UBYTE)((_x >> 8) & 0xFF) 1568 | #define BYTEToBytes(_x) (UBYTE)((_x) & 0xFF) 1569 | 1570 | #define PROGRAMHeader(VersionInfo,NumberOfObjects,GlobalBytes)\ 1571 | 'L','E','G','O',LONGToBytes(0),WORDToBytes((UWORD)(BYTECODE_VERSION * 100.0)),WORDToBytes(NumberOfObjects),LONGToBytes(GlobalBytes) 1572 | 1573 | #define VMTHREADHeader(OffsetToInstructions,LocalBytes)\ 1574 | LONGToBytes(OffsetToInstructions),0,0,0,0,LONGToBytes(LocalBytes) 1575 | 1576 | #define SUBCALLHeader(OffsetToInstructions,LocalBytes)\ 1577 | LONGToBytes(OffsetToInstructions),0,0,1,0,LONGToBytes(LocalBytes) 1578 | 1579 | #define BLOCKHeader(OffsetToInstructions,OwnerObjectId,TriggerCount)\ 1580 | LONGToBytes(OffsetToInstructions),WORDToBytes(OwnerObjectId),WORDToBytes(TriggerCount),LONGToBytes(0) 1581 | 1582 | // MACROS FOR PRIMITIVES AND SYSTEM CALLS 1583 | 1584 | #define PRIMPAR_SHORT 0x00 1585 | #define PRIMPAR_LONG 0x80 1586 | 1587 | #define PRIMPAR_CONST 0x00 1588 | #define PRIMPAR_VARIABEL 0x40 1589 | #define PRIMPAR_LOCAL 0x00 1590 | #define PRIMPAR_GLOBAL 0x20 1591 | #define PRIMPAR_HANDLE 0x10 1592 | #define PRIMPAR_ADDR 0x08 1593 | 1594 | #define PRIMPAR_INDEX 0x1F 1595 | #define PRIMPAR_CONST_SIGN 0x20 1596 | #define PRIMPAR_VALUE 0x3F 1597 | 1598 | #define PRIMPAR_BYTES 0x07 1599 | 1600 | #define PRIMPAR_STRING_OLD 0 1601 | #define PRIMPAR_1_BYTE 1 1602 | #define PRIMPAR_2_BYTES 2 1603 | #define PRIMPAR_4_BYTES 3 1604 | #define PRIMPAR_STRING 4 1605 | 1606 | #define PRIMPAR_LABEL 0x20 1607 | 1608 | #define HND(x) PRIMPAR_HANDLE | x 1609 | #define ADR(x) PRIMPAR_ADDR | x 1610 | 1611 | #define LCS (PRIMPAR_LONG | PRIMPAR_STRING) 1612 | 1613 | #define LAB1(v) (PRIMPAR_LONG | PRIMPAR_LABEL),(v & 0xFF) 1614 | 1615 | #define LC0(v) ((v & PRIMPAR_VALUE) | PRIMPAR_SHORT | PRIMPAR_CONST) 1616 | #define LC1(v) (PRIMPAR_LONG | PRIMPAR_CONST | PRIMPAR_1_BYTE),(v & 0xFF) 1617 | #define LC2(v) (PRIMPAR_LONG | PRIMPAR_CONST | PRIMPAR_2_BYTES),(v & 0xFF),((v >> 8) & 0xFF) 1618 | #define LC4(v) (PRIMPAR_LONG | PRIMPAR_CONST | PRIMPAR_4_BYTES),((ULONG)v & 0xFF),(((ULONG)v >> (ULONG)8) & 0xFF),(((ULONG)v >> (ULONG)16) & 0xFF),(((ULONG)v >> (ULONG)24) & 0xFF) 1619 | #define LCA(h) (PRIMPAR_LONG | PRIMPAR_CONST | PRIMPAR_1_BYTE | PRIMPAR_ARRAY),(i & 0xFF) 1620 | 1621 | #define LV0(i) ((i & PRIMPAR_INDEX) | PRIMPAR_SHORT | PRIMPAR_VARIABEL | PRIMPAR_LOCAL) 1622 | #define LV1(i) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_LOCAL | PRIMPAR_1_BYTE),(i & 0xFF) 1623 | #define LV2(i) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_LOCAL | PRIMPAR_2_BYTES),(i & 0xFF),((i >> 8) & 0xFF) 1624 | #define LV4(i) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_LOCAL | PRIMPAR_4_BYTES),(i & 0xFF),((i >> 8) & 0xFF),((i >> 16) & 0xFF),((i >> 24) & 0xFF) 1625 | #define LVA(h) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_LOCAL | PRIMPAR_1_BYTE | PRIMPAR_ARRAY),(i & 0xFF) 1626 | 1627 | #define GV0(i) ((i & PRIMPAR_INDEX) | PRIMPAR_SHORT | PRIMPAR_VARIABEL | PRIMPAR_GLOBAL) 1628 | #define GV1(i) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_GLOBAL | PRIMPAR_1_BYTE),(i & 0xFF) 1629 | #define GV2(i) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_GLOBAL | PRIMPAR_2_BYTES),(i & 0xFF),((i >> 8) & 0xFF) 1630 | #define GV4(i) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_GLOBAL | PRIMPAR_4_BYTES),(i & 0xFF),((i >> 8) & 0xFF),((i >> 16) & 0xFF),((i >> 24) & 0xFF) 1631 | #define GVA(h) (PRIMPAR_LONG | PRIMPAR_VARIABEL | PRIMPAR_GLOBAL | PRIMPAR_1_BYTE | PRIMPAR_ARRAY),(i & 0xFF) 1632 | 1633 | // MACROS FOR SUB CALLS 1634 | 1635 | 1636 | #define CALLPAR_IN 0x80 1637 | #define CALLPAR_OUT 0x40 1638 | 1639 | #define CALLPAR_TYPE 0x07 1640 | #define CALLPAR_DATA8 DATA_8 1641 | #define CALLPAR_DATA16 DATA_16 1642 | #define CALLPAR_DATA32 DATA_32 1643 | #define CALLPAR_DATAF DATA_F 1644 | #define CALLPAR_STRING DATA_S 1645 | 1646 | #define IN_8 (CALLPAR_IN | CALLPAR_DATA8) 1647 | #define IN_16 (CALLPAR_IN | CALLPAR_DATA16) 1648 | #define IN_32 (CALLPAR_IN | CALLPAR_DATA32) 1649 | #define IN_F (CALLPAR_IN | CALLPAR_DATAF) 1650 | #define IN_S (CALLPAR_IN | CALLPAR_STRING) 1651 | #define OUT_8 (CALLPAR_OUT | CALLPAR_DATA8) 1652 | #define OUT_16 (CALLPAR_OUT | CALLPAR_DATA16) 1653 | #define OUT_32 (CALLPAR_OUT | CALLPAR_DATA32) 1654 | #define OUT_F (CALLPAR_OUT | CALLPAR_DATAF) 1655 | #define OUT_S (CALLPAR_OUT | CALLPAR_STRING) 1656 | 1657 | #define IO_8 IN_8 | OUT_8 1658 | #define IO_16 IN_16 | OUT_16 1659 | #define IO_32 IN_32 | OUT_32 1660 | #define IO_F IN_F | OUT_F 1661 | #define IO_S IN_S | OUT_S 1662 | 1663 | 1664 | #endif /* BYTECODES_H_ */ 1665 | -------------------------------------------------------------------------------- /src/lms2012.h: -------------------------------------------------------------------------------- 1 | /* 2 | * LEGO® MINDSTORMS EV3 3 | * 4 | * Copyright (C) 2010-2013 The LEGO Group 5 | * 6 | * This program is free software; you can redistribute it and/or modify 7 | * it under the terms of the GNU General Public License as published by 8 | * the Free Software Foundation; either version 2 of the License, or 9 | * (at your option) any later version. 10 | * 11 | * This program is distributed in the hope that it will be useful, 12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 14 | * GNU General Public License for more details. 15 | * 16 | * You should have received a copy of the GNU General Public License 17 | * along with this program; if not, write to the Free Software 18 | * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 19 | */ 20 | 21 | 22 | /*! \page debug Terminal Configuration 23 | * 24 | \verbatim 25 | 26 | 27 | TERMINAL CONFIGURATION (in top of "lms2012.h") 28 | 29 | Normal release: DEBUG not defined, TERMINAL_ENABLED = 0, DEBUG_UART = 4 30 | 31 | Printf working: DEBUG not defined, TERMINAL_ENABLED = 0, DEBUG_UART = 0 32 | 33 | Development with debug messages: DEBUG defined, TERMINAL_ENABLED = 1, DEBUG_UART = 0 34 | 35 | */ 36 | 37 | 38 | //#define DEBUG //!< When defined debug messages is output on standard I/O (d_uart is different) 39 | 40 | #define TERMINAL_ENABLED 0 //!< DEBUG terminal enabled (0 = disabled, 1 = enabled) 41 | #define DEBUG_UART 4 //!< UART used for debug (0 = port1, 1 = port2, ... 4 = none) 42 | 43 | 44 | /* \endverbatim */ 45 | 46 | //#define DEBUG_VM 47 | //#define DEBUG_TRACE_TASK 48 | //#define DEBUG_C_COM 49 | //#define DEBUG_C_INPUT 50 | //#define DEBUG_C_INPUT_DAISYCHAIN 51 | //#define DEBUG_C_INPUT_DATALOG 52 | //#define DEBUG_C_INPUT_FAST_DATALOG 53 | //#define DEBUG_C_MEMORY 54 | //#define DEBUG_C_MEMORY_LOG 55 | //#define DEBUG_C_MEMORY_FILE 56 | //#define DEBUG_C_MEMORY_LOW 57 | //#define DEBUG_C_SOUND 58 | //#define DEBUG_C_UI 59 | 60 | //#define DEBUG_D_ANALOG 61 | //#define DEBUG_D_POWER 62 | //#define DEBUG_D_UART 63 | //#define DEBUG_D_UART_ERROR 64 | //#define DEBUG_D_UI 65 | //#define DEBUG_D_SOUND 66 | //#define DEBUG_D_IIC 67 | //#define DEBUG_D_USBDEV 68 | 69 | //#define ENABLE_TEST_ON_PORT4 70 | 71 | //#define BUFPRINTSIZE 100000 72 | //#define REMEMBER_TO_ENABLE_SAVE_USER_DATA 73 | //#define REMEMBER_TO_FIX_TYPEDATA 74 | 75 | //#define DEBUG_TRACE_USB_COMMAND 76 | //#define DEBUG_TRACE_MODE_CHANGE 77 | //#define DEBUG_TRACE_KEY 78 | //#define DEBUG_TRACE_ANGLE 79 | //#define DEBUG_TRACE_US 80 | //#define DEBUG_TRACE_VM 81 | //#define DEBUG_TRACE_DAISYCHAIN 82 | //#define DEBUG_BYTECODE_TIME 83 | //#define DEBUG_TRACE_FREEZE 84 | //#define DEBUG_TRACE_FILENAME 85 | //#define DEBUG_SDCARD 86 | //#define DEBUG_USBSTICK 87 | //#define DEBUG_VIRTUAL_BATT_TEMP 88 | //#define DEBUG_TEMP_SHUTDOWN 89 | //#define DEBUG_BACK_BLOCKED 90 | #define DEBUG_RECHARGEABLE 91 | 92 | 93 | 94 | #ifndef LMS2012_H_ 95 | #define LMS2012_H_ 96 | 97 | // HARDWARE PLATFORM 98 | 99 | #define EP2 4 //!< Schematics revision D 100 | #define FINALB 3 //!< Schematics revision B and C 101 | #define FINAL 2 //!< Final prototype 102 | #define SIMULATION 0 //!< LEGO digital simulation 103 | 104 | #define PLATFORM_START FINAL //!< Oldest supported hardware (older versions will use this) 105 | #define PLATFORM_END EP2 //!< Newest supported hardware (newer versions will use this) 106 | 107 | // Will be removed when not used anymore 108 | #define A4 -1 109 | #define EVALBOARD -2 110 | #define ONE2ONE 1 //!< First real size prototype 111 | 112 | 113 | #ifdef LEGO_SIMULATION 114 | #define HARDWARE SIMULATION 115 | #else 116 | 117 | #ifndef HARDWARE 118 | #define HARDWARE FINAL //!< Actual hardware platform (must be one of above) 119 | #endif 120 | 121 | #endif 122 | 123 | // Support for module parameter "HwId" 124 | // 125 | // Readout File int PCB 126 | // 127 | // V1.00 10 10 MP (h = home, e = education) 128 | // V0.50 05 5 EP3 129 | // V0.40 04 4 EP2 130 | // V0.30 03 3 EP1 (FINALB) (DEFAULT if file "HwId" not found) 131 | // V0.20 02 2 FINAL 132 | 133 | #ifdef HW_ID_SUPPORT 134 | 135 | char *HwId = "03"; 136 | 137 | #define HWID (((HwId[0] - '0') * 10) + (HwId[1] - '0')) 138 | 139 | #endif 140 | 141 | 142 | // FIRMWARE VARIANTS 143 | 144 | //#define OLDCALL //!< Don't use optimised sub calls 145 | //#define DISABLE_PRU_UARTS //!< Don't use port 3 and 4 for UART sensors 146 | //#define DISABLE_OLD_COLOR //!< Don't support NXT color sensor 147 | //#define DISABLE_ADC //!< Don't use ADC (no clock EMC test) 148 | //#define ADC_BITBANGING //!< Don't use SPI for a/d converter 149 | //#define DISABLE_DAISYCHAIN 150 | //#define DISABLE_DAISYCHAIN_COM_CALL 151 | //#define DISABLE_FAST_DATALOG_BUFFER 152 | //#define DISABLE_BUMBED 153 | //#define LOG_ASCII 154 | //#define DISABLE_FIQ_IIC 155 | #define UART1_FAKE_INTERRUPT //!< Don't use real interrupt on UART1 (linux prompt) 156 | //#define DISABLE_LOW_VOLTAGE //!< Don't shut down on low voltage 157 | //#define ENABLE_HIGH_CURRENT //!< Don't shut down on high current 158 | //#define DISABLE_LOW_MEMORY //!< Don't check low memory 159 | //#define DISABLE_UART_DATA_ERROR //!< Don't reset UART sensor if timeout or crc error 160 | #define DISABLE_PREEMPTED_VM //!< Don't run VM as preempted 161 | //#define DISABLE_SDCARD_SUPPORT //!< Don't use SD card 162 | #define DISABLE_USBSTICK_SUPPORT //!< Don't use USB stick 163 | //#define ENABLE_PERFORMANCE_TEST //!< Show performance bar in the top line 164 | //#define ENABLE_LOAD_TEST //!< Show integrated current in the top line 165 | //#define ENABLE_MEMORY_TEST //!< Show used memory in the top line 166 | //#define ENABLE_STATUS_TEST 167 | //#define DISABLE_VIRTUAL_BATT_TEMP 168 | //#define DISABLE_SOUND 169 | //#define DISABLE_PAR_ALIGNMENT //!< Disable possibility to align sub call parameter types 170 | //#define DISABLE_NEW_CALL_MUTEX //!< Disable smart object switching after return from non reentrant sub call (enables blocked thread call) 171 | //#define DISABLE_SYSTEM_BYTECODE //!< Disable the use of opSYSTEM command 172 | //#define DISABLE_FILENAME_CHECK //!< Disable "c_memory" filename check 173 | //#define DISABLE_AD_WORD_PROTECT //!< Disable A/D word result protection 174 | 175 | #define TESTDEVICE 3 176 | 177 | #ifdef Linux_X86 178 | #define DISABLE_DAISYCHAIN 179 | #define DISABLE_DAISYCHAIN_COM_CALL 180 | #endif 181 | 182 | #ifndef PCASM 183 | #include 184 | #endif 185 | 186 | #include "lmstypes.h" 187 | #include "bytecodes.h" 188 | 189 | // Hardware 190 | 191 | #define OUTPUTS vmOUTPUTS //!< Number of output ports in the system 192 | #define INPUTS vmINPUTS //!< Number of input ports in the system 193 | #define BUTTONS vmBUTTONS //!< Number of buttons in the system 194 | #define LEDS vmLEDS //!< Number of LEDs in the system 195 | 196 | #define LCD_WIDTH vmLCD_WIDTH //!< LCD horizontal pixels 197 | #define LCD_HEIGHT vmLCD_HEIGHT //!< LCD vertical pixels 198 | #define TOPLINE_HEIGHT vmTOPLINE_HEIGHT //!< Top line vertical pixels 199 | #define LCD_STORE_LEVELS vmLCD_STORE_LEVELS //!< Store levels 200 | 201 | // Software 202 | 203 | #define FG_COLOR vmFG_COLOR //!< Foreground color 204 | #define BG_COLOR vmBG_COLOR //!< Background color 205 | 206 | #define CHAIN_DEPT vmCHAIN_DEPT //!< Number of bricks in the USB daisy chain (master + slaves) 207 | 208 | #define EVENT_BT_PIN vmEVENT_BT_PIN 209 | 210 | // Folders 211 | 212 | #define MEMORY_FOLDER vmMEMORY_FOLDER 213 | #define PROGRAM_FOLDER vmPROGRAM_FOLDER 214 | #define DATALOG_FOLDER vmDATALOG_FOLDER 215 | #define SDCARD_FOLDER vmSDCARD_FOLDER 216 | #define USBSTICK_FOLDER vmUSBSTICK_FOLDER 217 | 218 | // Files 219 | #define DETAILS_FILE vmDETAILS_FILE //!< File containing firmware version 220 | 221 | // Extensions 222 | 223 | #define EXT_SOUND vmEXT_SOUND //!< Rudolf sound file 224 | #define EXT_GRAPHICS vmEXT_GRAPHICS //!< Rudolf graphics file 225 | #define EXT_BYTECODE vmEXT_BYTECODE //!< Rudolf byte code file 226 | #define EXT_TEXT vmEXT_TEXT //!< Rudolf text file 227 | #define EXT_DATALOG vmEXT_DATALOG //!< Rudolf datalog file 228 | #define EXT_PROGRAM vmEXT_PROGRAM //!< Rudolf program byte code file 229 | #define EXT_CONFIG vmEXT_CONFIG //!< rudolf configuration file 230 | 231 | /*! \page system 232 | * 233 | * \verbatim 234 | */ 235 | 236 | #define PROJECT "LMS2012" 237 | #define VERS 1.04 238 | #define SPECIALVERS 'H' //!< Minor version (not shown if less than ASCII zero) 239 | 240 | 241 | #define MAX_PROGRAMS SLOTS //!< Max number of programs (including UI and direct commands) running at a time 242 | #define MAX_BREAKPOINTS 4 //!< Max number of breakpoints (opCODES depends on this value) 243 | #define MAX_LABELS 32 //!< Max number of labels per program 244 | #define MAX_DEVICE_TYPE 127 //!< Highest type number (positive) 245 | #define MAX_VALID_TYPE vmMAX_VALID_TYPE //!< Highest valid type 246 | #define MAX_DEVICE_MODES 8 //!< Max number of modes in one device 247 | #define MAX_DEVICE_DATASETS 8 //!< Max number of data sets in one device 248 | #define MAX_DEVICE_DATALENGTH 32 //!< Max device data length 249 | 250 | #define MAX_DEVICE_BUSY_TIME 1200 //!< Max number of mS a device can be busy when read 251 | 252 | #define MAX_DEVICE_TYPES ((MAX_DEVICE_TYPE + 1) * MAX_DEVICE_MODES)//!< Max number of different device types and modes (max type data list size) 253 | 254 | #define MAX_FRAMES_PER_SEC 10 //!< Max frames per second update in display 255 | 256 | #define CACHE_DEEPT 10 //!< Max number of programs cached (in RECENT FILES MENU) 257 | #define MAX_HANDLES 250 //!< Max number of handles to memory pools and arrays in one program 258 | 259 | #define MAX_ARRAY_SIZE 1000000000 //!< Max array size 260 | #define MIN_ARRAY_ELEMENTS 0 //!< Min elements in a DATA8 array 261 | 262 | #define INSTALLED_MEMORY 6000 //!< Flash allocated to hold user programs/data 263 | #define RESERVED_MEMORY 100 //!< Memory reserve for system [KB] 264 | #define LOW_MEMORY 500 //!< Low memory warning [KB] 265 | 266 | #define LOGBUFFER_SIZE 1000 //!< Min log buffer size 267 | #define DEVICE_LOGBUF_SIZE 300 //!< Device log buffer size (black layer buffer) 268 | #define MIN_LIVE_UPDATE_TIME 10 //!< [mS] Min sample time when live update 269 | 270 | #define MIN_IIC_REPEAT_TIME 10 //!< [mS] Min IIC device repeat time 271 | #define MAX_IIC_REPEAT_TIME 1000 //!< [mS] Max IIC device repeat time 272 | 273 | #define MAX_COMMAND_BYTECODES 64 //!< Max number of byte codes in a debug terminal direct command 274 | #define MAX_COMMAND_LOCALS 64 //!< Max number of bytes allocated for direct command local variables 275 | #define MAX_COMMAND_GLOBALS 1021 //!< Max number of bytes allocated for direct command global variables 276 | 277 | #define UI_PRIORITY 20 //!< UI byte codes before switching VM thread 278 | #define C_PRIORITY 200 //!< C call byte codes 279 | 280 | #ifndef DISABLE_PREEMPTED_VM 281 | #define PRG_PRIORITY 2000 //!< Prg byte codes before switching VM thread 282 | #else 283 | #define PRG_PRIORITY 200 //!< Prg byte codes before switching VM thread 284 | #endif 285 | 286 | #define BUTTON_DEBOUNCE_TIME 30 287 | #define BUTTON_START_REPEAT_TIME 400 288 | #define BUTTON_REPEAT_TIME 200 289 | 290 | #define LONG_PRESS_TIME 3000 //!< [mS] Time pressed before long press recognised 291 | 292 | #define ADC_REF 5000 //!< [mV] maximal value on ADC 293 | #define ADC_RES 4095 //!< [CNT] maximal count on ADC 294 | 295 | #define IN1_ID_HYSTERESIS 50 //!< [mV] half of the span one Id takes up on input connection 1 voltage 296 | #define OUT5_ID_HYSTERESIS 100 //!< [mV] half of the span one Id takes up on output connection 5 voltage 297 | 298 | #define DEVICE_UPDATE_TIME 1000000 //!< Min device (sensor) update time [nS] 299 | #define DELAY_TO_TYPEDATA 10000 //!< Time from daisy chain active to upload type data [mS] 300 | #define DAISYCHAIN_MODE_TIME 10 //!< Time for daisy chain change mode [mS] 301 | #define MAX_FILE_HANDLES 64 //!< Max number of down load file handles 302 | #define MIN_HANDLE 3 //!< Min file handle to close 303 | 304 | #define ID_LENGTH 7 //!< Id length (BT MAC id) (incl. zero terminator) 305 | #define NAME_LENGTH 12 //!< Name length (not including zero termination) 306 | 307 | #define ERROR_BUFFER_SIZE 8 //!< Number of errors in buffer 308 | 309 | #define PWM_DEVICE "lms_pwm" //!< PWM device name 310 | #define PWM_DEVICE_NAME "/dev/lms_pwm" //!< PWM device file name 311 | 312 | #define MOTOR_DEVICE "lms_motor" //!< TACHO device name 313 | #define MOTOR_DEVICE_NAME "/dev/lms_motor" //!< TACHO device file name 314 | 315 | #define ANALOG_DEVICE "lms_analog" //!< ANALOG device name 316 | #define ANALOG_DEVICE_NAME "/dev/lms_analog" //!< ANALOG device file name 317 | 318 | #define POWER_DEVICE "lms_power" //!< POWER device name 319 | #define POWER_DEVICE_NAME "/dev/lms_power" //!< POWER device file name 320 | 321 | #define DCM_DEVICE "lms_dcm" //!< DCM device name 322 | #define DCM_DEVICE_NAME "/dev/lms_dcm" //!< DCM device file name 323 | 324 | #define UI_DEVICE "lms_ui" //!< UI device name 325 | #define UI_DEVICE_NAME "/dev/lms_ui" //!< UI device file name 326 | 327 | #define LCD_DEVICE "lms_display" //!< DISPLAY device name 328 | //#define LCD_DEVICE_NAME "/dev/lms_display" //!< DISPLAY device file name 329 | #define LCD_DEVICE_NAME "/dev/fb0" //!< DISPLAY device file name 330 | 331 | #define UART_DEVICE "lms_uart" //!< UART device name 332 | #define UART_DEVICE_NAME "/dev/lms_uart" //!< UART device file name 333 | 334 | #define USBDEV_DEVICE "lms_usbdev" //!< USB device 335 | #define USBDEV_DEVICE_NAME "/dev/lms_usbdev" //!< USB device 336 | 337 | #define USBHOST_DEVICE "lms_usbhost" //!< USB host 338 | #define USBHOST_DEVICE_NAME "/dev/lms_usbhost" //!< USB host 339 | 340 | #define SOUND_DEVICE "lms_sound" //!< SOUND device name 341 | #define SOUND_DEVICE_NAME "/dev/lms_sound" //!< SOUND device 342 | 343 | #define IIC_DEVICE "lms_iic" //!< IIC device name 344 | #define IIC_DEVICE_NAME "/dev/lms_iic" //!< IIC device 345 | 346 | #define BT_DEVICE "lms_bt" //!< BT device name 347 | #define BT_DEVICE_NAME "/dev/lms_bt" //!< BT device 348 | 349 | #define UPDATE_DEVICE "lms_update" //!< UPDATE device name 350 | #define UPDATE_DEVICE_NAME "/dev/lms_update" //!< UPDATE device 351 | 352 | #define TEST_PIN_DEVICE "lms_tst_pin" //!< TEST pin device name 353 | #define TEST_PIN_DEVICE_NAME "/dev/lms_tst_pin" //!< TEST pin device file name 354 | 355 | #define TEST_UART_DEVICE "lms_tst_uart" //!< TEST UART device name 356 | #define TEST_UART_DEVICE_NAME "/dev/lms_tst_uart" //!< TEST UART device file name 357 | 358 | 359 | #define DIR_DEEPT vmDIR_DEEPT //!< Max directory items allocated 360 | 361 | // File 362 | 363 | //*********************************************************************************************************************** 364 | //! \todo Filename sizes should only use vmPATHSIZE, vmNAMESIZE, vmEXTSIZE and vmFILENAMESIZE 365 | 366 | #define FILENAMESIZE vmFILENAMESIZE //!< All inclusive (path, filename, extension and zero termination) 367 | #define FILENAME_SIZE 52 //!< User filename size without extension including zero 368 | #define FOLDERNAME_SIZE 10 //!< Folder name size relative to "lms2012" folder including zero 369 | #define SUBFOLDERNAME_SIZE FILENAME_SIZE //!< Sub folder name size without "/" including zero 370 | 371 | #define MAX_FILENAME_SIZE (FOLDERNAME_SIZE + SUBFOLDERNAME_SIZE + FILENAME_SIZE + 5) 372 | 373 | //*********************************************************************************************************************** 374 | 375 | #define TYPEDATE_FILE_NAME "typedata" //!< TypeData filename 376 | #define ICON_FILE_NAME "icon" //!< Icon image filename 377 | #define TEXT_FILE_NAME "text" //!< Text filename 378 | 379 | #define DEMO_FILE_NAME "../prjs/BrkProg_SAVE/Demo.rpf" 380 | 381 | // Memory 382 | 383 | 384 | 385 | 386 | 387 | // SD card 388 | 389 | #ifdef Linux_X86 390 | #define SDCARD_DEVICE1 "/dev/mmcblk0" 391 | #define SDCARD_DEVICE2 "/dev/mmcblk0p1" 392 | #else 393 | #define SDCARD_DEVICE1 "/dev/mmcblk0" 394 | #define SDCARD_DEVICE2 "/dev/mmcblk0p1" 395 | #endif 396 | 397 | #define SDCARD_MOUNT "./mount_sdcard" 398 | #define SDCARD_UNMOUNT "./unmount_sdcard" 399 | 400 | // USB stick 401 | 402 | #ifndef Linux_X86 403 | #define USBSTICK_DEVICE "/dev/sda" 404 | #else 405 | #define USBSTICK_DEVICE "/dev/sdf1" 406 | #endif 407 | 408 | #define USBSTICK_MOUNT "./mount_usbstick" 409 | #define USBSTICK_UNMOUNT "./unmount_usbstick" 410 | 411 | /* 412 | #define DEFAULT_PRJS_FOLDER "~/lms2012/prjs" //!< Project folder name without trailing "/" 413 | #define DEFAULT_APPS_FOLDER "~/lms2012/apps" //!< Applet folder name without trailing "/" 414 | #define DEFAULT_TOOLS_FOLDER "~/lms2012/tools" //!< Setting folder name without trailing "/" 415 | #define DEFAULT_SYS_FOLDER "~/lms2012/sys" //!< System folder name without trailing "/" 416 | #define DEFAULT_SETUP_FOLDER "~/lms2012/sys" //!< Setup folder name without trailing "/" 417 | #define DEFAULT_SD_FOLDER "~/lms2012/SD Card" //!< Sd card folder name without trailing "/" 418 | #define DEFAULT_USB_FOLDER "~/lms2012/USB Memory"//!< USB Memory folder name without trailing "/" 419 | */ 420 | 421 | #define DEFAULT_FOLDER "ui" //!< Folder containing the first small programs 422 | #define DEFAULT_UI "ui" //!< Default user interface 423 | 424 | #define DEFAULT_VOLUME vmDEFAULT_VOLUME 425 | #define DEFAULT_SLEEPMINUTES vmDEFAULT_SLEEPMINUTES 426 | 427 | #define COM_CMD_DEVICE_NAME USBDEV_DEVICE_NAME //!< USB HID command pipe device file name 428 | 429 | /*! \endverbatim 430 | * 431 | */ 432 | 433 | /*! \page powermanagement Power Management 434 | * 435 | * This section describes various constants used in the power management 436 | * 437 | * 438 | *\n 439 | *
440 | * Battery Indicator 441 | *\n 442 | *
443 | * \verbatim 444 | */ 445 | 446 | #define BATT_INDICATOR_HIGH 7500 //!< Battery indicator high [mV] 447 | #define BATT_INDICATOR_LOW 6200 //!< Battery indicator low [mV] 448 | 449 | #define ACCU_INDICATOR_HIGH 7500 //!< Rechargeable battery indicator high [mV] 450 | #define ACCU_INDICATOR_LOW 7100 //!< Rechargeable battery indicator low [mV] 451 | 452 | /*! \endverbatim 453 | * \subpage pmbattind 454 | *\n 455 | *
456 | * Low Voltage Shutdown 457 | *\n 458 | *
459 | * \verbatim 460 | */ 461 | 462 | #define LOW_VOLTAGE_SHUTDOWN_TIME 10000 //!< Time from shutdown lower limit to shutdown [mS] 463 | 464 | #define BATT_WARNING_HIGH 6.2 //!< Battery voltage warning upper limit [V] 465 | #define BATT_WARNING_LOW 5.5 //!< Battery voltage warning lower limit [V] 466 | #define BATT_SHUTDOWN_HIGH 5.5 //!< Battery voltage shutdown upper limit [V] 467 | #define BATT_SHUTDOWN_LOW 4.5 //!< Battery voltage shutdown lower limit [V] 468 | 469 | #define ACCU_WARNING_HIGH 7.1 //!< Rechargeable battery voltage warning upper limit [V] 470 | #define ACCU_WARNING_LOW 6.5 //!< Rechargeable battery voltage warning lower limit [V] 471 | #define ACCU_SHUTDOWN_HIGH 6.5 //!< Rechargeable battery voltage shutdown upper limit [V] 472 | #define ACCU_SHUTDOWN_LOW 6.0 //!< Rechargeable battery voltage shutdown lower limit [V] 473 | 474 | /*! \endverbatim 475 | * \subpage pmbattsd 476 | *\n 477 | */ 478 | #ifdef ENABLE_HIGH_CURRENT 479 | /*! \page powermanagement 480 | * 481 | *
482 | * High Load Shutdown 483 | *\n 484 | *
485 | * \verbatim 486 | */ 487 | 488 | #define LOAD_SHUTDOWN_FAIL 4.0 //!< Current limit for instantly shutdown [A] 489 | #define LOAD_SHUTDOWN_HIGH 3.0 //!< Current limit for integrated current shutdown [A*S] 490 | #define LOAD_BREAK_EVEN 1.75 //!< Current limit for integrated current break even [A*S] 491 | 492 | #define LOAD_SLOPE_UP 0.2 //!< Current slope when current is above break even [A/S] 493 | #define LOAD_SLOPE_DOWN 0.1 //!< Current slope when current is below break even [A/S] 494 | 495 | /*! \endverbatim 496 | * \subpage pmloadsd 497 | *\n 498 | */ 499 | #endif 500 | 501 | #ifndef DISABLE_VIRTUAL_BATT_TEMP 502 | /*! \page powermanagement 503 | * 504 | *
505 | * High Temperature Shutdown 506 | *\n 507 | *
508 | * \verbatim 509 | */ 510 | 511 | #define TEMP_SHUTDOWN_FAIL 45.0 //!< Temperature rise before fail shutdown [C] 512 | #define TEMP_SHUTDOWN_WARNING 40.0 //!< Temperature rise before warning [C] 513 | 514 | /*! \endverbatim 515 | * \subpage pmtempsd 516 | *\n 517 | */ 518 | #endif 519 | 520 | #define UPDATE_TIME1 2 //!< Update repeat time1 [mS] 521 | #define UPDATE_TIME2 10 //!< Update repeat time2 [mS] 522 | #define UPDATE_MEMORY 200 //!< Update memory size [mS] 523 | #define UPDATE_SDCARD 500 //!< Update sdcard size [mS] 524 | #define UPDATE_USBSTICK 500 //!< Update usbstick size [mS] 525 | 526 | 527 | // Per start of (polution) defines 528 | #define MAX_SOUND_DATA_SIZE 250 529 | #define SOUND_CHUNK 250 530 | #define SOUND_ADPCM_CHUNK 125 531 | #define SOUND_MASTER_CLOCK 132000000 532 | #define SOUND_TONE_MASTER_CLOCK 1031250 533 | #define SOUND_MIN_FRQ 250 534 | #define SOUND_MAX_FRQ 10000 535 | #define SOUND_MAX_LEVEL 8 536 | #define SOUND_FILE_BUFFER_SIZE SOUND_CHUNK + 2 // 12.8 mS @ 8KHz 537 | #define SOUND_BUFFER_COUNT 3 538 | #define SOUND_FILE_FORMAT_NORMAL 0x0100 // RSO-file 539 | #define SOUND_FILE_FORMAT_COMPRESSED 0x0101 // RSO-file compressed 540 | // Per end of defines 541 | 542 | 543 | /*! 544 | * 545 | * \n 546 | */ 547 | 548 | 549 | #define VtoC(V) ((UWORD)((V * ADC_RES) / ADC_REF)) 550 | #define CtoV(C) ((UWORD)((C * ADC_REF) / ADC_RES)) 551 | #define MtoV(M) ((UWORD)((M * ADC_REF * 100) / (ADC_RES * 52))) 552 | 553 | #define KB 1024 554 | 555 | enum 556 | { 557 | FALSE = 0, 558 | TRUE = 1, 559 | }; 560 | 561 | 562 | // Reserved device types 563 | typedef enum 564 | { 565 | // TYPE_KEEP = 0, //!< Type value that won't change type in byte codes 566 | TYPE_NXT_TOUCH = 1, //!< Device is NXT touch sensor 567 | TYPE_NXT_LIGHT = 2, //!< Device is NXT light sensor 568 | TYPE_NXT_SOUND = 3, //!< Device is NXT sound sensor 569 | TYPE_NXT_COLOR = 4, //!< Device is NXT color sensor 570 | 571 | TYPE_TACHO = 7, //!< Device is a tacho motor 572 | TYPE_MINITACHO = 8, //!< Device is a mini tacho motor 573 | TYPE_NEWTACHO = 9, //!< Device is a new tacho motor 574 | 575 | TYPE_THIRD_PARTY_START = 50, 576 | TYPE_THIRD_PARTY_END = 99, 577 | 578 | TYPE_IIC_UNKNOWN = 100, 579 | 580 | TYPE_NXT_TEST = 101, //!< Device is a NXT ADC test sensor 581 | 582 | TYPE_NXT_IIC = 123, //!< Device is NXT IIC sensor 583 | TYPE_TERMINAL = 124, //!< Port is connected to a terminal 584 | TYPE_UNKNOWN = 125, //!< Port not empty but type has not been determined 585 | TYPE_NONE = 126, //!< Port empty or not available 586 | TYPE_ERROR = 127, //!< Port not empty and type is invalid 587 | } 588 | TYPE; 589 | 590 | 591 | 592 | /*! \page connections Connections 593 | * 594 | * \anchor connectiontypes 595 | * 596 | * Following defines sets the input and output port connection type\n 597 | * 598 | * These connection types are evaluated in the DCM driver \ref DcmDriver "Device Detection Manager Driver" 599 | * 600 | * \verbatim 601 | */ 602 | 603 | typedef enum 604 | { 605 | CONN_UNKNOWN = 111, //!< Connection is fake (test) 606 | 607 | CONN_DAISYCHAIN = 117, //!< Connection is daisy chained 608 | CONN_NXT_COLOR = 118, //!< Connection type is NXT color sensor 609 | CONN_NXT_DUMB = 119, //!< Connection type is NXT analog sensor 610 | CONN_NXT_IIC = 120, //!< Connection type is NXT IIC sensor 611 | 612 | CONN_INPUT_DUMB = 121, //!< Connection type is LMS2012 input device with ID resistor 613 | CONN_INPUT_UART = 122, //!< Connection type is LMS2012 UART sensor 614 | 615 | CONN_OUTPUT_DUMB = 123, //!< Connection type is LMS2012 output device with ID resistor 616 | CONN_OUTPUT_INTELLIGENT = 124, //!< Connection type is LMS2012 output device with communication 617 | CONN_OUTPUT_TACHO = 125, //!< Connection type is LMS2012 tacho motor with series ID resistance 618 | 619 | CONN_NONE = 126, //!< Port empty or not available 620 | CONN_ERROR = 127, //!< Port not empty and type is invalid 621 | } 622 | CONN; 623 | 624 | /*\endverbatim 625 | * 626 | * \n 627 | */ 628 | 629 | 630 | 631 | /*! \page objectstatus Object Status 632 | * 633 | \verbatim 634 | 635 | Image load -> Initialize all objects 636 | 637 | 638 | Initialize -> if TriggerCount == 0 -> RUNNING (VMTHREAD) 639 | else -> STOPPED (waiting for 1. trigger) 640 | 641 | 1.Trigger -> Initialise -> WAITING 642 | 643 | Triggered -> Enqueue -> RUNNING 644 | 645 | Done -> Dequeue -> STOPPED 646 | 647 | 648 | Program start 649 | | 650 | v 651 | STOPPED -------> WAITING -------> RUNNING --------, 652 | ^ 1.trig/ n.trig/ done/ | 653 | | Reset+Enqueue Dequeue | 654 | | | 655 | '----------------------------------------------' 656 | 657 | \endverbatim 658 | */ 659 | 660 | 661 | /*! \enum DSPSTAT 662 | * 663 | * Dispatch status values 664 | */ 665 | typedef enum 666 | { 667 | NOBREAK = 0x0100, //!< Dispatcher running (looping) 668 | STOPBREAK = 0x0200, //!< Break because of program stop 669 | SLEEPBREAK = 0x0400, //!< Break because of sleeping 670 | INSTRBREAK = 0x0800, //!< Break because of opcode break 671 | BUSYBREAK = 0x1000, //!< Break because of waiting for completion 672 | PRGBREAK = 0x2000, //!< Break because of program break 673 | USERBREAK = 0x4000, //!< Break because of user decision 674 | FAILBREAK = 0x8000 //!< Break because of fail 675 | } 676 | DSPSTAT; 677 | 678 | typedef void (*PRIM)(void); //!< Prototype for all byte codes 679 | 680 | 681 | 682 | /*! \page memorylayout Memory Layout 683 | * 684 | * RAM layout 685 | * 686 | *- GlobalVariables (aligned) 687 | * 688 | *- ObjectPointerList (aligned) 689 | * 690 | *- OBJ (aligned) 691 | * - Ip (4 bytes) 692 | * - Status (2 bytes) 693 | * - TriggerCount/CallerId (2 bytes) 694 | * - Local (0..MAX Bytes)\n 695 | * 696 | */ 697 | 698 | /*! \struct OBJ 699 | * Object data is used to hold the variables used for an object (allocated at image load time) 700 | */ 701 | typedef struct // Object 702 | { 703 | IP Ip; //!< Object instruction pointer 704 | LP pLocal; //!< Local variable pointer 705 | #ifndef DISABLE_NEW_CALL_MUTEX 706 | UBYTE ObjStatus; //!< Object status 707 | UBYTE Blocked; 708 | #else 709 | UWORD ObjStatus; //!< Object status 710 | #endif 711 | union //!< Different meaning for SUBCALL and BLOCKS 712 | { 713 | OBJID CallerId; //!< Caller id used for SUBCALL to save object id to return to 714 | TRIGGER TriggerCount; //!< Trigger count used by BLOCK's trigger logic 715 | }u; 716 | VARDATA Local[]; //!< Poll of bytes used for local variables 717 | } 718 | OBJ; 719 | 720 | 721 | /*! \struct BRKP 722 | * Breakpoint data hold information used for breakpoint 723 | */ 724 | typedef struct 725 | { 726 | IMINDEX Addr; //!< Offset to breakpoint address from image start 727 | OP OpCode; //!< Saved substituted opcode 728 | } 729 | BRKP; 730 | 731 | /*! \struct PRG 732 | * Program data hold information about a program 733 | */ 734 | typedef struct 735 | { 736 | ULONG InstrCnt; //!< Instruction counter used for performance analyses 737 | ULONG InstrTime; //!< Instruction time used for performance analyses 738 | 739 | ULONG StartTime; //!< Program start time [mS] 740 | ULONG RunTime; //!< Program run time [uS] 741 | 742 | IP pImage; //!< Pointer to start of image 743 | GP pData; //!< Pointer to start of data 744 | GP pGlobal; //!< Pointer to start of global bytes 745 | OBJHEAD* pObjHead; //!< Pointer to start of object headers 746 | OBJ** pObjList; //!< Pointer to object pointer list 747 | IP ObjectIp; //!< Working object Ip 748 | LP ObjectLocal; //!< Working object locals 749 | 750 | OBJID Objects; //!< No of objects in image 751 | OBJID ObjectId; //!< Active object id 752 | 753 | OBJSTAT Status; //!< Program status 754 | OBJSTAT StatusChange; //!< Program status change 755 | RESULT Result; //!< Program result (OK, BUSY, FAIL) 756 | 757 | BRKP Brkp[MAX_BREAKPOINTS]; //!< Storage for breakpoint logic 758 | 759 | LABEL Label[MAX_LABELS]; //!< Storage for labels 760 | UWORD Debug; //!< Debug flag 761 | 762 | DATA8 Name[FILENAME_SIZE]; 763 | 764 | } 765 | PRG; 766 | 767 | 768 | #define TYPE_NAME_LENGTH 11 769 | #define SYMBOL_LENGTH 4 //!< Symbol leng th (not including zero) 770 | 771 | /*! \struct TYPES 772 | * Device type data 773 | */ 774 | typedef struct // if data type changes - remember to change "cInputTypeDataInit" ! 775 | { 776 | SBYTE Name[TYPE_NAME_LENGTH + 1]; //!< Device name 777 | DATA8 Type; //!< Device type 778 | DATA8 Connection; 779 | DATA8 Mode; //!< Device mode 780 | DATA8 DataSets; 781 | DATA8 Format; 782 | DATA8 Figures; 783 | DATA8 Decimals; 784 | DATA8 Views; 785 | DATAF RawMin; //!< Raw minimum value (e.c. 0.0) 786 | DATAF RawMax; //!< Raw maximum value (e.c. 1023.0) 787 | DATAF PctMin; //!< Percent minimum value (e.c. -100.0) 788 | DATAF PctMax; //!< Percent maximum value (e.c. 100.0) 789 | DATAF SiMin; //!< SI unit minimum value (e.c. -100.0) 790 | DATAF SiMax; //!< SI unit maximum value (e.c. 100.0) 791 | UWORD InvalidTime; //!< mS from type change to valid data 792 | UWORD IdValue; //!< Device id value (e.c. 0 ~ UART) 793 | DATA8 Pins; //!< Device pin setup 794 | SBYTE Symbol[SYMBOL_LENGTH + 1]; //!< SI unit symbol 795 | UWORD Align; 796 | } 797 | TYPES; 798 | 799 | #define TYPE_PARAMETERS 19 //!< Number of members in the structure above 800 | #define MAX_DEVICE_INFOLENGTH 54 //!< Number of bytes in the structure above (can not be changed) 801 | 802 | 803 | /*!\enum ERR 804 | * 805 | * Describes error numbers 806 | */ 807 | typedef enum 808 | { 809 | TOO_MANY_ERRORS_TO_BUFFER, 810 | TYPEDATA_TABEL_FULL, 811 | TYPEDATA_FILE_NOT_FOUND, 812 | ANALOG_DEVICE_FILE_NOT_FOUND, 813 | ANALOG_SHARED_MEMORY, 814 | UART_DEVICE_FILE_NOT_FOUND, 815 | UART_SHARED_MEMORY, 816 | IIC_DEVICE_FILE_NOT_FOUND, 817 | IIC_SHARED_MEMORY, 818 | DISPLAY_SHARED_MEMORY, 819 | UI_SHARED_MEMORY, 820 | UI_DEVICE_FILE_NOT_FOUND, 821 | LCD_DEVICE_FILE_NOT_FOUND, 822 | OUTPUT_SHARED_MEMORY, 823 | COM_COULD_NOT_OPEN_FILE, 824 | COM_NAME_TOO_SHORT, 825 | COM_NAME_TOO_LONG, 826 | COM_INTERNAL, 827 | VM_INTERNAL, 828 | VM_PROGRAM_VALIDATION, 829 | VM_PROGRAM_NOT_STARTED, 830 | VM_PROGRAM_FAIL_BREAK, 831 | VM_PROGRAM_INSTRUCTION_BREAK, 832 | VM_PROGRAM_NOT_FOUND, 833 | SOUND_DEVICE_FILE_NOT_FOUND, 834 | SOUND_SHARED_MEMORY, 835 | FILE_OPEN_ERROR, 836 | FILE_READ_ERROR, 837 | FILE_WRITE_ERROR, 838 | FILE_CLOSE_ERROR, 839 | FILE_GET_HANDLE_ERROR, 840 | FILE_NAME_ERROR, 841 | USB_SHARED_MEMORY, 842 | OUT_OF_MEMORY, 843 | ERRORS 844 | } 845 | ERR; 846 | 847 | // INTERFACE FOR SHARED LIBRARIES 848 | 849 | extern void PrimParAdvance(void); // Dummy get parameter 850 | 851 | extern void* PrimParPointer(void); // Get pointer to primitives and system calls parameters 852 | 853 | extern IP GetImageStart(void); // Get pointer to start of image 854 | 855 | extern void SetDispatchStatus(DSPSTAT Status); // Set dispatch status (result from executing byte code) 856 | 857 | extern void SetInstructions(ULONG Instructions); // Set number of instructions before VMThread change 858 | 859 | extern PRGID CurrentProgramId(void); // Get current program id 860 | 861 | extern OBJSTAT ProgramStatus(PRGID PrgId); // Get program status 862 | 863 | extern OBJSTAT ProgramStatusChange(PRGID PrgId); // Get program status change 864 | 865 | extern void ProgramEnd(PRGID PrgId); 866 | 867 | extern OBJID CallingObjectId(void); // Get calling objects id 868 | 869 | extern void AdjustObjectIp(IMOFFS Value); // Adjust IP 870 | 871 | extern IP GetObjectIp(void); // Get IP 872 | 873 | extern void SetObjectIp(IP Ip); // Set IP 874 | 875 | extern ULONG GetTimeUS(void); // Get uS 876 | 877 | extern ULONG GetTimeMS(void); // Get mS 878 | 879 | extern ULONG GetTime(void); // Get actual program time 880 | 881 | extern ULONG CurrentObjectIp(void); // Get current object ip 882 | 883 | extern void VmPrint(char *pString); // print string 884 | 885 | extern void SetTerminalEnable(DATA8 Value); // Terminal enable/disable 886 | 887 | extern DATA8 GetTerminalEnable(void); // Get terminal enable state 888 | 889 | extern void GetResourcePath(char *pString,DATA8 MaxLength);// Get resource path 890 | 891 | extern void* VmMemoryResize(HANDLER Handle,DATA32 Elements); 892 | 893 | extern void SetVolumePercent(DATA8 Volume); 894 | 895 | extern DATA8 GetVolumePercent(void); 896 | 897 | extern void SetSleepMinutes(DATA8 Minutes); 898 | 899 | extern DATA8 GetSleepMinutes(void); 900 | 901 | extern DSPSTAT ExecuteByteCode(IP pByteCode,GP pGlobals,LP pLocals); // Execute byte code stream (C-call) 902 | 903 | extern DATA8 CheckSdcard(DATA8 *pChanged,DATA32 *pTotal,DATA32 *pFree,DATA8 Force); 904 | 905 | extern DATA8 CheckUsbstick(DATA8 *pChanged,DATA32 *pTotal,DATA32 *pFree,DATA8 Force); 906 | 907 | extern void SetUiUpdate(void); 908 | 909 | extern RESULT ValidateChar(DATA8 *pChar,DATA8 Set); 910 | 911 | extern RESULT ValidateString(DATA8 *pString,DATA8 Set); 912 | 913 | extern ERR LogErrorGet(void); 914 | 915 | #ifdef BUFPRINTSIZE 916 | extern void BufPrint(char Cmd,char *pFormat, ...); 917 | #endif 918 | 919 | 920 | 921 | #define ERR_STRING_SIZE vmERR_STRING_SIZE // Inclusive zero termination 922 | 923 | extern void LogErrorNumber(ERR Error); // Log error number 924 | extern DATA8 LogErrorNumberExists(ERR Error); 925 | 926 | 927 | #ifndef DISABLE_OLD_COLOR 928 | 929 | #define COLORS 4 930 | #define CALPOINTS 3 931 | 932 | 933 | /*! \page NxtColorMemory 934 | * 935 | * Shared Memory 936 | * 937 | *
938 | * 939 | * 940 | * \verbatim 941 | */ 942 | 943 | typedef struct 944 | { 945 | ULONG Calibration[CALPOINTS][COLORS]; 946 | UWORD CalLimits[CALPOINTS - 1]; 947 | UWORD Crc; 948 | UWORD ADRaw[COLORS]; 949 | UWORD SensorRaw[COLORS]; 950 | } 951 | COLORSTRUCT; 952 | 953 | /*\endverbatim 954 | * 955 | * \n 956 | */ 957 | 958 | #endif 959 | 960 | 961 | // INTERFACE BETWEEN SHARED LIBRARIES AND MODULES 962 | 963 | /*! \page AnalogModuleMemory 964 | * Shared Memory 965 | * 966 | *
967 | * 968 | * It is possible to get a pointer to the raw analogue values for use in userspace 969 | * this pointer will point to a struct and the layout is following: 970 | * 971 | * \verbatim 972 | */ 973 | 974 | typedef struct 975 | { 976 | DATA16 InPin1[INPUTS]; //!< Analog value at input port connection 1 977 | DATA16 InPin6[INPUTS]; //!< Analog value at input port connection 6 978 | DATA16 OutPin5[OUTPUTS]; //!< Analog value at output port connection 5 979 | DATA16 BatteryTemp; //!< Battery temperature 980 | DATA16 MotorCurrent; //!< Current flowing to motors 981 | DATA16 BatteryCurrent; //!< Current flowing from the battery 982 | DATA16 Cell123456; //!< Voltage at battery cell 1, 2, 3,4, 5, and 6 983 | #ifndef DISABLE_FAST_DATALOG_BUFFER 984 | DATA16 Pin1[INPUTS][DEVICE_LOGBUF_SIZE]; //!< Raw value from analog device 985 | DATA16 Pin6[INPUTS][DEVICE_LOGBUF_SIZE]; //!< Raw value from analog device 986 | UWORD Actual[INPUTS]; 987 | UWORD LogIn[INPUTS]; 988 | UWORD LogOut[INPUTS]; 989 | #endif 990 | #ifndef DISABLE_OLD_COLOR 991 | COLORSTRUCT NxtCol[INPUTS]; 992 | #endif 993 | DATA16 OutPin5Low[OUTPUTS]; //!< Analog value at output port connection 5 when connection 6 is low 994 | 995 | DATA8 Updated[INPUTS]; 996 | 997 | DATA8 InDcm[INPUTS]; //!< Input port device types 998 | DATA8 InConn[INPUTS]; 999 | 1000 | DATA8 OutDcm[OUTPUTS]; //!< Output port device types 1001 | DATA8 OutConn[OUTPUTS]; 1002 | #ifndef DISABLE_PREEMPTED_VM 1003 | UWORD PreemptMilliSeconds; 1004 | #endif 1005 | } 1006 | ANALOG; 1007 | 1008 | /*\endverbatim 1009 | * 1010 | * \n 1011 | */ 1012 | 1013 | 1014 | /*! \page UartModuleMemory 1015 | * 1016 | * Shared Memory 1017 | * 1018 | *
1019 | * 1020 | * It is possible to get a pointer to the uart values for use in userspace 1021 | * this pointer will point to a struct and the layout is following: 1022 | * 1023 | * \verbatim 1024 | */ 1025 | 1026 | #define UART_DATA_LENGTH MAX_DEVICE_DATALENGTH 1027 | #define UART_BUFFER_SIZE 64 1028 | 1029 | typedef struct 1030 | { 1031 | TYPES TypeData[INPUTS][MAX_DEVICE_MODES]; //!< TypeData 1032 | 1033 | #ifndef DISABLE_FAST_DATALOG_BUFFER 1034 | UWORD Repeat[INPUTS][DEVICE_LOGBUF_SIZE]; 1035 | DATA8 Raw[INPUTS][DEVICE_LOGBUF_SIZE][UART_DATA_LENGTH]; //!< Raw value from UART device 1036 | UWORD Actual[INPUTS]; 1037 | UWORD LogIn[INPUTS]; 1038 | #else 1039 | DATA8 Raw[INPUTS][UART_DATA_LENGTH]; //!< Raw value from UART device 1040 | #endif 1041 | DATA8 Status[INPUTS]; //!< Status 1042 | DATA8 Output[INPUTS][UART_DATA_LENGTH]; //!< Bytes to UART device 1043 | DATA8 OutputLength[INPUTS]; 1044 | } 1045 | UART; 1046 | 1047 | /*\endverbatim 1048 | * 1049 | * \n 1050 | */ 1051 | 1052 | 1053 | #define UART_PORT_CHANGED 0x01 //!< Input port changed 1054 | #define UART_DATA_READY 0x08 //!< Data is ready 1055 | #define UART_WRITE_REQUEST 0x10 //!< Write request 1056 | 1057 | 1058 | typedef struct 1059 | { 1060 | DATA8 Connection[INPUTS]; 1061 | DATA8 Type[INPUTS]; 1062 | DATA8 Mode[INPUTS]; 1063 | } 1064 | DEVCON; 1065 | 1066 | 1067 | typedef struct 1068 | { 1069 | TYPES TypeData; 1070 | DATA8 Port; 1071 | DATA8 Mode; 1072 | } 1073 | UARTCTL; 1074 | 1075 | #define UART_SET_CONN _IOWR('u',0,DEVCON) 1076 | #define UART_READ_MODE_INFO _IOWR('u',1,UARTCTL) 1077 | #define UART_NACK_MODE_INFO _IOWR('u',2,UARTCTL) 1078 | #define UART_CLEAR_CHANGED _IOWR('u',3,UARTCTL) 1079 | 1080 | 1081 | /*! \page IicModuleMemory 1082 | * 1083 | * Shared Memory 1084 | * 1085 | *
1086 | * 1087 | * It is possible to get a pointer to the iic values for use in userspace 1088 | * this pointer will point to a struct and the layout is following: 1089 | * 1090 | * \verbatim 1091 | */ 1092 | 1093 | #define IIC_DATA_LENGTH MAX_DEVICE_DATALENGTH 1094 | #define IIC_NAME_LENGTH 8 1095 | 1096 | typedef struct 1097 | { 1098 | TYPES TypeData[INPUTS][MAX_DEVICE_MODES]; //!< TypeData 1099 | 1100 | #ifndef DISABLE_FAST_DATALOG_BUFFER 1101 | UWORD Repeat[INPUTS][DEVICE_LOGBUF_SIZE]; 1102 | DATA8 Raw[INPUTS][DEVICE_LOGBUF_SIZE][IIC_DATA_LENGTH]; //!< Raw value from IIC device 1103 | UWORD Actual[INPUTS]; 1104 | UWORD LogIn[INPUTS]; 1105 | #else 1106 | DATA8 Raw[INPUTS][IIC_DATA_LENGTH]; //!< Raw value from IIC device 1107 | #endif 1108 | DATA8 Status[INPUTS]; //!< Status 1109 | DATA8 Changed[INPUTS]; 1110 | DATA8 Output[INPUTS][IIC_DATA_LENGTH]; //!< Bytes to IIC device 1111 | DATA8 OutputLength[INPUTS]; 1112 | } 1113 | IIC; 1114 | 1115 | /*\endverbatim 1116 | * 1117 | * \n 1118 | */ 1119 | 1120 | 1121 | #define IIC_PORT_CHANGED 0x01 //!< Input port changed 1122 | #define IIC_DATA_READY 0x08 //!< Data is ready 1123 | #define IIC_WRITE_REQUEST 0x10 //!< Write request 1124 | 1125 | 1126 | typedef struct 1127 | { 1128 | TYPES TypeData; 1129 | DATA8 Port; 1130 | DATA8 Mode; 1131 | } 1132 | IICCTL; 1133 | 1134 | 1135 | typedef struct 1136 | { 1137 | RESULT Result; 1138 | DATA8 Port; 1139 | DATA8 Repeat; 1140 | DATA16 Time; 1141 | DATA8 WrLng; 1142 | DATA8 WrData[IIC_DATA_LENGTH]; 1143 | DATA8 RdLng; 1144 | DATA8 RdData[IIC_DATA_LENGTH]; 1145 | } 1146 | IICDAT; 1147 | 1148 | 1149 | typedef struct 1150 | { 1151 | DATA8 Port; 1152 | DATA16 Time; 1153 | DATA8 Type; 1154 | DATA8 Mode; 1155 | DATA8 Manufacturer[IIC_NAME_LENGTH + 1]; 1156 | DATA8 SensorType[IIC_NAME_LENGTH + 1]; 1157 | DATA8 SetupLng; 1158 | ULONG SetupString; 1159 | DATA8 PollLng; 1160 | ULONG PollString; 1161 | DATA8 ReadLng; 1162 | } 1163 | IICSTR; 1164 | 1165 | 1166 | #define IIC_SET_CONN _IOWR('i',2,DEVCON) 1167 | #define IIC_READ_TYPE_INFO _IOWR('i',3,IICCTL) 1168 | #define IIC_SETUP _IOWR('i',5,IICDAT) 1169 | #define IIC_SET _IOWR('i',6,IICSTR) 1170 | 1171 | 1172 | 1173 | 1174 | #define TST_PIN_LENGTH 8 1175 | 1176 | typedef struct 1177 | { 1178 | DATA8 Port; 1179 | DATA8 Length; 1180 | DATA8 String[TST_PIN_LENGTH + 1]; 1181 | } 1182 | TSTPIN; 1183 | 1184 | #define TST_PIN_ON _IOWR('t',1,TSTPIN) 1185 | #define TST_PIN_OFF _IOWR('t',2,TSTPIN) 1186 | #define TST_PIN_READ _IOWR('t',3,TSTPIN) 1187 | #define TST_PIN_WRITE _IOWR('t',4,TSTPIN) 1188 | 1189 | 1190 | 1191 | 1192 | #define TST_UART_LENGTH UART_BUFFER_SIZE 1193 | 1194 | typedef struct 1195 | { 1196 | DATA32 Bitrate; 1197 | DATA8 Port; 1198 | DATA8 Length; 1199 | DATA8 String[TST_UART_LENGTH]; 1200 | } 1201 | TSTUART; 1202 | 1203 | #define TST_UART_ON _IOWR('t',5,TSTUART) 1204 | #define TST_UART_OFF _IOWR('t',6,TSTUART) 1205 | #define TST_UART_EN _IOWR('t',7,TSTUART) 1206 | #define TST_UART_DIS _IOWR('t',8,TSTUART) 1207 | #define TST_UART_READ _IOWR('t',9,TSTUART) 1208 | #define TST_UART_WRITE _IOWR('t',10,TSTUART) 1209 | 1210 | 1211 | 1212 | 1213 | /*! \page UiModuleMemory 1214 | * 1215 | * Shared Memory 1216 | * 1217 | *
1218 | * 1219 | * It is possible to get a pointer to the ui button states for use in userspace 1220 | * this pointer will point to a struct and the layout is following: 1221 | * 1222 | * \verbatim 1223 | */ 1224 | 1225 | typedef struct 1226 | { 1227 | DATA8 Pressed[BUTTONS]; //!< Pressed status 1228 | } 1229 | UI; 1230 | 1231 | /*\endverbatim 1232 | * 1233 | * \n 1234 | */ 1235 | 1236 | 1237 | #define LCD_BUFFER_SIZE (((LCD_WIDTH + 7) / 8) * LCD_HEIGHT) 1238 | #define LCD_TOPLINE_SIZE (((LCD_WIDTH + 7) / 8) * (TOPLINE_HEIGHT + 1)) 1239 | 1240 | 1241 | /*! \page DisplayModuleMemory 1242 | * 1243 | * Shared Memory 1244 | * 1245 | *
1246 | * 1247 | * It is possible to get a pointer to the display memory for use in userspace 1248 | * this pointer will point to a frame buffer as follows: 1249 | * 1250 | * \verbatim 1251 | */ 1252 | 1253 | typedef struct 1254 | { 1255 | UBYTE Lcd[LCD_BUFFER_SIZE]; 1256 | } 1257 | LCD; 1258 | 1259 | /*\endverbatim 1260 | * 1261 | * \n 1262 | */ 1263 | 1264 | 1265 | /*! \page SoundModuleMemory 1266 | * 1267 | * Shared Memory 1268 | * 1269 | *
1270 | * 1271 | * It is possible to get a pointer to the sound ready flag for use in userspace 1272 | * this pointer will point to a struct and the layout is following: 1273 | * 1274 | * \verbatim 1275 | */ 1276 | 1277 | typedef struct 1278 | { 1279 | DATA8 Status; //!< Status 1280 | } 1281 | SOUND; 1282 | 1283 | /*\endverbatim 1284 | * 1285 | * \n 1286 | */ 1287 | 1288 | 1289 | /*! \page UsbModuleMemory 1290 | * 1291 | * Shared Memory 1292 | * 1293 | *
1294 | * 1295 | * It is possible to get a pointer to the USB Speed (FULL or HIGH) for use in userspace 1296 | * this pointer will point to a struct and the layout is following: 1297 | * 1298 | * \verbatim 1299 | */ 1300 | 1301 | enum { 1302 | FULL_SPEED, 1303 | HIGH_SPEED 1304 | }; 1305 | 1306 | typedef struct 1307 | { 1308 | DATA8 Speed; 1309 | } 1310 | USB_SPEED; 1311 | 1312 | /*\endverbatim 1313 | * 1314 | * \n 1315 | */ 1316 | 1317 | /*! \page VmNonvolatileMemory 1318 | * 1319 | * VM non volatile Memory 1320 | * 1321 | *
1322 | * 1323 | * This struct will be loaded at start up and save when closing down VM 1324 | * 1325 | * \verbatim 1326 | */ 1327 | 1328 | typedef struct 1329 | { 1330 | DATA8 VolumePercent; //!< System default volume [0..100%] 1331 | DATA8 SleepMinutes; //!< System sleep [0..120min] (0 = ~) 1332 | } 1333 | NONVOL; 1334 | 1335 | /*\endverbatim 1336 | * 1337 | * \n 1338 | */ 1339 | 1340 | 1341 | /* 1342 | * Motor/OUTPUT Typedef 1343 | */ 1344 | typedef struct 1345 | { 1346 | SLONG TachoCounts; 1347 | SBYTE Speed; 1348 | SLONG TachoSensor; 1349 | }MOTORDATA; 1350 | 1351 | typedef struct 1352 | { 1353 | DATA8 Cmd; 1354 | DATA8 Nos; 1355 | DATA8 Power; 1356 | DATA32 Step1; 1357 | DATA32 Step2; 1358 | DATA32 Step3; 1359 | DATA8 Brake; 1360 | } STEPPOWER; 1361 | 1362 | typedef struct 1363 | { 1364 | DATA8 Cmd; 1365 | DATA8 Nos; 1366 | DATA8 Power; 1367 | DATA32 Time1; 1368 | DATA32 Time2; 1369 | DATA32 Time3; 1370 | DATA8 Brake; 1371 | } TIMEPOWER; 1372 | 1373 | typedef struct 1374 | { 1375 | DATA8 Cmd; 1376 | DATA8 Nos; 1377 | DATA8 Speed; 1378 | DATA32 Step1; 1379 | DATA32 Step2; 1380 | DATA32 Step3; 1381 | DATA8 Brake; 1382 | } STEPSPEED; 1383 | 1384 | typedef struct 1385 | { 1386 | DATA8 Cmd; 1387 | DATA8 Nos; 1388 | DATA8 Speed; 1389 | DATA32 Time1; 1390 | DATA32 Time2; 1391 | DATA32 Time3; 1392 | DATA8 Brake; 1393 | } TIMESPEED; 1394 | 1395 | typedef struct 1396 | { 1397 | DATA8 Cmd; 1398 | DATA8 Nos; 1399 | DATA8 Speed; 1400 | DATA16 Turn; 1401 | DATA32 Step; 1402 | DATA8 Brake; 1403 | } STEPSYNC; 1404 | 1405 | typedef struct 1406 | { 1407 | DATA8 Cmd; 1408 | DATA8 Nos; 1409 | DATA8 Speed; 1410 | DATA16 Turn; 1411 | DATA32 Time; 1412 | DATA8 Brake; 1413 | } TIMESYNC; 1414 | /* 1415 | * End of Motor/OUTPUT Typedef 1416 | */ 1417 | 1418 | 1419 | #define PRINTBUFFERSIZE 160 1420 | 1421 | typedef struct 1422 | { 1423 | NONVOL NonVol; 1424 | DATA8 FirstProgram[MAX_FILENAME_SIZE]; 1425 | 1426 | char PrintBuffer[PRINTBUFFERSIZE + 1]; 1427 | DATA8 TerminalEnabled; 1428 | 1429 | PRGID FavouritePrg; 1430 | PRGID ProgramId; //!< Program id running 1431 | PRG Program[MAX_PROGRAMS]; //!< Program[0] is the UI byte codes running 1432 | 1433 | 1434 | ULONG InstrCnt; //!< Instruction counter (performance test) 1435 | IP pImage; //!< Pointer to start of image 1436 | GP pGlobal; //!< Pointer to start of global bytes 1437 | OBJHEAD* pObjHead; //!< Pointer to start of object headers 1438 | OBJ** pObjList; //!< Pointer to object pointer list 1439 | 1440 | IP ObjectIp; //!< Working object Ip 1441 | LP ObjectLocal; //!< Working object locals 1442 | OBJID Objects; //!< No of objects in image 1443 | OBJID ObjectId; //!< Active object id 1444 | 1445 | IP ObjIpSave; 1446 | GP ObjGlobalSave; 1447 | LP ObjLocalSave; 1448 | DSPSTAT DispatchStatusSave; 1449 | ULONG PrioritySave; 1450 | 1451 | long TimerDataSec; 1452 | long TimerDatanSec; 1453 | 1454 | UWORD Debug; 1455 | 1456 | UWORD Test; 1457 | 1458 | UWORD RefCount; 1459 | 1460 | ULONG TimeuS; 1461 | 1462 | ULONG OldTime1; 1463 | ULONG OldTime2; 1464 | ULONG NewTime; 1465 | #ifdef ENABLE_PERFORMANCE_TEST 1466 | ULONG PerformTimer; 1467 | DATAF PerformTime; 1468 | #endif 1469 | 1470 | DSPSTAT DispatchStatus; //!< Dispatch status 1471 | ULONG Priority; //!< Object priority 1472 | 1473 | ULONG Value; 1474 | HANDLER Handle; 1475 | 1476 | ERR Errors[ERROR_BUFFER_SIZE]; 1477 | UBYTE ErrorIn; 1478 | UBYTE ErrorOut; 1479 | 1480 | DATA32 MemorySize; 1481 | DATA32 MemoryFree; 1482 | ULONG MemoryTimer; 1483 | 1484 | #ifndef DISABLE_SDCARD_SUPPORT 1485 | DATA32 SdcardSize; 1486 | DATA32 SdcardFree; 1487 | ULONG SdcardTimer; 1488 | DATA8 SdcardOk; 1489 | #endif 1490 | 1491 | #ifndef DISABLE_USBSTICK_SUPPORT 1492 | DATA32 UsbstickSize; 1493 | DATA32 UsbstickFree; 1494 | ULONG UsbstickTimer; 1495 | DATA8 UsbstickOk; 1496 | #endif 1497 | 1498 | LCD LcdBuffer; //!< Copy of last LCD update 1499 | DATA8 LcdUpdated; //!< LCD updated 1500 | 1501 | ANALOG Analog; 1502 | ANALOG *pAnalog; 1503 | int AdcFile; 1504 | 1505 | #ifdef ENABLE_STATUS_TEST 1506 | DATA8 Status; 1507 | #endif 1508 | 1509 | #if (HARDWARE == SIMULATION) 1510 | class NXT * nxt; 1511 | #endif 1512 | }GLOBALS; 1513 | 1514 | 1515 | #if (HARDWARE == SIMULATION) 1516 | extern GLOBALS * gInstance; 1517 | #define VMInstance (*gInstance) 1518 | RESULT mSchedInit(); 1519 | RESULT mSchedCtrl(); 1520 | RESULT mSchedExit(); 1521 | 1522 | void setInstance(GLOBALS * _Instance); 1523 | GLOBALS * getInstance(); 1524 | #else 1525 | extern GLOBALS VMInstance; 1526 | #endif 1527 | 1528 | 1529 | #endif /* LMS2012_H_ */ 1530 | -------------------------------------------------------------------------------- /src/lmstypes.h: -------------------------------------------------------------------------------- 1 | /* 2 | * LEGO® MINDSTORMS EV3 3 | * 4 | * Copyright (C) 2010-2013 The LEGO Group 5 | * 6 | * This program is free software; you can redistribute it and/or modify 7 | * it under the terms of the GNU General Public License as published by 8 | * the Free Software Foundation; either version 2 of the License, or 9 | * (at your option) any later version. 10 | * 11 | * This program is distributed in the hope that it will be useful, 12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 14 | * GNU General Public License for more details. 15 | * 16 | * You should have received a copy of the GNU General Public License 17 | * along with this program; if not, write to the Free Software 18 | * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 19 | */ 20 | 21 | 22 | #ifndef LMSTYPES_H_ 23 | #define LMSTYPES_H_ 24 | 25 | // BASIC DATA TYPES 26 | 27 | #ifndef LEGO_SIMULATION 28 | 29 | typedef unsigned char UBYTE; //!< Basic Type used to symbolise 8 bit unsigned values 30 | typedef unsigned short UWORD; //!< Basic Type used to symbolise 16 bit unsigned values 31 | typedef unsigned int ULONG; //!< Basic Type used to symbolise 32 bit unsigned values 32 | 33 | typedef signed char SBYTE; //!< Basic Type used to symbolise 8 bit signed values 34 | typedef signed short SWORD; //!< Basic Type used to symbolise 16 bit signed values 35 | typedef signed int SLONG; //!< Basic Type used to symbolise 32 bit signed values 36 | 37 | typedef float FLOAT; //!< Basic Type used to symbolise 32 bit floating point values 38 | 39 | #define LFILE FILE 40 | 41 | #else 42 | 43 | #include 44 | #include 45 | 46 | typedef LEGO::UInt8 UBYTE; //!< Basic Type used to symbolise 8 bit unsigned values 47 | typedef LEGO::UInt16 UWORD; //!< Basic Type used to symbolise 16 bit unsigned values 48 | typedef unsigned long ULONG; //!< Basic Type used to symbolise 32 bit unsigned values 49 | 50 | 51 | typedef LEGO::Int8 SBYTE; //!< Basic Type used to symbolise 8 bit signed values 52 | typedef LEGO::Int16 SWORD; //!< Basic Type used to symbolise 16 bit signed values 53 | typedef LEGO::Int32 SLONG; //!< Basic Type used to symbolise 32 bit signed values 54 | 55 | typedef LEGO::Real32 FLOAT; //!< Basic Type used to symbolise 32 bit floating point values 56 | 57 | #endif 58 | 59 | // VM DATA TYPES 60 | 61 | typedef SBYTE DATA8; //!< VM Type for 1 byte signed value 62 | typedef SWORD DATA16; //!< VM Type for 2 byte signed value 63 | typedef SLONG DATA32; //!< VM Type for 4 byte signed value 64 | typedef FLOAT DATAF; //!< VM Type for 4 byte floating point value 65 | 66 | // VM VARIABLE TYPES 67 | 68 | typedef UBYTE VARDATA; //!< Variable base type 69 | typedef UBYTE IMGDATA; //!< Image base type 70 | 71 | typedef UWORD PRGID; //!< Program id type 72 | 73 | typedef UWORD OBJID; //!< Object id type 74 | typedef IMGDATA* IP; //!< Instruction pointer type 75 | typedef VARDATA* LP; //!< Local variable pointer type 76 | typedef VARDATA* GP; //!< global variable pointer type 77 | 78 | typedef ULONG IMINDEX; //!< ImageData index type 79 | typedef ULONG GBINDEX; //!< GlobalBytes index type 80 | typedef ULONG LBINDEX; //!< LocalBytes index type 81 | typedef UWORD TRIGGER; //!< TriggerCount type 82 | typedef UBYTE PARS; //!< NoOfParameters type 83 | typedef SLONG IMOFFS; //!< ImageData offset type 84 | 85 | typedef DATA16 HANDLER; //!< Memory list index 86 | 87 | 88 | 89 | /*! \page imagelayout Image Layout 90 | * The image consists of three different components in this fixed order: imageheader, objectheaders and byte codes. 91 | * 92 | * The imageheader tells something about image version, filesize, no of objectheaders (objects) and no of global variable bytes. 93 | * 94 | * 95 | * Objectheaders contains different informations depending on the nature of the object: 96 | * 97 | *- The VMTHREAD object (former TBC_TOPVI) \n 98 | * - OffsetToInstructions tells were to find the corresponding byte codes (offset from image start) \n 99 | * - OwnerObjectId must be zero \n 100 | * - TriggerCount is used but must be zero \n 101 | * - LocalBytes describes the number of bytes for local variables \n 102 | * 103 | *- The SUBCALL object (former TBC_VI and TBC_VI_ALIAS) \n 104 | * - OffsetToInstructions tells were to find the corresponding byte codes (if alias this is equal to mother object) \n 105 | * - OwnerObjectId must be zero \n 106 | * - TriggerCount is used and must be one \n 107 | * - LocalBytes describes the number of bytes for local variables \n 108 | * 109 | *- The BLOCK object (former CLUMP) \n 110 | * - OffsetToInstructions tells were to find the corresponding byte codes (offset from image start) \n 111 | * - OwnerObjectId is equal to object id it belongs to (not equal to zero) \n 112 | * - TriggerCount is used to determine how many triggers needed before the BLOCK object is activated \n 113 | * - LocalBytes must be zero (locals are defined in the owner object) \n 114 | * 115 | * Byte codes are described in a different section. 116 | * 117 | * Little Endian are used (addresses and data are represented with LSB on lowest address and MSB on highest address). 118 | * 119 | * Offset to instructions is number of bytes from start of image to start of object instructions. 120 | * 121 | * Index to global variables are byte based and counted from start of globals (zero based). 122 | * 123 | * Index to local variables are byte based and counted from start of object locals (zero based). 124 | * 125 | * Object ID's is not zero based - First object (VMTHEAD) is named 1. 126 | * 127 | */ 128 | 129 | /*! \page imagelayout 130 | * 131 | * FILE layout (aligned) 132 | * 133 | *- IMGHEAD (aligned) 134 | * - Sign (4 bytes) 135 | * - ImageSize (4 bytes) 136 | * - VersionInfo (2 bytes) 137 | * - NumberOfObjects (2 bytes) 138 | * - GlobalBytes (4 bytes) 139 | */ 140 | 141 | /*! \struct IMGHEAD 142 | * Image header 143 | */ 144 | typedef struct 145 | { 146 | UBYTE Sign[4]; //!< Place holder for the file type identifier 147 | IMINDEX ImageSize; //!< Image size 148 | UWORD VersionInfo; //!< Version identifier 149 | OBJID NumberOfObjects; //!< Total number of objects in image 150 | GBINDEX GlobalBytes; //!< Number of bytes to allocate for global variables 151 | } 152 | IMGHEAD; 153 | 154 | /*! \page imagelayout 155 | * 156 | *- OBJHEAD (aligned) 157 | * - OffsetToInstructions (4 bytes) 158 | * - OwnerObjectId (2 bytes) 159 | * - TriggerCount (2 bytes) 160 | * - LocalBytes (4 bytes) 161 | * 162 | */ 163 | 164 | /*! \struct OBJHEAD 165 | * Object header used for all types of objects (VMTHREAD, SUBCALL, BLOCK and ALIAS) 166 | */ 167 | typedef struct // Object header 168 | { 169 | IP OffsetToInstructions; //!< Offset to instructions from image start 170 | OBJID OwnerObjectId; //!< Used by BLOCK's to hold the owner id 171 | TRIGGER TriggerCount; //!< Used to determine how many triggers needed before the BLOCK object is activated 172 | LBINDEX LocalBytes; //!< Number of bytes to allocate for local variables 173 | } 174 | OBJHEAD; 175 | 176 | 177 | /*! \struct LABEL 178 | * Label data hold information used for labels 179 | */ 180 | typedef struct 181 | { 182 | IMINDEX Addr; //!< Offset to breakpoint address from image start 183 | } 184 | LABEL; 185 | 186 | 187 | #endif /* LMSTYPES_H_ */ 188 | -------------------------------------------------------------------------------- /src/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "ADRC.h" 3 | #include "TWIP.h" 4 | #include "Motor.h" 5 | 6 | #define GYRO_PORT 1 7 | #define ACCEL_PORT 2 8 | #define MOTOR_LEFT 1 9 | #define MOTOR_RIGHT 4 10 | 11 | using namespace std; 12 | using namespace Eigen; 13 | 14 | int main(int argc, char* argv[]) 15 | { 16 | const float dt = 0.01; 17 | const float u_max = 100.0f; 18 | const float u_min = -100.0f; 19 | 20 | if(argc != 7) { 21 | cout << "Usage: balance wo_inner wc_inner b0_inner wo_outer wc_outer b0_outer" << endl; 22 | return 1; 23 | } 24 | 25 | const float wo_inner = atof(argv[1]); 26 | const float wc_inner = atof(argv[2]); 27 | const float b0_inner = atof(argv[3]); 28 | 29 | const float wo_outer = atof(argv[4]); 30 | const float wc_outer = atof(argv[5]); 31 | const float b0_outer = atof(argv[6]); 32 | 33 | TWIP robot(GYRO_PORT, ACCEL_PORT, MOTOR_LEFT, MOTOR_RIGHT, dt); 34 | 35 | Vector2f y; 36 | float u = 0.0f; 37 | 38 | float wheel_setpoint = 0.0f; 39 | float angle_setpoint = 0.0f; 40 | 41 | ADRC inner_loop(wo_inner, wc_inner, b0_inner, dt); 42 | ADRC outer_loop(wo_outer, wc_outer, b0_outer, dt); 43 | 44 | while(true) { 45 | y = robot.output(u); 46 | angle_setpoint = outer_loop.Update(angle_setpoint, y[1], wheel_setpoint); 47 | u = inner_loop.Update(u, y[0], angle_setpoint); 48 | u = max(min(u, u_max), u_min); 49 | usleep(10000); 50 | } 51 | 52 | return 0; 53 | } 54 | --------------------------------------------------------------------------------