SITL: add simulated MaxSonarI2CXL i2c sensor

This commit is contained in:
Peter Barker 2020-08-03 13:23:10 +10:00 committed by Peter Barker
parent 80d7a4ee5e
commit b5050c1e11
3 changed files with 69 additions and 0 deletions

View File

@ -22,6 +22,7 @@
#include "SIM_I2C.h"
#include "SIM_ToshibaLED.h"
#include "SIM_MaxSonarI2CXL.h"
#include <signal.h>
@ -41,6 +42,7 @@ public:
static IgnoredI2CDevice ignored;
static ToshibaLED toshibaled;
static MaxSonarI2CXL maxsonari2cxl;
struct i2c_device_at_address {
uint8_t bus;
@ -51,6 +53,7 @@ struct i2c_device_at_address {
{ 1, 0x38, ignored }, // NCP5623
{ 1, 0x39, ignored }, // NCP5623C
{ 1, 0x40, ignored }, // KellerLD
{ 1, 0x70, maxsonari2cxl },
{ 1, 0x76, ignored }, // MS56XX
};

View File

@ -0,0 +1,45 @@
#include "SIM_MaxSonarI2CXL.h"
#include <SITL/SITL.h>
#include <SITL/SIM_Aircraft.h>
#include <stdio.h>
int SITL::MaxSonarI2CXL::rdwr(I2C::i2c_rdwr_ioctl_data *&data)
{
const uint32_t now = AP_HAL::millis();
struct I2C::i2c_msg &msg = data->msgs[0];
if (msg.flags == I2C_M_RD) {
// driver is attempting to receive reading...
if (now - cmd_take_reading_received_ms < 20) {
// not sure we ought to be returning -1 here - what does
// the real device do? return stale data? garbage data?
return -1;
}
if (msg.len != 2) {
AP_HAL::panic("Unxpected message length (%u)", msg.len);
}
const uint16_t range_cm = rangefinder_range * 100;
msg.buf[0] = range_cm >> 8;
msg.buf[1] = range_cm & 0xff;
return 0;
}
const uint8_t CMD_TAKE_READING = 0x51;
const uint8_t cmd = msg.buf[0];
if (cmd != CMD_TAKE_READING) {
AP_HAL::panic("Unknown command (%u)", cmd);
}
cmd_take_reading_received_ms = now;
return 0;
};
void SITL::MaxSonarI2CXL::update(const Aircraft &aircraft)
{
rangefinder_range = aircraft.rangefinder_range();
}

View File

@ -0,0 +1,21 @@
#pragma once
#include "SIM_I2CDevice.h"
namespace SITL {
class MaxSonarI2CXL : public I2CDevice
{
public:
void update(const class Aircraft &aircraft) override;
int rdwr(I2C::i2c_rdwr_ioctl_data *&data) override;
private:
uint32_t cmd_take_reading_received_ms;
float rangefinder_range;
};
} // namespace SITL