diff --git a/slam-libraries/viam-cartographer/src/main.cc b/slam-libraries/viam-cartographer/src/main.cc index 6e27d392..d4fe0f26 100644 --- a/slam-libraries/viam-cartographer/src/main.cc +++ b/slam-libraries/viam-cartographer/src/main.cc @@ -37,6 +37,10 @@ int main(int argc, char** argv) { builder.AddListeningPort(slamService.port, grpc::InsecureServerCredentials(), selected_port.get()); + // Increasing the gRPC max message size from the default value of 4MB to + // 32MB, to match the limit that is set in RDK. This is necessary for + // transmitting large pointclouds. + builder.SetMaxSendMessageSize(32 * 1024 * 1024); builder.RegisterService(&slamService); // Start the SLAM gRPC server diff --git a/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc b/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc index fb197023..1c8fa820 100644 --- a/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc +++ b/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc @@ -51,6 +51,11 @@ int main(int argc, char **argv) { builder.AddListeningPort(slamService.slam_port, grpc::InsecureServerCredentials(), selected_port.get()); + + // Increasing the gRPC max message size from the default value of 4MB to + // 32MB, to match the limit that is set in RDK. This is necessary for + // transmitting large pointclouds. + builder.SetMaxSendMessageSize(32 * 1024 * 1024); builder.RegisterService(&slamService); // Start the SLAM gRPC server