From 653b554a3151b3f4f5c3d74b421c6b03a3798bf5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 Apr 2020 13:29:26 +1000 Subject: [PATCH] SITL: add simulated mavlink-attached rangefinder --- libraries/SITL/SIM_RF_MAVLink.cpp | 64 +++++++++++++++++++++++++++++++ libraries/SITL/SIM_RF_MAVLink.h | 45 ++++++++++++++++++++++ libraries/SITL/SIM_Vicon.h | 1 + 3 files changed, 110 insertions(+) create mode 100644 libraries/SITL/SIM_RF_MAVLink.cpp create mode 100644 libraries/SITL/SIM_RF_MAVLink.h diff --git a/libraries/SITL/SIM_RF_MAVLink.cpp b/libraries/SITL/SIM_RF_MAVLink.cpp new file mode 100644 index 0000000000..93e24c6950 --- /dev/null +++ b/libraries/SITL/SIM_RF_MAVLink.cpp @@ -0,0 +1,64 @@ +/* + 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 MAVLink Serial rangefinder +*/ + +#include "SIM_RF_MAVLink.h" + +#include + +#include +#include + +using namespace SITL; + +uint32_t RF_MAVLink::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) +{ + // we share channels with the ArduPilot binary! + + // we're swiping the Vicon's channel here. If it causes issues we + // may need to allocate an additional mavlink channel for the rangefinder + const mavlink_channel_t mavlink_ch = (mavlink_channel_t)(MAVLINK_COMM_0+5); + if (!valid_channel(mavlink_ch)) { + AP_HAL::panic("Invalid mavlink channel"); + } + + mavlink_message_t msg; + const uint8_t system_id = 32; + const uint8_t component_id = 32; + const mavlink_distance_sensor_t distance_sensor{ + time_boot_ms: AP_HAL::millis(), + min_distance: 10, // cm + max_distance: 10, // cm + current_distance: alt_cm, + type: 0, + id: 72, // ID + MAV_SENSOR_ROTATION_PITCH_270, + 255, // 255 is unknown covariance + 0, // 0 is unknown horizontal fov + 0, // 0 is unknown vertical fov + {0,0,0,0} // unknown/unused quat + }; + const uint16_t len = mavlink_msg_distance_sensor_encode(system_id, + component_id, + &msg, + &distance_sensor); + if (len > buflen) { + AP_HAL::panic("Insufficient buffer passed in"); + } + const uint16_t retlen = mavlink_msg_to_send_buffer(buffer, &msg); + return retlen; +} diff --git a/libraries/SITL/SIM_RF_MAVLink.h b/libraries/SITL/SIM_RF_MAVLink.h new file mode 100644 index 0000000000..cc5c284cb4 --- /dev/null +++ b/libraries/SITL/SIM_RF_MAVLink.h @@ -0,0 +1,45 @@ +/* + 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 NMEA serial rangefinder + +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rf_mavlink --speedup=1 + +param set SERIAL5_PROTOCOL 1 +param set RNGFND1_TYPE 10 +graph RANGEFINDER.distance +graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance +reboot + +arm throttle +rc 3 1600 +*/ + +#pragma once + +#include "SIM_SerialRangeFinder.h" + +namespace SITL { + +class RF_MAVLink : public SerialRangeFinder { +public: + + uint32_t packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) override; + +private: + +}; + +} diff --git a/libraries/SITL/SIM_Vicon.h b/libraries/SITL/SIM_Vicon.h index e114df1e6f..376c1bedd5 100644 --- a/libraries/SITL/SIM_Vicon.h +++ b/libraries/SITL/SIM_Vicon.h @@ -43,6 +43,7 @@ private: const uint8_t component_id = 18; // we share channels with the ArduPilot binary! + // Beware: the mavlink rangefinder shares this channel. const mavlink_channel_t mavlink_ch = (mavlink_channel_t)(MAVLINK_COMM_0+5); uint64_t last_observation_usec;