Skip to content

Commit

Permalink
refactor(euclidean_cluster)!: fix namespace and directory structure (#…
Browse files Browse the repository at this point in the history
…7887)

* refactor: update include paths for euclidean_cluster code

Signed-off-by: Taekjin LEE <[email protected]>

refactor: fix namespace

Signed-off-by: Taekjin LEE <[email protected]>

chore: update include paths for euclidean_cluster code

Signed-off-by: Taekjin LEE <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: Taekjin LEE <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and KhalilSelyan committed Jul 22, 2024
1 parent c0f191a commit ebb1aaf
Show file tree
Hide file tree
Showing 18 changed files with 62 additions and 64 deletions.
3 changes: 0 additions & 3 deletions perception/detection_by_tracker/src/debugger/debugger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@

#include "autoware/universe_utils/ros/debug_publisher.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"
#include "euclidean_cluster/euclidean_cluster.hpp"
#include "euclidean_cluster/utils.hpp"
#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options)
setMaxSearchRange();

shape_estimator_ = std::make_shared<autoware::shape_estimation::ShapeEstimator>(true, true);
cluster_ = std::make_shared<euclidean_cluster::VoxelGridBasedEuclideanCluster>(
cluster_ = std::make_shared<autoware::euclidean_cluster::VoxelGridBasedEuclideanCluster>(
false, 10, 10000, 0.7, 0.3, 0);
debugger_ = std::make_shared<Debugger>(this);
published_time_publisher_ =
Expand Down Expand Up @@ -277,7 +277,7 @@ float DetectionByTracker::optimizeUnderSegmentedObject(
const auto & label = target_object.classification.front().label;

// initialize clustering parameters
euclidean_cluster::VoxelGridBasedEuclideanCluster cluster(
autoware::euclidean_cluster::VoxelGridBasedEuclideanCluster cluster(
false, 4, 10000, initial_cluster_range, initial_voxel_size, 0);

// convert to pcl
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
#ifndef DETECTION_BY_TRACKER_NODE_HPP_
#define DETECTION_BY_TRACKER_NODE_HPP_

#include "autoware/euclidean_cluster/euclidean_cluster.hpp"
#include "autoware/euclidean_cluster/utils.hpp"
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
#include "autoware/shape_estimation/shape_estimator.hpp"
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
#include "debugger/debugger.hpp"
#include "euclidean_cluster/euclidean_cluster.hpp"
#include "euclidean_cluster/utils.hpp"
#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
#include "tracker/tracker_handler.hpp"
#include "utils/utils.hpp"

Expand Down Expand Up @@ -69,7 +69,7 @@ class DetectionByTracker : public rclcpp::Node

TrackerHandler tracker_handler_;
std::shared_ptr<autoware::shape_estimation::ShapeEstimator> shape_estimator_;
std::shared_ptr<euclidean_cluster::EuclideanClusterInterface> cluster_;
std::shared_ptr<autoware::euclidean_cluster::EuclideanClusterInterface> cluster_;
std::shared_ptr<Debugger> debugger_;
std::map<uint8_t, int> max_search_distance_for_merger_;
std::map<uint8_t, int> max_search_distance_for_divider_;
Expand Down
28 changes: 14 additions & 14 deletions perception/euclidean_cluster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,45 +13,45 @@ include_directories(
${PCL_INCLUDE_DIRS}
)

ament_auto_add_library(cluster_lib SHARED
lib/utils.cpp
ament_auto_add_library(${PROJECT_NAME}_lib SHARED
lib/euclidean_cluster.cpp
lib/voxel_grid_based_euclidean_cluster.cpp
lib/utils.cpp
)

target_link_libraries(cluster_lib
target_link_libraries(${PROJECT_NAME}_lib
${PCL_LIBRARIES}
)

target_include_directories(cluster_lib
target_include_directories(${PROJECT_NAME}_lib
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)

ament_auto_add_library(euclidean_cluster_node_core SHARED
ament_auto_add_library(${PROJECT_NAME}_node_core SHARED
src/euclidean_cluster_node.cpp
)
target_link_libraries(euclidean_cluster_node_core
target_link_libraries(${PROJECT_NAME}_node_core
${PCL_LIBRARIES}
cluster_lib
${PROJECT_NAME}_lib
)

rclcpp_components_register_node(euclidean_cluster_node_core
PLUGIN "euclidean_cluster::EuclideanClusterNode"
rclcpp_components_register_node(${PROJECT_NAME}_node_core
PLUGIN "autoware::euclidean_cluster::EuclideanClusterNode"
EXECUTABLE euclidean_cluster_node
)

ament_auto_add_library(voxel_grid_based_euclidean_cluster_node_core SHARED
ament_auto_add_library(${PROJECT_NAME}_voxel_grid_node_core SHARED
src/voxel_grid_based_euclidean_cluster_node.cpp
)
target_link_libraries(voxel_grid_based_euclidean_cluster_node_core
target_link_libraries(${PROJECT_NAME}_voxel_grid_node_core
${PCL_LIBRARIES}
cluster_lib
${PROJECT_NAME}_lib
)

rclcpp_components_register_node(voxel_grid_based_euclidean_cluster_node_core
PLUGIN "euclidean_cluster::VoxelGridBasedEuclideanClusterNode"
rclcpp_components_register_node(${PROJECT_NAME}_voxel_grid_node_core
PLUGIN "autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode"
EXECUTABLE voxel_grid_based_euclidean_cluster_node
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@

#pragma once

#include "euclidean_cluster/euclidean_cluster_interface.hpp"
#include "euclidean_cluster/utils.hpp"
#include "autoware/euclidean_cluster/euclidean_cluster_interface.hpp"
#include "autoware/euclidean_cluster/utils.hpp"

#include <pcl/point_types.h>

#include <vector>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
class EuclideanCluster : public EuclideanClusterInterface
{
Expand All @@ -42,4 +42,4 @@ class EuclideanCluster : public EuclideanClusterInterface
float tolerance_;
};

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

#include <vector>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
class EuclideanClusterInterface
{
Expand Down Expand Up @@ -54,4 +54,4 @@ class EuclideanClusterInterface
int max_cluster_size_;
};

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

#include <vector>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud);
void convertPointCloudClusters2Msg(
Expand All @@ -37,4 +37,4 @@ void convertPointCloudClusters2Msg(
void convertObjectMsg2SensorMsg(
const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input,
sensor_msgs::msg::PointCloud2 & output);
} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,15 @@

#pragma once

#include "euclidean_cluster/euclidean_cluster_interface.hpp"
#include "euclidean_cluster/utils.hpp"
#include "autoware/euclidean_cluster/euclidean_cluster_interface.hpp"
#include "autoware/euclidean_cluster/utils.hpp"

#include <pcl/filters/voxel_grid.h>
#include <pcl/point_types.h>

#include <vector>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
class VoxelGridBasedEuclideanCluster : public EuclideanClusterInterface
{
Expand Down Expand Up @@ -52,4 +52,4 @@ class VoxelGridBasedEuclideanCluster : public EuclideanClusterInterface
int min_points_number_per_voxel_;
};

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def load_composable_node_param(param_path):

use_low_height_euclidean_component = ComposableNode(
package=pkg,
plugin="euclidean_cluster::EuclideanClusterNode",
plugin="autoware::euclidean_cluster::EuclideanClusterNode",
name=AnonName("euclidean_cluster"),
remappings=[
("input", "low_height/pointcloud"),
Expand All @@ -60,7 +60,7 @@ def load_composable_node_param(param_path):

disuse_low_height_euclidean_component = ComposableNode(
package=pkg,
plugin="euclidean_cluster::EuclideanClusterNode",
plugin="autoware::euclidean_cluster::EuclideanClusterNode",
name=AnonName("euclidean_cluster"),
remappings=[
("input", LaunchConfiguration("input_pointcloud")),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def load_composable_node_param(param_path):
use_low_height_euclidean_component = ComposableNode(
package=pkg,
namespace=ns,
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
plugin="autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
name="euclidean_cluster",
remappings=[
("input", "low_height/pointcloud"),
Expand All @@ -61,7 +61,7 @@ def load_composable_node_param(param_path):
disuse_low_height_euclidean_component = ComposableNode(
package=pkg,
namespace=ns,
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
plugin="autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
name="euclidean_cluster",
remappings=[
("input", LaunchConfiguration("input_pointcloud")),
Expand Down
6 changes: 3 additions & 3 deletions perception/euclidean_cluster/lib/euclidean_cluster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "euclidean_cluster/euclidean_cluster.hpp"
#include "autoware/euclidean_cluster/euclidean_cluster.hpp"

#include <pcl/kdtree/kdtree.h>
#include <pcl/segmentation/extract_clusters.h>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
EuclideanCluster::EuclideanCluster()
{
Expand Down Expand Up @@ -93,4 +93,4 @@ bool EuclideanCluster::cluster(
return true;
}

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
6 changes: 3 additions & 3 deletions perception/euclidean_cluster/lib/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,15 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "euclidean_cluster/utils.hpp"
#include "autoware/euclidean_cluster/utils.hpp"

#include <autoware_perception_msgs/msg/object_classification.hpp>
#include <sensor_msgs/msg/point_field.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tier4_perception_msgs/msg/detected_object_with_feature.hpp>
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud)
{
Expand Down Expand Up @@ -128,4 +128,4 @@ void convertObjectMsg2SensorMsg(
output.height = 1;
output.is_dense = false;
}
} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"

#include <pcl/kdtree/kdtree.h>
#include <pcl/segmentation/extract_clusters.h>

#include <unordered_map>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
VoxelGridBasedEuclideanCluster::VoxelGridBasedEuclideanCluster()
{
Expand Down Expand Up @@ -166,4 +166,4 @@ bool VoxelGridBasedEuclideanCluster::cluster(
return true;
}

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
8 changes: 4 additions & 4 deletions perception/euclidean_cluster/src/euclidean_cluster_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@

#include "euclidean_cluster_node.hpp"

#include "euclidean_cluster/utils.hpp"
#include "autoware/euclidean_cluster/utils.hpp"

#include <vector>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
EuclideanClusterNode::EuclideanClusterNode(const rclcpp::NodeOptions & options)
: Node("euclidean_cluster_node", options)
Expand Down Expand Up @@ -86,8 +86,8 @@ void EuclideanClusterNode::onPointCloud(
}
}

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster

#include <rclcpp_components/register_node_macro.hpp>

RCLCPP_COMPONENTS_REGISTER_NODE(euclidean_cluster::EuclideanClusterNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::euclidean_cluster::EuclideanClusterNode)
7 changes: 4 additions & 3 deletions perception/euclidean_cluster/src/euclidean_cluster_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#pragma once

#include "euclidean_cluster/euclidean_cluster.hpp"
#include "autoware/euclidean_cluster/euclidean_cluster.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
Expand All @@ -26,7 +26,8 @@

#include <chrono>
#include <memory>
namespace euclidean_cluster

namespace autoware::euclidean_cluster
{
class EuclideanClusterNode : public rclcpp::Node
{
Expand All @@ -45,4 +46,4 @@ class EuclideanClusterNode : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
};

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@

#include "voxel_grid_based_euclidean_cluster_node.hpp"

#include "euclidean_cluster/utils.hpp"
#include "autoware/euclidean_cluster/utils.hpp"

#include <vector>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
VoxelGridBasedEuclideanClusterNode::VoxelGridBasedEuclideanClusterNode(
const rclcpp::NodeOptions & options)
Expand Down Expand Up @@ -89,8 +89,8 @@ void VoxelGridBasedEuclideanClusterNode::onPointCloud(
}
}

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster

#include <rclcpp_components/register_node_macro.hpp>

RCLCPP_COMPONENTS_REGISTER_NODE(euclidean_cluster::VoxelGridBasedEuclideanClusterNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode)
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#pragma once

#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
Expand All @@ -26,7 +26,7 @@

#include <memory>

namespace euclidean_cluster
namespace autoware::euclidean_cluster
{
class VoxelGridBasedEuclideanClusterNode : public rclcpp::Node
{
Expand All @@ -45,4 +45,4 @@ class VoxelGridBasedEuclideanClusterNode : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
};

} // namespace euclidean_cluster
} // namespace autoware::euclidean_cluster
Loading

0 comments on commit ebb1aaf

Please sign in to comment.