/* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* Simulator for the LightWare S45B proximity sensor ./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 # proximity param set PRX1_TYPE 8 # s45b reboot arm throttle rc 3 1600 # for avoidance: param set DISARM_DELAY 0 param set AVOID_ENABLE 2 # use proximity sensor param set AVOID_MARGIN 2.00 # 2m param set AVOID_BEHAVE 0 # slide reboot mode loiter script /tmp/post-locations.scr arm throttle rc 3 1600 rc 3 1500 rc 2 1450 */ #pragma once #include "SIM_PS_LightWare.h" #ifndef HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED #define HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED HAL_SIM_PS_LIGHTWARE_ENABLED #endif #if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED #include #include namespace SITL { class PS_LightWare_SF45B : public PS_LightWare { public: using PS_LightWare::PS_LightWare; uint32_t packet_for_location(const Location &location, uint8_t *data, uint8_t buflen) override; void update(const Location &location) override; private: template class PACKED PackedMessage { public: PackedMessage(T _msg, uint16_t _flags) : msg(_msg), flags(_flags) { flags |= (sizeof(T)) << 6; } uint8_t preamble { PREAMBLE }; uint16_t flags; T msg; uint16_t checksum; uint16_t calculate_checksum(uint16_t len) const WARN_IF_UNUSED { uint16_t ret = 0; for (uint8_t i=0; i packed_msgstream; PackedMessage packed_distance_output; PackedMessage packed_update_rate; } _msg; uint8_t _buflen; static uint16_t checksum_bytes(const char *buffer, uint8_t len) { uint16_t crc = 0; for (uint8_t i=0; i> 6) - 1; } static const uint8_t PREAMBLE = 0xAA; void move_preamble_in_buffer(uint8_t search_start_pos=0); enum class InputState { WANT_PREAMBLE = 45, WANT_FLAGS = 46, WANT_PAYLOAD = 47, WANT_CRC = 48, }; InputState _inputstate = InputState::WANT_PREAMBLE; void set_inputstate(InputState newstate) { // ::fprintf(stderr, "Moving from inputstate (%u) to (%u)\n", (uint8_t)_inputstate, (uint8_t)newstate); _inputstate = newstate; } /* * SETTINGS */ uint32_t stream; uint32_t desired_fields; uint8_t update_rate; /* * OUTPUT HANDLING */ struct { bool stream; bool desired_fields; bool update_rate; } send_response; enum class State { SCANNING = 21, }; State _state = State::SCANNING; void set_state(State newstate) { // ::fprintf(stderr, "Moving from state (%u) to (%u)\n", (uint8_t)_state, (uint8_t)newstate); _state = newstate; } void update_output(const Location &location); void update_output_responses(); void update_output_scan(const Location &location); uint32_t last_scan_output_time_ms; float last_degrees_bf; // previous iteration's lidar angle float last_dir = 1; // previous iterations movement direction. +1 CW, -1 for CCW }; }; #endif // HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED