SITL: add simulated SF45B

This commit is contained in:
Peter Barker 2020-12-08 21:13:41 +11:00 committed by Peter Barker
parent c1202e4878
commit 449b0fb145
3 changed files with 518 additions and 0 deletions

View File

@ -0,0 +1,37 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
Base class for LightWare Proximity Sensor serial devices.
*/
#pragma once
#include "SIM_SerialProximitySensor.h"
#include <stdio.h>
namespace SITL {
class PS_LightWare : public SerialProximitySensor {
public:
PS_LightWare() { }
private:
};
};

View File

@ -0,0 +1,222 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
Simulator for the RPLidarA2 proximity sensor
*/
#include "SIM_PS_LightWare_SF45B.h"
#include <GCS_MAVLink/GCS.h>
#include <stdio.h>
#include <errno.h>
using namespace SITL;
uint32_t PS_LightWare_SF45B::packet_for_location(const Location &location,
uint8_t *data,
uint8_t buflen)
{
return 0;
}
void PS_LightWare_SF45B::move_preamble_in_buffer(uint8_t search_start_pos)
{
uint8_t i;
for (i=search_start_pos; i<_buflen; i++) {
if ((uint8_t)_msg.buffer[i] == PREAMBLE) {
break;
}
}
if (i == 0) {
return;
}
memmove(_msg.buffer, &_msg.buffer[i], _buflen-i);
_buflen = _buflen - i;
}
// handle a valid message in _msg.buffer
void PS_LightWare_SF45B::send(const char *data, uint32_t len)
{
const ssize_t ret = write_to_autopilot(data, len);
if (ret < 0 || (uint32_t)ret != len) {
abort();
}
}
void PS_LightWare_SF45B::handle_message()
{
// GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Got message %u", (unsigned)_msg.packed_msgstream.msg.msgid);
switch (MessageID(_msg.packed_msgstream.msg.msgid)) {
case MessageID::STREAM: {
stream = _msg.packed_msgstream.msg.stream;
send_response.stream = true;
return;
}
case MessageID::DISTANCE_OUTPUT: {
desired_fields = _msg.packed_distance_output.msg.desired_fields;
send_response.desired_fields = true;
return;
}
case MessageID::UPDATE_RATE: {
update_rate = _msg.packed_update_rate.msg.rate;
send_response.update_rate = true;
return;
}
case MessageID::DISTANCE_DATA_CM: {
::fprintf(stderr, "Got a distance data. Weird.\n");
return;
}
}
// AP_HAL::panic("Unrecognised message (%u)", _msg.common.msgid);
::fprintf(stderr, "Unrecognised message (%u)\n", _msg.packed_msgstream.msg.msgid);
}
void PS_LightWare_SF45B::update_input()
{
const ssize_t n = read_from_autopilot(&_msg.buffer[_buflen], ARRAY_SIZE(_msg.buffer) - _buflen - 1);
if (n < 0) {
// TODO: do better here
if (errno != EAGAIN && errno != EWOULDBLOCK && errno != 0) {
AP_HAL::panic("Failed to read from autopilot");
}
} else {
_buflen += n;
}
switch (_inputstate) {
case InputState::WANT_PREAMBLE:
move_preamble_in_buffer();
if (_buflen == 0) {
return;
}
set_inputstate(InputState::WANT_FLAGS);
FALLTHROUGH;
case InputState::WANT_FLAGS:
if (_buflen < 4) { // 1 preamble, 2 flags, 1 msg
return;
}
set_inputstate(InputState::WANT_PAYLOAD);
FALLTHROUGH;
case InputState::WANT_PAYLOAD: {
// 1 preamble, 2 flags, 1 msg + payload
const uint8_t want_len = 4 + payload_length();
if (_buflen < want_len) {
return;
}
set_inputstate(InputState::WANT_CRC);
FALLTHROUGH;
}
case InputState::WANT_CRC: {
// 1 preamble, 2 flags, 1 msg + payload + 2 crc
const uint8_t want_len = 4 + payload_length() + 2;
if (_buflen < want_len) {
return;
}
const uint16_t got_checksum = UINT16_VALUE(uint8_t(_msg.buffer[want_len-1]), uint8_t(_msg.buffer[want_len-2]));
const uint16_t calc_checksum = msg_checksum();
if (calc_checksum == got_checksum) {
// GCS_SEND_TEXT(MAV_SEVERITY_INFO, "sim-SF45B: Got one (%u)!", _msg.common.msgid);
// see if this was a read or a write request..
handle_message();
} else {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "sim-SF45B: Bad checksum");
}
// consume these bytes
move_preamble_in_buffer(want_len-1);
set_inputstate(InputState::WANT_PREAMBLE);
return;
}
}
}
void PS_LightWare_SF45B::update(const Location &location)
{
update_input();
update_output(location);
}
void PS_LightWare_SF45B::update_output(const Location &location)
{
switch (_state) {
case State::SCANNING:
update_output_responses();
update_output_scan(location);
return;
}
}
void PS_LightWare_SF45B::update_output_responses()
{
if (send_response.stream) {
send_response.stream = false;
PackedMessage<MsgStream> packed { MsgStream(stream), 0x1 };
packed.update_checksum();
send((char*)&packed, sizeof(packed));
}
if (send_response.update_rate) {
send_response.update_rate = false;
PackedMessage<UpdateRate> packed { UpdateRate(update_rate), 0x1 };
packed.update_checksum();
send((char*)&packed, sizeof(packed));
}
if (send_response.desired_fields) {
send_response.desired_fields = false;
PackedMessage<DistanceOutput> packed { DistanceOutput(desired_fields), 0x1 };
packed.update_checksum();
send((char*)&packed, sizeof(packed));
}
}
void PS_LightWare_SF45B::update_output_scan(const Location &location)
{
const uint32_t now = AP_HAL::millis();
if (last_scan_output_time_ms == 0) {
last_scan_output_time_ms = now;
return;
}
const uint32_t time_delta = (now - last_scan_output_time_ms);
const uint32_t samples_per_second = 1000;
const float samples_per_ms = samples_per_second / 1000.0f;
const uint32_t sample_count = time_delta / samples_per_ms;
const float degrees_per_ms = 3600 / 1000.0f;
const float degrees_per_sample = degrees_per_ms / samples_per_ms;
// ::fprintf(stderr, "Packing %u samples in for %ums interval (%f degrees/sample)\n", sample_count, time_delta, degrees_per_sample);
last_scan_output_time_ms += sample_count/samples_per_ms;
for (uint32_t i=0; i<sample_count; i++) {
const float current_degrees_bf = fmod((last_degrees_bf + degrees_per_sample), 360.0f);
last_degrees_bf = current_degrees_bf;
const float MAX_RANGE = 16.0f;
float distance = measure_distance_at_angle_bf(location, current_degrees_bf);
// ::fprintf(stderr, "SIM: %f=%fm\n", current_degrees_bf, distance);
if (distance > MAX_RANGE) {
// sensor returns zero for out-of-range
distance = 0.0f;
}
PackedMessage<DistanceDataCM> packed_distance_data {
DistanceDataCM(
uint16_t(distance*100.0),
uint16_t(current_degrees_bf * 100)
), 0x1 };
packed_distance_data.update_checksum();
send((char*)&packed_distance_data, sizeof(packed_distance_data));
}
}

View File

@ -0,0 +1,259 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
Simulator for the LightWare S45B proximity sensor
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,0,0
param set SERIAL5_PROTOCOL 11 # proximity
param set PRX_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"
#include <AP_Math/crc.h>
namespace SITL {
class PS_LightWare_SF45B : public PS_LightWare {
public:
uint32_t packet_for_location(const Location &location,
uint8_t *data,
uint8_t buflen) override;
void update(const Location &location) override;
PS_LightWare_SF45B() : PS_LightWare() { }
private:
template <typename T>
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<len; i++) {
ret = crc_xmodem_update(ret, ((const char*)this)[i]);
}
return ret;
}
uint16_t calculate_checksum() const WARN_IF_UNUSED {
return calculate_checksum(3+sizeof(T));
}
void update_checksum() {
checksum = calculate_checksum();
}
};
class PACKED MsgStream {
public:
MsgStream(uint32_t _stream) :
stream(_stream)
{ }
uint8_t msgid { (uint8_t)MessageID::STREAM };
uint32_t stream;
};
class PACKED DistanceOutput {
public:
DistanceOutput(uint32_t _desired_fields) :
desired_fields(_desired_fields)
{ }
uint8_t msgid { (uint8_t)MessageID::DISTANCE_OUTPUT };
uint32_t desired_fields;
};
class PACKED UpdateRate {
public:
UpdateRate(uint8_t _rate) :
rate(_rate)
{ }
uint8_t msgid { (uint8_t)MessageID::UPDATE_RATE };
uint8_t rate;
};
class PACKED DistanceDataCM {
public:
DistanceDataCM(uint16_t _distance_cm, uint16_t _angle_cd) :
distance_cm(_distance_cm),
angle_cd(_angle_cd)
{ }
uint8_t msgid { (uint8_t)MessageID::DISTANCE_DATA_CM };
uint16_t distance_cm;
uint16_t angle_cd;
};
// message ids
enum class MessageID : uint8_t {
// PRODUCT_NAME = 0,
// HARDWARE_VERSION = 1,
// FIRMWARE_VERSION = 2,
// SERIAL_NUMBER = 3,
// TEXT_MESSAGE = 7,
// USER_DATA = 9,
// TOKEN = 10,
// SAVE_PARAMETERS = 12,
// RESET = 14,
// STAGE_FIRMWARE = 16,
// COMMIT_FIRMWARE = 17,
DISTANCE_OUTPUT = 27,
STREAM = 30,
DISTANCE_DATA_CM = 44,
// DISTANCE_DATA_MM = 45,
// LASER_FIRING = 50,
// TEMPERATURE = 57,
UPDATE_RATE = 66,
// NOISE = 74,
// ZERO_OFFSET = 75,
// LOST_SIGNAL_COUNTER = 76,
// BAUD_RATE = 79,
// I2C_ADDRESS = 80,
// STEPPER_STATUS = 93,
// SCAN_ON_STARTUP = 94,
// SCAN_ENABLE = 96,
// SCAN_POSITION = 97,
// SCAN_LOW_ANGLE = 98,
// SCAN_HIGH_ANGLE = 99
};
/*
* Input Handling
*/
void update_input();
// make the message in the buffer a read message and return to sender
void boomerang_buffer_message(uint8_t len);
// handle a complete checksummed message
void handle_message();
void send(const char *data, uint32_t len);
union u {
u() {}
char buffer[256]; // from-autopilot
PackedMessage<MsgStream> packed_msgstream;
PackedMessage<DistanceOutput> packed_distance_output;
PackedMessage<UpdateRate> 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<len; i++) {
crc = crc_xmodem_update(crc, buffer[i]);
}
return crc;
}
uint16_t msg_checksum() const {
// 4 is 1 preamble, 2 flags, 1 msgid
return checksum_bytes(_msg.buffer, payload_length() + 4);
}
uint8_t payload_length() const {
if (_buflen < 3) {
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
}
return (_msg.packed_msgstream.flags >> 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;
};
};