diff --git a/include/ouster/os1.h b/include/ouster/os1.h index f6d77b30..8156eb6c 100644 --- a/include/ouster/os1.h +++ b/include/ouster/os1.h @@ -86,7 +86,7 @@ using PulseMode = pulse_mode_t; * @param window_rejection to reject short range data (true), or to accept short range data (false) * @note This function was added to configure advanced operation modes for Autoware */ -void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_str, bool window_rejection); +void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_str); } } diff --git a/src/os1.cpp b/src/os1.cpp index 2ff1661a..96e20359 100644 --- a/src/os1.cpp +++ b/src/os1.cpp @@ -25,10 +25,8 @@ using ns = std::chrono::nanoseconds; */ static OperationMode _operation_mode = ouster::OS1::MODE_1024x10; static PulseMode _pulse_mode = ouster::OS1::PULSE_STANDARD; -static bool _window_rejection = true; static std::string _operation_mode_str = ""; static std::string _pulse_mode_str = ""; -static std::string _window_rejection_str = ""; //---------------- struct client { @@ -249,10 +247,6 @@ std::shared_ptr init_client(const std::string& hostname, success &= do_cmd_chk("set_config_param", "pulse_mode " + _pulse_mode_str); do_configure = true; } - if (curr_window_rejection_str != _window_rejection_str) { - success &= do_cmd_chk("set_config_param", "window_rejection_enable " + _window_rejection_str); - do_configure = true; - } if (!success) return std::shared_ptr(); @@ -320,11 +314,10 @@ bool read_imu_packet(const client& cli, uint8_t* buf) { * @note Added to support advanced mode parameters configuration for Autoware */ //---------------- -void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_str, bool window_rejection) +void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_str) { _operation_mode_str = operation_mode_str; _pulse_mode_str = pulse_mode_str; - _window_rejection = window_rejection; _operation_mode = ouster::OS1::MODE_1024x10; if (_operation_mode_str == std::string("512x10")) { @@ -349,8 +342,6 @@ void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_ } else { std::cout << "Selected pulse mode " << _pulse_mode_str << " is invalid, using default mode \"STANDARD\"" << std::endl; } - - _window_rejection_str = ((_window_rejection) ? std::string("1") : std::string("0")); } //---------------- diff --git a/src/os1_node.cpp b/src/os1_node.cpp index 0dcb8a72..9f8d1da7 100644 --- a/src/os1_node.cpp +++ b/src/os1_node.cpp @@ -50,7 +50,6 @@ int main(int argc, char** argv) { auto pointcloud_mode = nh.param("pointcloud_mode", std::string("NATIVE")); auto operation_mode_str = nh.param("operation_mode", std::string("1024x10")); auto pulse_mode_str = nh.param("pulse_mode", std::string("STANDARD")); - auto window_rejection = nh.param("window_rejection", true); /** * @note Added to support Velodyne compatible pointcloud format for Autoware @@ -62,7 +61,7 @@ int main(int argc, char** argv) { * @note Added to support advanced mode parameters configuration for Autoware */ //defines the advanced parameters - ouster::OS1::set_advanced_params(operation_mode_str, pulse_mode_str, window_rejection); + ouster::OS1::set_advanced_params(operation_mode_str, pulse_mode_str); auto queue_size = 10; if (operation_mode_str == std::string("512x20") || operation_mode_str == std::string("1024x20")) { queue_size = 20;