Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add lidar apollo instance segmentation package #115

Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
39 commits
Select commit Hold shift + click to select a range
ea00eb5
release v0.4.0
mitsudome-r Sep 18, 2020
d985824
check if gdown command exists (#707)
harihitode Jul 21, 2020
577b8a6
Fix/cublas dependency (#849)
yukkysaito Aug 28, 2020
3641de2
remove ROS1 packages temporarily
mitsudome-r Sep 29, 2020
d857275
Revert "remove ROS1 packages temporarily"
mitsudome-r Oct 8, 2020
6a13768
add COLCON_IGNORE to ros1 packages
mitsudome-r Oct 8, 2020
0744066
Rename launch files to launch.xml (#28)
nnmm Oct 15, 2020
d561a63
Port lidar apollo instance segmentation (#98)
mitsudome-r Nov 19, 2020
c719a1e
Rename h files to hpp (#142)
nnmm Dec 3, 2020
378387a
Adjust copyright notice on 532 out of 699 source files (#143)
nnmm Dec 3, 2020
7113d6d
Use quotes for includes where appropriate (#144)
nnmm Dec 7, 2020
40d3d14
Run uncrustify on the entire Pilot.Auto codebase (#151)
nnmm Dec 8, 2020
7197a56
[tensorrt_yolo3][lidar_apollo_instance_segmentation] fix objection re…
mitsudome-r Dec 15, 2020
697eae8
adding linters to lidar_apollo_instance_segmentation (#173)
nik-tier4 Dec 23, 2020
b55eeb4
Ros2 v0.8.0 lidar apollo instance segmentation (#256)
wep21 Jan 17, 2021
a0eb299
add use_sim-time option (#454)
tkimura4 Mar 26, 2021
487d5cf
Format launch files (#1219)
kenji-miyake Mar 30, 2021
6007d0e
fix reliability (#1222)
tkimura4 Apr 1, 2021
6306688
Unify Apache-2.0 license name (#1242)
kmiya Apr 15, 2021
bc2c48b
Remove use_sim_time for set_parameter (#1260)
wep21 Apr 26, 2021
50110e2
Perception components (#1368)
wep21 May 26, 2021
814fccc
[lidar_apollo_instance_segmentation]: Change subscriber queue size(5 …
wep21 Jul 6, 2021
8f63b47
Add pre-commit (#1560)
KeisukeShima Jul 19, 2021
d2ae4a3
Fix build error with TensorRT v8 (#1612)
wep21 Jul 19, 2021
5b0e31f
Add markdownlint and prettier (#1661)
kenji-miyake Jul 20, 2021
2032d98
Fix MD029 (#1813)
kenji-miyake Aug 9, 2021
45a0eb1
Fix -Wunused-parameter (#1836)
kenji-miyake Aug 14, 2021
0a094ea
suppress warnings in perception directory (#1866)
h-ohta Aug 16, 2021
a946fc1
Ignore -Wdeprecated-declarations in lidar_apollo_instance_segmentatio…
kenji-miyake Aug 17, 2021
ef7fe71
Refactor shape estimation for detection by tracking (#1861)
yukkysaito Aug 30, 2021
9cebdb1
add sort-package-xml hook in pre-commit (#1881)
KeisukeShima Sep 9, 2021
6312820
Detection by tracker (#1910)
yukkysaito Sep 29, 2021
58ffe4d
Change formatter to clang-format and black (#2332)
kenji-miyake Nov 2, 2021
c78382e
Add COLCON_IGNORE (#500)
kenji-miyake Nov 4, 2021
63c9543
Port lidar apollo instance segmentation to .auto (#548)
wep21 Nov 10, 2021
83568cc
Update document for lidar apollo instance segmentation (#597)
wep21 Nov 15, 2021
99ad02c
Sync .auto branch with the latest branch in internal repository (#691)
wep21 Nov 18, 2021
9513dca
Merge branch 'tier4/proposal' into 1-add-lidar-apollo-instance-segmen…
1222-takeshi Dec 6, 2021
3bc0cb0
Merge branch 'tier4/proposal' into 1-add-lidar-apollo-instance-segmen…
1222-takeshi Dec 6, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
suppress warnings in perception directory (#1866)
* add maybe unused

* add Werror
  • Loading branch information
h-ohta authored and YoheiMishina committed Dec 1, 2021
commit 0a094ea7147f5e581666a7a0d924f13b8f8864f9
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
set(CMAKE_CXX_EXTENSIONS OFF)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
endif()
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -O3")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D_MWAITXINTRIN_H_INCLUDED")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ T * DisjointSetFind(T * x)
}

template<class T>
void DisjointSetMerge(T * x, const T * y)
void DisjointSetMerge([[maybe_unused]] T * x, [[maybe_unused]] const T * y)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@ FeatureMap::FeatureMap(const int width, const int height, const int range)
count_data = &(map_data[0]) + width * height * 2;
nonempty_data = &(map_data[0]) + width * height * 3;
}
void FeatureMap::initializeMap(std::vector<float> & map) {}
void FeatureMap::resetMap(std::vector<float> & map)
void FeatureMap::initializeMap([[maybe_unused]] std::vector<float> & map) {}
void FeatureMap::resetMap([[maybe_unused]] std::vector<float> & map)
{
const int size = width * height;
for (int i = 0; i < size; ++i) {
Expand All @@ -64,8 +64,8 @@ FeatureMapWithIntensity::FeatureMapWithIntensity(const int width, const int heig
mean_intensity_data = &(map_data[0]) + width * height * 4;
nonempty_data = &(map_data[0]) + width * height * 5;
}
void FeatureMapWithIntensity::initializeMap(std::vector<float> & map) {}
void FeatureMapWithIntensity::resetMap(std::vector<float> & map)
void FeatureMapWithIntensity::initializeMap([[maybe_unused]] std::vector<float> & map) {}
void FeatureMapWithIntensity::resetMap([[maybe_unused]] std::vector<float> & map)
{
const int size = width * height;
for (int i = 0; i < size; ++i) {
Expand All @@ -88,7 +88,7 @@ FeatureMapWithConstant::FeatureMapWithConstant(const int width, const int height
distance_data = &(map_data[0]) + width * height * 4;
nonempty_data = &(map_data[0]) + width * height * 5;
}
void FeatureMapWithConstant::initializeMap(std::vector<float> & map)
void FeatureMapWithConstant::initializeMap([[maybe_unused]] std::vector<float> & map)
{
for (int row = 0; row < height; ++row) {
for (int col = 0; col < width; ++col) {
Expand All @@ -106,7 +106,7 @@ void FeatureMapWithConstant::initializeMap(std::vector<float> & map)
}
}

void FeatureMapWithConstant::resetMap(std::vector<float> & map)
void FeatureMapWithConstant::resetMap([[maybe_unused]] std::vector<float> & map)
{
const int size = width * height;
for (int i = 0; i < size; ++i) {
Expand All @@ -130,7 +130,7 @@ FeatureMapWithConstantAndIntensity::FeatureMapWithConstantAndIntensity(
distance_data = &(map_data[0]) + width * height * 6;
nonempty_data = &(map_data[0]) + width * height * 7;
}
void FeatureMapWithConstantAndIntensity::initializeMap(std::vector<float> & map)
void FeatureMapWithConstantAndIntensity::initializeMap([[maybe_unused]] std::vector<float> & map)
{
for (int row = 0; row < height; ++row) {
for (int col = 0; col < width; ++col) {
Expand All @@ -148,7 +148,7 @@ void FeatureMapWithConstantAndIntensity::initializeMap(std::vector<float> & map)
}
}

void FeatureMapWithConstantAndIntensity::resetMap(std::vector<float> & map)
void FeatureMapWithConstantAndIntensity::resetMap([[maybe_unused]] std::vector<float> & map)
{
const int size = width * height;
for (int i = 0; i < size; ++i) {
Expand Down