Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_EFI/AP_EFI_Serial_MS.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#pragma once1516#include "AP_EFI_config.h"1718#if AP_EFI_SERIAL_MS_ENABLED1920#include "AP_EFI.h"21#include "AP_EFI_Backend.h"2223// RPM Threshold for fuel consumption estimator24#define RPM_THRESHOLD 1002526class AP_EFI_Serial_MS: public AP_EFI_Backend {2728public:29// Constructor with initialization30AP_EFI_Serial_MS(AP_EFI &_frontend);3132// Update the state structure33void update() override;3435private:36AP_HAL::UARTDriver *port;37void parse_realtime_data();38bool read_incoming_realtime_data();39void send_request(uint8_t table, uint16_t first_offset, uint16_t last_offset);40uint8_t read_byte_CRC32();41uint32_t CRC32_compute_byte(uint32_t inCrc32, uint8_t data);4243// Serial Protocol Variables44uint32_t checksum;45uint8_t step;46uint8_t response_flag;47uint16_t message_counter;48uint32_t last_request_ms;4950// confirmed that last command was ok51bool last_command_confirmed;5253// Command Response Codes54enum response_codes {55RESPONSE_WRITE_OK =0x00,56RESPONSE_REALTIME_DATA,57RESPONSE_PAGE_DATA,58RESPONSE_CONFIG_ERROR,59RESPONSE_PAGE10_OK,60RESPONSE_CAN_DATA,61// Error Responses62ERR_UNDERRUN = 0X80,63ERR_OVERRUN,64ERR_CRC_FAILURE,65ERR_UNRECOGNIZED_COMMAND,66ERR_OUT_OF_RANGE,67ERR_SERIAL_BUSY,68ERR_FLASH_LOCKED,69ERR_SEQ_FAIL_1,70ERR_SEQ_FAIL_2,71ERR_CAN_QUEUE_FULL,72ERR_CAN_TIMEOUT,73ERR_CAN_FAILURE,74ERR_PARITY,75ERR_FRAMING,76ERR_SERIAL_NOISE,77ERR_TXMODE_RANGE,78ERR_UNKNOWN79};8081// Realtime Data Table Locations82enum realtime_data {83PW1_MSB = 2,84PW1_LSB,85RPM_MSB = 6,86RPM_LSB,87ADVANCE_MSB,88ADVANCE_LSB,89ENGINE_BM = 11,90BAROMETER_MSB = 16,91BAROMETER_LSB,92MAP_MSB,93MAP_LSB,94MAT_MSB,95MAT_LSB,96CHT_MSB,97CHT_LSB,98TPS_MSB,99TPS_LSB,100AFR1_MSB = 28,101AFR1_LSB,102AFR2_MSB,103AFR2_LSB,104DWELL_MSB = 62,105DWELL_LSB,106LOAD = 66,107FUEL_PRESSURE_MSB = 128,108FUEL_PRESSURE_LSB,109// Helpers used when sending request110RT_FIRST_OFFSET = PW1_MSB,111RT_LAST_OFFSET = FUEL_PRESSURE_LSB112};113};114115#endif // AP_EFI_SERIAL_MS_ENABLED116117118