From bc5c5e9253fe6a857af85607ec8e4fa8815bedec Mon Sep 17 00:00:00 2001 From: jeremyhyde-viam <92594844+jeremyhyde-viam@users.noreply.github.com> Date: Fri, 9 Dec 2022 17:47:59 -0500 Subject: [PATCH 1/6] set max message size --- slam-libraries/viam-cartographer/src/main.cc | 3 +++ slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc | 3 +++ 2 files changed, 6 insertions(+) diff --git a/slam-libraries/viam-cartographer/src/main.cc b/slam-libraries/viam-cartographer/src/main.cc index ba09ef10..0e52a95a 100644 --- a/slam-libraries/viam-cartographer/src/main.cc +++ b/slam-libraries/viam-cartographer/src/main.cc @@ -11,6 +11,8 @@ #include "slam_service/config.h" #include "slam_service/slam_service.h" +const int maxMessageSize = 32 * 1024 * 1024;; + void exit_loop_handler(int s) { LOG(INFO) << "Finishing session.\n"; viam::b_continue_session = false; @@ -38,6 +40,7 @@ int main(int argc, char** argv) { builder.AddListeningPort(slamService.port, grpc::InsecureServerCredentials(), selected_port.get()); + builder.SetMaxSendMessageSize(maxMessageSize); 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 ab552e51..bfa581b6 100644 --- a/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc +++ b/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc @@ -18,6 +18,8 @@ using grpc::Server; using grpc::ServerBuilder; using SlamPtr = std::unique_ptr; +const int maxMessageSize = 32 * 1024 * 1024; + void exit_loop_handler(int s) { BOOST_LOG_TRIVIAL(info) << "Finishing session"; viam::b_continue_session = false; @@ -51,6 +53,7 @@ int main(int argc, char **argv) { builder.AddListeningPort(slamService.slam_port, grpc::InsecureServerCredentials(), selected_port.get()); + builder.SetMaxSendMessageSize(maxMessageSize); builder.RegisterService(&slamService); // Start the SLAM gRPC server From 45bb75b7a40adcc8158c16c6dc295ccd81c5ffde Mon Sep 17 00:00:00 2001 From: jeremyhyde-viam <92594844+jeremyhyde-viam@users.noreply.github.com> Date: Fri, 9 Dec 2022 17:53:25 -0500 Subject: [PATCH 2/6] make format --- slam-libraries/viam-cartographer/src/main.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/slam-libraries/viam-cartographer/src/main.cc b/slam-libraries/viam-cartographer/src/main.cc index 0e52a95a..8f761709 100644 --- a/slam-libraries/viam-cartographer/src/main.cc +++ b/slam-libraries/viam-cartographer/src/main.cc @@ -11,7 +11,8 @@ #include "slam_service/config.h" #include "slam_service/slam_service.h" -const int maxMessageSize = 32 * 1024 * 1024;; +const int maxMessageSize = 32 * 1024 * 1024; +; void exit_loop_handler(int s) { LOG(INFO) << "Finishing session.\n"; From 84a1e6f9e42e5baf62ab86bddfc08b9a8e8f9f07 Mon Sep 17 00:00:00 2001 From: jeremyhyde-viam <92594844+jeremyhyde-viam@users.noreply.github.com> Date: Fri, 9 Dec 2022 17:58:16 -0500 Subject: [PATCH 3/6] clean --- slam-libraries/viam-cartographer/src/main.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/slam-libraries/viam-cartographer/src/main.cc b/slam-libraries/viam-cartographer/src/main.cc index 8f761709..decf68c0 100644 --- a/slam-libraries/viam-cartographer/src/main.cc +++ b/slam-libraries/viam-cartographer/src/main.cc @@ -12,7 +12,6 @@ #include "slam_service/slam_service.h" const int maxMessageSize = 32 * 1024 * 1024; -; void exit_loop_handler(int s) { LOG(INFO) << "Finishing session.\n"; From deebcd1df1e0c5fce5529d52be7f9d04b7858326 Mon Sep 17 00:00:00 2001 From: jeremyhyde-viam <92594844+jeremyhyde-viam@users.noreply.github.com> Date: Mon, 12 Dec 2022 15:00:46 -0500 Subject: [PATCH 4/6] add comment for max size --- slam-libraries/viam-cartographer/src/main.cc | 7 ++++--- slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc | 6 +++++- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/slam-libraries/viam-cartographer/src/main.cc b/slam-libraries/viam-cartographer/src/main.cc index decf68c0..3b069fdc 100644 --- a/slam-libraries/viam-cartographer/src/main.cc +++ b/slam-libraries/viam-cartographer/src/main.cc @@ -11,8 +11,6 @@ #include "slam_service/config.h" #include "slam_service/slam_service.h" -const int maxMessageSize = 32 * 1024 * 1024; - void exit_loop_handler(int s) { LOG(INFO) << "Finishing session.\n"; viam::b_continue_session = false; @@ -40,7 +38,10 @@ int main(int argc, char** argv) { builder.AddListeningPort(slamService.port, grpc::InsecureServerCredentials(), selected_port.get()); - builder.SetMaxSendMessageSize(maxMessageSize); + // 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 bfa581b6..b057ce73 100644 --- a/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc +++ b/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc @@ -53,7 +53,11 @@ int main(int argc, char **argv) { builder.AddListeningPort(slamService.slam_port, grpc::InsecureServerCredentials(), selected_port.get()); - builder.SetMaxSendMessageSize(maxMessageSize); + + // 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 From 2e716f0c38775d62aaceff6bf12f12bc59d6fa75 Mon Sep 17 00:00:00 2001 From: jeremyhyde-viam <92594844+jeremyhyde-viam@users.noreply.github.com> Date: Mon, 12 Dec 2022 15:02:22 -0500 Subject: [PATCH 5/6] forgot one --- slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc | 2 -- 1 file changed, 2 deletions(-) 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 b057ce73..9e5b31f5 100644 --- a/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc +++ b/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc @@ -18,8 +18,6 @@ using grpc::Server; using grpc::ServerBuilder; using SlamPtr = std::unique_ptr; -const int maxMessageSize = 32 * 1024 * 1024; - void exit_loop_handler(int s) { BOOST_LOG_TRIVIAL(info) << "Finishing session"; viam::b_continue_session = false; From e9c2c3425760166b2dd9fb3f4b9ecb2ab9b60426 Mon Sep 17 00:00:00 2001 From: jeremyhyde-viam <92594844+jeremyhyde-viam@users.noreply.github.com> Date: Mon, 12 Dec 2022 15:08:57 -0500 Subject: [PATCH 6/6] make format --- slam-libraries/viam-cartographer/src/main.cc | 6 +++--- slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/slam-libraries/viam-cartographer/src/main.cc b/slam-libraries/viam-cartographer/src/main.cc index 3b069fdc..90d80d1a 100644 --- a/slam-libraries/viam-cartographer/src/main.cc +++ b/slam-libraries/viam-cartographer/src/main.cc @@ -38,9 +38,9 @@ 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. + // 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); 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 9e5b31f5..f3973ad6 100644 --- a/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc +++ b/slam-libraries/viam-orb-slam3/orbslam_server_v1_main.cc @@ -52,9 +52,9 @@ int main(int argc, char **argv) { 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. + // 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);