mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: add #if HAL_PROXIMITY_ENABLED
This commit is contained in:
parent
34d6094838
commit
1fad5d46e7
|
@ -14,6 +14,8 @@
|
|||
*/
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include "AP_Proximity_LightWareSF40C_v09.h"
|
||||
#include "AP_Proximity_RPLidarA2.h"
|
||||
#include "AP_Proximity_TeraRangerTower.h"
|
||||
|
@ -502,3 +504,5 @@ AP_Proximity *proximity()
|
|||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -14,8 +14,16 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_PROXIMITY_ENABLED
|
||||
#define HAL_PROXIMITY_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024)
|
||||
#endif
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
@ -187,3 +195,5 @@ private:
|
|||
namespace AP {
|
||||
AP_Proximity *proximity();
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,9 +13,11 @@
|
|||
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_AirSimSITL.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <stdio.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -93,4 +95,6 @@ bool AP_Proximity_AirSimSITL::get_upward_distance(float &distance) const
|
|||
return false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -15,9 +15,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
|
@ -43,3 +44,5 @@ private:
|
|||
|
||||
};
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,14 +13,14 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AC_Avoidance/AP_OADatabase.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -205,3 +205,5 @@ void AP_Proximity_Backend::database_push(float angle, float pitch, float distanc
|
|||
|
||||
oaDb->queue_push(temp_pos, timestamp_ms, distance);
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -14,9 +14,11 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include "AP_Proximity_Boundary_3D.h"
|
||||
|
||||
|
@ -118,3 +120,5 @@ protected:
|
|||
// Methods to manipulate 3D boundary in this class
|
||||
AP_Proximity_Boundary_3D boundary;
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -15,6 +15,7 @@
|
|||
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
/*
|
||||
|
@ -41,3 +42,4 @@ bool AP_Proximity_Backend_Serial::detect()
|
|||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0) != nullptr;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
class AP_Proximity_Backend_Serial : public AP_Proximity_Backend
|
||||
{
|
||||
public:
|
||||
|
@ -16,3 +17,5 @@ protected:
|
|||
|
||||
AP_HAL::UARTDriver *_uart; // uart for communicating with sensor
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,6 +1,23 @@
|
|||
#include "AP_Proximity_Backend.h"
|
||||
/*
|
||||
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_Proximity_Boundary_3D.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
/*
|
||||
Constructor.
|
||||
This incorporates initialisation as well.
|
||||
|
@ -357,3 +374,5 @@ bool AP_Proximity_Boundary_3D::get_layer_distances(uint8_t layer_number, float d
|
|||
|
||||
return valid_distances;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -15,6 +15,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#include <Filter/LowPassFilter.h>
|
||||
|
||||
#define PROXIMITY_NUM_SECTORS 8 // number of sectors
|
||||
|
@ -156,3 +160,4 @@ private:
|
|||
LowPassFilterFloat _filtered_distance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // low pass filter
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,11 +13,13 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Proximity_LightWareSF40C.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include "AP_Proximity_LightWareSF40C.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -418,3 +420,5 @@ uint16_t AP_Proximity_LightWareSF40C::buff_to_uint16(uint8_t b0, uint8_t b1) con
|
|||
uint16_t leval = (uint16_t)b0 | (uint16_t)b1 << 8;
|
||||
return leval;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#define PROXIMITY_SF40C_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
|
||||
#define PROXIMITY_SF40C_PAYLOAD_LEN_MAX 256 // maximum payload size we can accept (in some configurations sensor may send as large as 1023)
|
||||
#define PROXIMITY_SF40C_COMBINE_READINGS 7 // combine this many readings together to improve efficiency
|
||||
|
@ -150,3 +151,5 @@ private:
|
|||
uint32_t buff_to_uint32(uint8_t b0, uint8_t b1, uint8_t b2, uint8_t b3) const;
|
||||
uint16_t buff_to_uint16(uint8_t b0, uint8_t b1) const;
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,8 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity_LightWareSF40C_v09.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
|
||||
|
@ -360,3 +362,5 @@ void AP_Proximity_LightWareSF40C_v09::clear_buffers()
|
|||
element_num = 0;
|
||||
memset(element_buf, 0, sizeof(element_buf));
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#define PROXIMITY_SF40C_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
|
||||
|
||||
class AP_Proximity_LightWareSF40C_v09 : public AP_Proximity_Backend_Serial
|
||||
|
@ -88,3 +88,5 @@ private:
|
|||
uint8_t _motor_direction = 99; // motor direction as reported by lidar
|
||||
int16_t _forward_direction = 999; // forward direction as reported by lidar
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -16,10 +16,12 @@
|
|||
http://support.lightware.co.za/sf45/#/commands
|
||||
*/
|
||||
|
||||
#include "AP_Proximity_LightWareSF45B.h"
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
#include "AP_Proximity_LightWareSF45B.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -197,3 +199,5 @@ uint8_t AP_Proximity_LightWareSF45B::convert_angle_to_minisector(float angle_deg
|
|||
{
|
||||
return wrap_360(angle_deg + (PROXIMITY_SF45B_COMBINE_READINGS_DEG * 0.5f)) / PROXIMITY_SF45B_COMBINE_READINGS_DEG;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,9 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include <Filter/Filter.h>
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_LightWareSerial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <Filter/Filter.h>
|
||||
|
||||
class AP_Proximity_LightWareSF45B : public AP_Proximity_LightWareSerial
|
||||
{
|
||||
|
||||
|
@ -100,3 +101,5 @@ private:
|
|||
} _sensor_state;
|
||||
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,11 +13,13 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Proximity_LightWareSerial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include "AP_Proximity_LightWareSerial.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -138,3 +140,5 @@ bool AP_Proximity_LightWareSerial::parse_byte(uint8_t b)
|
|||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#define PROXIMITY_LIGHTWARE_PAYLOAD_LEN_MAX 256 // maximum payload size we can accept (in some configurations sensor may send as large as 1023)
|
||||
|
||||
class AP_Proximity_LightWareSerial : public AP_Proximity_Backend_Serial
|
||||
|
@ -48,3 +48,5 @@ protected:
|
|||
uint8_t crc_high; // crc high byte
|
||||
} _msg;
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,8 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity_MAV.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
|
||||
|
@ -261,3 +263,5 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t &
|
|||
}
|
||||
return;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
class AP_Proximity_MAV : public AP_Proximity_Backend
|
||||
{
|
||||
|
||||
|
@ -42,3 +43,5 @@ private:
|
|||
uint32_t _last_upward_update_ms; // system time of last update of upward distance
|
||||
float _distance_upward; // upward distance in meters
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -26,8 +26,10 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity_RPLidarA2.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
|
||||
|
@ -358,3 +360,5 @@ void AP_Proximity_RPLidarA2::parse_response_data()
|
|||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -29,10 +29,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
#include <AP_HAL/AP_HAL.h> ///< for UARTDriver
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
class AP_Proximity_RPLidarA2 : public AP_Proximity_Backend_Serial
|
||||
{
|
||||
|
@ -121,3 +120,5 @@ private:
|
|||
_sensor_health sensor_health;
|
||||
} payload;
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,8 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity_RangeFinder.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
|
@ -90,3 +92,5 @@ bool AP_Proximity_RangeFinder::get_upward_distance(float &distance) const
|
|||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#define PROXIMITY_RANGEFIDER_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
|
||||
|
||||
class AP_Proximity_RangeFinder : public AP_Proximity_Backend
|
||||
|
@ -33,3 +34,5 @@ private:
|
|||
uint32_t _last_upward_update_ms; // system time of last update distance
|
||||
float _distance_upward = -1; // upward distance in meters, negative if the last reading was out of range
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,11 +13,14 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Proximity_SITL.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include "AP_Proximity_SITL.h"
|
||||
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
#include <stdio.h>
|
||||
|
||||
|
@ -124,3 +127,5 @@ bool AP_Proximity_SITL::get_upward_distance(float &distance) const
|
|||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include "AP_Proximity_Backend.h"
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
|
@ -37,3 +39,5 @@ private:
|
|||
|
||||
};
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -13,8 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity_TeraRangerTower.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
|
@ -103,3 +105,5 @@ void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_
|
|||
}
|
||||
_last_distance_received_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#define PROXIMITY_TRTOWER_TIMEOUT_MS 300 // requests timeout after 0.3 seconds
|
||||
|
||||
class AP_Proximity_TeraRangerTower : public AP_Proximity_Backend_Serial
|
||||
|
@ -32,3 +32,5 @@ private:
|
|||
// request related variables
|
||||
uint32_t _last_distance_received_ms; // system time of last distance measurement received from sensor
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -15,6 +15,8 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_Proximity_TeraRangerTowerEvo.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_Math/crc.h>
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
|
@ -158,3 +160,5 @@ void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint
|
|||
}
|
||||
_last_distance_received_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#include "AP_Proximity_Backend_Serial.h"
|
||||
|
||||
#define PROXIMITY_TRTOWER_TIMEOUT_MS 300 // requests timeout after 0.3 seconds
|
||||
|
@ -56,3 +58,5 @@ private:
|
|||
// const uint8_t REFRESH_500_HZ[5] = { (uint8_t)0x00, (uint8_t)0x52, (uint8_t)0x03, (uint8_t)0x05, (uint8_t)0xD6};
|
||||
// const uint8_t REFRESH_600_HZ[5] = { (uint8_t)0x00, (uint8_t)0x52, (uint8_t)0x03, (uint8_t)0x06, (uint8_t)0xDF};
|
||||
};
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
Loading…
Reference in New Issue