@@ -45,12 +45,12 @@ std::vector<float> cast_to_float(const std::vector<double> & double_vector)
4545StreamPetrNode::StreamPetrNode (const rclcpp::NodeOptions & node_options)
4646: Node(" autoware_camera_streampetr" , node_options),
4747 logger_name_ (" camera_streampetr" ),
48- multithreading_(declare_parameter<bool >(" multithreading" , false )),
48+ multithreading_(declare_parameter<bool >(" multithreading" )),
4949 tf_buffer_(this ->get_clock ()),
5050 tf_listener_(tf_buffer_),
51- rois_number_(static_cast <size_t >(declare_parameter<int >(" model_params.rois_number" , 6 ))),
52- max_camera_time_diff_(declare_parameter<float >(" max_camera_time_diff" , 0 . 15f )),
53- anchor_camera_id_(declare_parameter<int >(" anchor_camera_id" , 0 )),
51+ rois_number_(static_cast <size_t >(declare_parameter<int >(" model_params.rois_number" ))),
52+ max_camera_time_diff_(declare_parameter<float >(" max_camera_time_diff" )),
53+ anchor_camera_id_(declare_parameter<int >(" anchor_camera_id" )),
5454 debug_mode_(declare_parameter<bool >(" debug_mode" ))
5555{
5656 RCLCPP_INFO (
@@ -67,15 +67,15 @@ StreamPetrNode::StreamPetrNode(const rclcpp::NodeOptions & node_options)
6767 declare_parameter<std::string>(" model_params.position_embedding_path" );
6868
6969 const std::string backbone_engine_path =
70- declare_parameter<std::string>(" model_params.backbone_engine_path" , " " );
70+ declare_parameter<std::string>(" model_params.backbone_engine_path" );
7171 const std::string head_engine_path =
72- declare_parameter<std::string>(" model_params.head_engine_path" , " " );
72+ declare_parameter<std::string>(" model_params.head_engine_path" );
7373 const std::string position_embedding_engine_path =
74- declare_parameter<std::string>(" model_params.position_embedding_engine_path" , " " );
74+ declare_parameter<std::string>(" model_params.position_embedding_engine_path" );
7575
7676 const std::string trt_precision = declare_parameter<std::string>(" model_params.trt_precision" );
7777 const uint64_t workspace_size =
78- 1ULL << declare_parameter<int >(" model_params.workspace_size" , 32 ); // Default 4GB
78+ 1ULL << declare_parameter<int >(" model_params.workspace_size" ); // Default 4GB
7979
8080 const bool use_temporal = declare_parameter<bool >(" model_params.use_temporal" );
8181 const double search_distance_2d =
@@ -92,8 +92,8 @@ StreamPetrNode::StreamPetrNode(const rclcpp::NodeOptions & node_options)
9292 declare_parameter<std::vector<double >>(" post_process_params.yaw_norm_thresholds" );
9393 const std::vector<float > detection_range =
9494 cast_to_float (declare_parameter<std::vector<double >>(" model_params.detection_range" ));
95- const int pre_memory_length = declare_parameter<int >(" model_params.pre_memory_length" , 1024 );
96- const int post_memory_length = declare_parameter<int >(" model_params.post_memory_length" , 1280 );
95+ const int pre_memory_length = declare_parameter<int >(" model_params.pre_memory_length" );
96+ const int post_memory_length = declare_parameter<int >(" model_params.post_memory_length" );
9797
9898 NetworkConfig network_config{
9999 logger_name_,
0 commit comments