AP_Proximity: Remove Morse backend
This commit is contained in:
parent
0e50023593
commit
c1d67705ce
@ -23,7 +23,6 @@
|
|||||||
#include "AP_Proximity_LightWareSF40C.h"
|
#include "AP_Proximity_LightWareSF40C.h"
|
||||||
#include "AP_Proximity_LightWareSF45B.h"
|
#include "AP_Proximity_LightWareSF45B.h"
|
||||||
#include "AP_Proximity_SITL.h"
|
#include "AP_Proximity_SITL.h"
|
||||||
#include "AP_Proximity_MorseSITL.h"
|
|
||||||
#include "AP_Proximity_AirSimSITL.h"
|
#include "AP_Proximity_AirSimSITL.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
@ -35,7 +34,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _TYPE
|
// @Param: _TYPE
|
||||||
// @DisplayName: Proximity type
|
// @DisplayName: Proximity type
|
||||||
// @Description: What type of proximity sensor is connected
|
// @Description: What type of proximity sensor is connected
|
||||||
// @Values: 0:None,7:LightwareSF40c,1:LightWareSF40C-legacy,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,11:MorseSITL,12:AirSimSITL
|
// @Values: 0:None,7:LightwareSF40c,1:LightWareSF40C-legacy,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,12:AirSimSITL
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_TYPE", 1, AP_Proximity, _type[0], 0),
|
AP_GROUPINFO("_TYPE", 1, AP_Proximity, _type[0], 0),
|
||||||
@ -155,7 +154,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: 2_TYPE
|
// @Param: 2_TYPE
|
||||||
// @DisplayName: Second Proximity type
|
// @DisplayName: Second Proximity type
|
||||||
// @Description: What type of proximity sensor is connected
|
// @Description: What type of proximity sensor is connected
|
||||||
// @Values: 0:None,7:LightwareSF40c,1:LightWareSF40C-legacy,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,11:MorseSITL,12:AirSimSITL
|
// @Values: 0:None,7:LightwareSF40c,1:LightWareSF40C-legacy,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,12:AirSimSITL
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("2_TYPE", 16, AP_Proximity, _type[1], 0),
|
AP_GROUPINFO("2_TYPE", 16, AP_Proximity, _type[1], 0),
|
||||||
@ -342,11 +341,6 @@ void AP_Proximity::detect_instance(uint8_t instance)
|
|||||||
drivers[instance] = new AP_Proximity_SITL(*this, state[instance]);
|
drivers[instance] = new AP_Proximity_SITL(*this, state[instance]);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
case Type::MorseSITL:
|
|
||||||
state[instance].instance = instance;
|
|
||||||
drivers[instance] = new AP_Proximity_MorseSITL(*this, state[instance]);
|
|
||||||
return;
|
|
||||||
|
|
||||||
case Type::AirSimSITL:
|
case Type::AirSimSITL:
|
||||||
state[instance].instance = instance;
|
state[instance].instance = instance;
|
||||||
drivers[instance] = new AP_Proximity_AirSimSITL(*this, state[instance]);
|
drivers[instance] = new AP_Proximity_AirSimSITL(*this, state[instance]);
|
||||||
|
@ -50,7 +50,6 @@ public:
|
|||||||
SF45B = 8,
|
SF45B = 8,
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
SITL = 10,
|
SITL = 10,
|
||||||
MorseSITL = 11,
|
|
||||||
AirSimSITL = 12,
|
AirSimSITL = 12,
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
@ -1,90 +0,0 @@
|
|||||||
/*
|
|
||||||
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/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
||||||
#include "AP_Proximity_MorseSITL.h"
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
|
||||||
|
|
||||||
#define PROXIMITY_MAX_RANGE 200.0f
|
|
||||||
#define PROXIMITY_ACCURACY 0.1f
|
|
||||||
|
|
||||||
// update the state of the sensor
|
|
||||||
void AP_Proximity_MorseSITL::update(void)
|
|
||||||
{
|
|
||||||
SITL::vector3f_array &points = sitl->state.scanner.points;
|
|
||||||
SITL::float_array &ranges = sitl->state.scanner.ranges;
|
|
||||||
if (points.length != ranges.length ||
|
|
||||||
points.length == 0) {
|
|
||||||
set_status(AP_Proximity::Status::NoData);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
set_status(AP_Proximity::Status::Good);
|
|
||||||
|
|
||||||
memset(_distance_valid, 0, sizeof(_distance_valid));
|
|
||||||
memset(_angle, 0, sizeof(_angle));
|
|
||||||
memset(_distance, 0, sizeof(_distance));
|
|
||||||
|
|
||||||
for (uint16_t i=0; i<points.length; i++) {
|
|
||||||
Vector3f &point = points.data[i];
|
|
||||||
float &range = ranges.data[i];
|
|
||||||
distance_maximum = MAX(distance_maximum, range);
|
|
||||||
if (point.is_zero()) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
float angle_deg = wrap_360(degrees(atan2f(-point.y, point.x)));
|
|
||||||
uint16_t angle_rounded = uint16_t(angle_deg+0.5);
|
|
||||||
const uint8_t sector = convert_angle_to_sector(angle_rounded);
|
|
||||||
if (!_distance_valid[sector] || range < _distance[sector]) {
|
|
||||||
_distance_valid[sector] = true;
|
|
||||||
_distance[sector] = range;
|
|
||||||
_angle[sector] = angle_deg;
|
|
||||||
update_boundary_for_sector(sector, true);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
printf("npoints=%u\n", points.length);
|
|
||||||
for (uint16_t i=0; i<PROXIMITY_NUM_SECTORS; i++) {
|
|
||||||
printf("sector[%u] ang=%.1f dist=%.1f\n", i, _angle[i], _distance[i]);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
// get maximum and minimum distances (in meters) of primary sensor
|
|
||||||
float AP_Proximity_MorseSITL::distance_max() const
|
|
||||||
{
|
|
||||||
// we don't have a data field from Morse for max range, so we use the max
|
|
||||||
// we've ever seen
|
|
||||||
return distance_maximum;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_Proximity_MorseSITL::distance_min() const
|
|
||||||
{
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
|
|
||||||
// get distance upwards in meters. returns true on success
|
|
||||||
bool AP_Proximity_MorseSITL::get_upward_distance(float &distance) const
|
|
||||||
{
|
|
||||||
// we don't have an upward facing laser
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
@ -1,30 +0,0 @@
|
|||||||
#pragma once
|
|
||||||
|
|
||||||
#include "AP_Proximity.h"
|
|
||||||
#include "AP_Proximity_Backend.h"
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
||||||
#include <SITL/SITL.h>
|
|
||||||
|
|
||||||
class AP_Proximity_MorseSITL : public AP_Proximity_Backend
|
|
||||||
{
|
|
||||||
|
|
||||||
public:
|
|
||||||
// constructor
|
|
||||||
using AP_Proximity_Backend::AP_Proximity_Backend;
|
|
||||||
|
|
||||||
// update state
|
|
||||||
void update(void) override;
|
|
||||||
|
|
||||||
// get maximum and minimum distances (in meters) of sensor
|
|
||||||
float distance_max() const override;
|
|
||||||
float distance_min() const override;
|
|
||||||
|
|
||||||
// get distance upwards in meters. returns true on success
|
|
||||||
bool get_upward_distance(float &distance) const override;
|
|
||||||
|
|
||||||
private:
|
|
||||||
SITL::SITL *sitl = AP::sitl();
|
|
||||||
float distance_maximum;
|
|
||||||
};
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
Loading…
Reference in New Issue
Block a user