Skip to content

Commit

Permalink
change namespace from to
Browse files Browse the repository at this point in the history
Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>
  • Loading branch information
MasatoSaeki committed Jul 22, 2024
1 parent d7527e0 commit 5b820c6
Show file tree
Hide file tree
Showing 48 changed files with 136 additions and 136 deletions.
2 changes: 1 addition & 1 deletion perception/autoware_lidar_centerpoint/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
)

rclcpp_components_register_node(${PROJECT_NAME}_component
PLUGIN "autoware::centerpoint::LidarCenterPointNode"
PLUGIN "autoware::lidar_centerpoint::LidarCenterPointNode"
EXECUTABLE ${PROJECT_NAME}_node
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <cstddef>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
class CenterPointConfig
{
Expand Down Expand Up @@ -132,6 +132,6 @@ class CenterPointConfig
std::size_t down_grid_size_y_ = grid_size_y_ / downsample_factor_;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <utility>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
class NetworkParam
{
Expand Down Expand Up @@ -107,6 +107,6 @@ class CenterPointTRT
cuda::unique_ptr<unsigned int[]> num_voxels_d_{nullptr};
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

class DetectionClassRemapper
Expand All @@ -42,6 +42,6 @@ class DetectionClassRemapper
int num_labels_;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__DETECTION_CLASS_REMAPPER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
class VoxelEncoderTRT : public TensorRTWrapper
{
Expand Down Expand Up @@ -48,6 +48,6 @@ class HeadTRT : public TensorRTWrapper
std::vector<std::size_t> out_channel_sizes_;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,14 @@
#include "cuda.h"
#include "cuda_runtime_api.h"

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
cudaError_t scatterFeatures_launch(
const float * pillar_features, const int * coords, const unsigned int * num_pillars,
const std::size_t max_voxel_size, const std::size_t encoder_out_feature_size,
const std::size_t grid_size_x, const std::size_t grid_size_y, float * scattered_features,
cudaStream_t stream);

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <memory>
#include <string>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

class TensorRTWrapper
Expand Down Expand Up @@ -62,6 +62,6 @@ class TensorRTWrapper
tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine> engine_{nullptr};
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include <string>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

class LidarCenterPointNode : public rclcpp::Node
Expand Down Expand Up @@ -69,6 +69,6 @@ class LidarCenterPointNode : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,14 @@
#include "autoware/lidar_centerpoint/utils.hpp"
#include "thrust/device_vector.h"

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
// Non-maximum suppression (NMS) uses the distance on the xy plane instead of
// intersection over union (IoU) to suppress overlapped objects.
std::size_t circleNMS(
thrust::device_vector<Box3D> & boxes3d, const float distance_threshold,
thrust::device_vector<bool> & keep_mask, cudaStream_t stream);

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
using autoware_perception_msgs::msg::DetectedObject;

Expand Down Expand Up @@ -76,6 +76,6 @@ class NonMaximumSuppression
std::vector<bool> target_class_mask_{};
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__POSTPROCESS__NON_MAXIMUM_SUPPRESSION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
class PostProcessCUDA
{
Expand All @@ -41,6 +41,6 @@ class PostProcessCUDA
thrust::device_vector<float> yaw_norm_thresholds_d_;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__POSTPROCESS__POSTPROCESS_KERNEL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

#include "autoware/lidar_centerpoint/cuda_utils.hpp"

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
class DensificationParam
{
Expand Down Expand Up @@ -89,6 +89,6 @@ class PointCloudDensification
std::list<PointCloudWithTransform> pointcloud_cache_;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__PREPROCESS__POINTCLOUD_DENSIFICATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "cuda.h"
#include "cuda_runtime_api.h"

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
cudaError_t generateSweepPoints_launch(
const float * input_points, size_t points_size, int input_point_step, float time_lag,
Expand All @@ -41,6 +41,6 @@ cudaError_t generateFeatures_launch(
const float voxel_size_y, const float voxel_size_z, const float range_min_x,
const float range_min_y, const float range_min_z, float * features, cudaStream_t stream);

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__PREPROCESS__PREPROCESS_KERNEL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <memory>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
class VoxelGeneratorTemplate
{
Expand Down Expand Up @@ -54,6 +54,6 @@ class VoxelGenerator : public VoxelGeneratorTemplate
std::size_t generateSweepPoints(float * d_points, cudaStream_t stream) override;
};

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__PREPROCESS__VOXEL_GENERATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

void box3DToDetectedObject(
Expand All @@ -39,6 +39,6 @@ std::array<double, 36> convertTwistCovarianceMatrix(const Box3D & box3d);

bool isCarLikeVehicleLabel(const uint8_t label);

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__ROS_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <cstddef>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
struct Box3D
{
Expand Down Expand Up @@ -49,6 +49,6 @@ struct Box3D
// cspell: ignore divup
std::size_t divup(const std::size_t a, const std::size_t b);

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint

#endif // AUTOWARE__LIDAR_CENTERPOINT__UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

<group if="$(var use_pointcloud_container)">
<load_composable_node target="$(var pointcloud_container_name)">
<composable_node pkg="autoware_lidar_centerpoint" plugin="autoware::centerpoint::LidarCenterPointNode" name="lidar_centerpoint">
<composable_node pkg="autoware_lidar_centerpoint" plugin="autoware::lidar_centerpoint::LidarCenterPointNode" name="lidar_centerpoint">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param from="$(var model_param_path)" allow_substs="true"/>
Expand Down
4 changes: 2 additions & 2 deletions perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <string>
#include <vector>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
CenterPointTRT::CenterPointTRT(
const NetworkParam & encoder_param, const NetworkParam & head_param,
Expand Down Expand Up @@ -200,4 +200,4 @@ void CenterPointTRT::postProcess(std::vector<Box3D> & det_boxes3d)
}
}

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "autoware/lidar_centerpoint/detection_class_remapper.hpp"

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

void DetectionClassRemapper::setParameters(
Expand Down Expand Up @@ -68,4 +68,4 @@ void DetectionClassRemapper::mapClasses(autoware_perception_msgs::msg::DetectedO
}
}

Check warning on line 69 in perception/autoware_lidar_centerpoint/lib/detection_class_remapper.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

DetectionClassRemapper::mapClasses has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "autoware/lidar_centerpoint/network/network_trt.hpp"

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
bool VoxelEncoderTRT::setProfile(
nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network,
Expand Down Expand Up @@ -79,4 +79,4 @@ bool HeadTRT::setProfile(
return true;
}

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ namespace
const std::size_t THREADS_PER_BLOCK = 32;
} // namespace

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
__global__ void scatterFeatures_kernel(
const float * pillar_features, const int * coords, const unsigned int * num_pillars,
Expand Down Expand Up @@ -64,4 +64,4 @@ cudaError_t scatterFeatures_launch(
return cudaGetLastError();
}

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <memory>
#include <string>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{
TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config) : config_(config)
{
Expand Down Expand Up @@ -164,4 +164,4 @@ bool TensorRTWrapper::loadEngine(const std::string & engine_path)
return true;
}

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace
const std::size_t THREADS_PER_BLOCK_NMS = 16;
} // namespace

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

__device__ inline float dist2dPow(const Box3D * a, const Box3D * b)
Expand Down Expand Up @@ -140,4 +140,4 @@ std::size_t circleNMS(
return num_to_keep;
}

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <object_recognition_utils/geometry.hpp>
#include <object_recognition_utils/object_recognition_utils.hpp>

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

void NonMaximumSuppression::setParameters(const NMSParams & params)
Expand Down Expand Up @@ -101,4 +101,4 @@ std::vector<DetectedObject> NonMaximumSuppression::apply(

return output_objects;
}
} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ namespace
const std::size_t THREADS_PER_BLOCK = 32;
} // namespace

namespace autoware::centerpoint
namespace autoware::lidar_centerpoint
{

struct is_score_greater
Expand Down Expand Up @@ -192,4 +192,4 @@ cudaError_t PostProcessCUDA::generateDetectedBoxes3D_launch(
return cudaGetLastError();
}

} // namespace autoware::centerpoint
} // namespace autoware::lidar_centerpoint
Loading

0 comments on commit 5b820c6

Please sign in to comment.