mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: fix reliable stream buffer size
Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
e0f5e30985
commit
3bb6fb460e
|
@ -480,12 +480,12 @@ bool AP_DDS_Client::init()
|
||||||
}
|
}
|
||||||
|
|
||||||
// setup reliable stream buffers
|
// setup reliable stream buffers
|
||||||
input_reliable_stream = new uint8_t[DDS_STREAM_HISTORY*DDS_BUFFER_SIZE];
|
input_reliable_stream = new uint8_t[DDS_BUFFER_SIZE];
|
||||||
if (input_reliable_stream == nullptr) {
|
if (input_reliable_stream == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"DDS Client: allocation failed");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"DDS Client: allocation failed");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
output_reliable_stream = new uint8_t[DDS_STREAM_HISTORY*DDS_BUFFER_SIZE];
|
output_reliable_stream = new uint8_t[DDS_BUFFER_SIZE];
|
||||||
if (output_reliable_stream == nullptr) {
|
if (output_reliable_stream == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"DDS Client: allocation failed");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"DDS Client: allocation failed");
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -24,8 +24,9 @@
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
|
||||||
|
#define DDS_MTU 512
|
||||||
#define DDS_STREAM_HISTORY 8
|
#define DDS_STREAM_HISTORY 8
|
||||||
#define DDS_BUFFER_SIZE 512
|
#define DDS_BUFFER_SIZE DDS_MTU * DDS_STREAM_HISTORY
|
||||||
|
|
||||||
// UDP only on SITL for now
|
// UDP only on SITL for now
|
||||||
#define AP_DDS_UDP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
#define AP_DDS_UDP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||||
|
|
Loading…
Reference in New Issue