Skip to content

Commit

Permalink
refactor(detected_object_validation)!: fix namespace and directory st…
Browse files Browse the repository at this point in the history
…ructure (autowarefoundation#7866)

* refactor: update include paths for detected object filters

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

* refactor: set proper namespace

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

* refactor: move utils to be shared

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

* refactor: remove unnecessary dependencies in detected_object_validation/package.xml

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

* chore: Override functions in pcl_validator.hpp

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

* style(pre-commit): autofix

* refactor: pcl_validator to obstacle_pointcloud_validator, ogm_validator to occupancy_grid_map_validator

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

---------

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
technolojin and pre-commit-ci[bot] authored Jul 8, 2024
1 parent 094f2e2 commit f28ccd8
Show file tree
Hide file tree
Showing 16 changed files with 153 additions and 112 deletions.
28 changes: 10 additions & 18 deletions perception/detected_object_validation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,8 @@ include_directories(
)

# Generate occupancy grid based validator exe file
set(OCCUPANCY_GRID_BASED_VALIDATOR_SRC
src/occupancy_grid_based_validator.cpp
)

ament_auto_add_library(occupancy_grid_based_validator SHARED
${OCCUPANCY_GRID_BASED_VALIDATOR_SRC}
src/occupancy_grid_map/occupancy_grid_map_validator.cpp
)

target_link_libraries(occupancy_grid_based_validator
Expand All @@ -42,12 +38,8 @@ target_link_libraries(occupancy_grid_based_validator
)

# Generate obstacle pointcloud based validator exe file
set(OBSTACLE_POINTCLOUD_BASED_VALIDATOR_SRC
src/obstacle_pointcloud_based_validator.cpp
)

ament_auto_add_library(obstacle_pointcloud_based_validator SHARED
${OBSTACLE_POINTCLOUD_BASED_VALIDATOR_SRC}
src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp
)

target_link_libraries(obstacle_pointcloud_based_validator
Expand All @@ -56,32 +48,32 @@ target_link_libraries(obstacle_pointcloud_based_validator
)

ament_auto_add_library(object_lanelet_filter SHARED
src/object_lanelet_filter.cpp
src/utils.cpp
src/lanelet_filter/lanelet_filter.cpp
lib/utils/utils.cpp
)

ament_auto_add_library(object_position_filter SHARED
src/object_position_filter.cpp
src/utils.cpp
src/position_filter/position_filter.cpp
lib/utils/utils.cpp
)

rclcpp_components_register_node(obstacle_pointcloud_based_validator
PLUGIN "obstacle_pointcloud_based_validator::ObstaclePointCloudBasedValidator"
PLUGIN "autoware::detected_object_validation::obstacle_pointcloud::ObstaclePointCloudBasedValidator"
EXECUTABLE obstacle_pointcloud_based_validator_node
)

rclcpp_components_register_node(object_lanelet_filter
PLUGIN "object_lanelet_filter::ObjectLaneletFilterNode"
PLUGIN "autoware::detected_object_validation::lanelet_filter::ObjectLaneletFilterNode"
EXECUTABLE object_lanelet_filter_node
)

rclcpp_components_register_node(object_position_filter
PLUGIN "object_position_filter::ObjectPositionFilterNode"
PLUGIN "autoware::detected_object_validation::position_filter::ObjectPositionFilterNode"
EXECUTABLE object_position_filter_node
)

rclcpp_components_register_node(occupancy_grid_based_validator
PLUGIN "occupancy_grid_based_validator::OccupancyGridBasedValidator"
PLUGIN "autoware::detected_object_validation::occupancy_grid_map::OccupancyGridBasedValidator"
EXECUTABLE occupancy_grid_based_validator_node
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
#define DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
#ifndef AUTOWARE__DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
#define AUTOWARE__DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_

#include <autoware_perception_msgs/msg/detected_objects.hpp>

#include <cstdint>

namespace autoware::detected_object_validation
{
namespace utils
{
struct FilterTargetLabel
Expand Down Expand Up @@ -48,5 +51,6 @@ inline bool hasBoundingBox(const autoware_perception_msgs::msg::DetectedObject &
}

} // namespace utils
} // namespace autoware::detected_object_validation

#endif // DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
#endif // AUTOWARE__DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

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

#include <autoware_perception_msgs/msg/object_classification.hpp>

namespace autoware::detected_object_validation
{
namespace utils
{
using Label = autoware_perception_msgs::msg::ObjectClassification;
Expand All @@ -27,4 +29,6 @@ bool FilterTargetLabel::isTarget(const uint8_t label) const
(label == Label::TRAILER && TRAILER) || (label == Label::MOTORCYCLE && MOTORCYCLE) ||
(label == Label::BICYCLE && BICYCLE) || (label == Label::PEDESTRIAN && PEDESTRIAN);
}

} // namespace utils
} // namespace autoware::detected_object_validation
3 changes: 0 additions & 3 deletions perception/detected_object_validation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,17 +22,14 @@
<depend>autoware_perception_msgs</depend>
<depend>autoware_test_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>message_filters</depend>
<depend>nav_msgs</depend>
<depend>object_recognition_utils</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_perception_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,22 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "detected_object_validation/detected_object_filter/object_lanelet_filter.hpp"
#include "lanelet_filter.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>
#include <object_recognition_utils/object_recognition_utils.hpp>
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware_lanelet2_extension/utility/message_conversion.hpp"
#include "autoware_lanelet2_extension/utility/query.hpp"
#include "object_recognition_utils/object_recognition_utils.hpp"

#include <boost/geometry/algorithms/convex_hull.hpp>
#include <boost/geometry/algorithms/disjoint.hpp>
#include <boost/geometry/algorithms/intersects.hpp>

#include <lanelet2_core/geometry/Polygon.h>

namespace object_lanelet_filter
namespace autoware::detected_object_validation
{
namespace lanelet_filter
{
ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & node_options)
: Node("object_lanelet_filter_node", node_options),
Expand Down Expand Up @@ -309,7 +311,9 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
return false;
}

} // namespace object_lanelet_filter
} // namespace lanelet_filter
} // namespace autoware::detected_object_validation

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(object_lanelet_filter::ObjectLaneletFilterNode)
RCLCPP_COMPONENTS_REGISTER_NODE(
autoware::detected_object_validation::lanelet_filter::ObjectLaneletFilterNode)
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_
#define DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_
#ifndef LANELET_FILTER__LANELET_FILTER_HPP_
#define LANELET_FILTER__LANELET_FILTER_HPP_

#include "detected_object_validation/utils/utils.hpp"
#include "autoware/detected_object_validation/utils/utils.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/ros/debug_publisher.hpp"
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
#include "autoware_lanelet2_extension/utility/utilities.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
#include <autoware_lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include "autoware_map_msgs/msg/lanelet_map_bin.hpp"
#include "autoware_perception_msgs/msg/detected_objects.hpp"

#include <lanelet2_core/Forward.h>
#include <tf2_ros/buffer.h>
Expand All @@ -33,7 +33,9 @@
#include <memory>
#include <string>

namespace object_lanelet_filter
namespace autoware::detected_object_validation
{
namespace lanelet_filter
{
using autoware::universe_utils::LinearRing2d;
using autoware::universe_utils::MultiPoint2d;
Expand Down Expand Up @@ -92,6 +94,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace object_lanelet_filter
} // namespace lanelet_filter
} // namespace autoware::detected_object_validation

#endif // DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_
#endif // LANELET_FILTER__LANELET_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,21 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_
#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_
#ifndef OBSTACLE_POINTCLOUD__DEBUGGER_HPP_
#define OBSTACLE_POINTCLOUD__DEBUGGER_HPP_

#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>

namespace obstacle_pointcloud_based_validator
namespace autoware::detected_object_validation
{
namespace obstacle_pointcloud
{
class Debugger
{
Expand Down Expand Up @@ -106,6 +108,8 @@ class Debugger
return pointcloud_xyz;
}
};
} // namespace obstacle_pointcloud_based_validator

#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_
} // namespace obstacle_pointcloud
} // namespace autoware::detected_object_validation

#endif // OBSTACLE_POINTCLOUD__DEBUGGER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp"
#define EIGEN_MPL2_ONLY

#include "obstacle_pointcloud_validator.hpp"

#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
#include <object_recognition_utils/object_recognition_utils.hpp>
Expand All @@ -25,11 +27,12 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#define EIGEN_MPL2_ONLY
#include <Eigen/Core>
#include <Eigen/Geometry>

namespace obstacle_pointcloud_based_validator
namespace autoware::detected_object_validation
{
namespace obstacle_pointcloud
{
namespace bg = boost::geometry;
using Shape = autoware_perception_msgs::msg::Shape;
Expand Down Expand Up @@ -369,8 +372,9 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
"debug/pipeline_latency_ms", pipeline_latency);
}

} // namespace obstacle_pointcloud_based_validator
} // namespace obstacle_pointcloud
} // namespace autoware::detected_object_validation

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(
obstacle_pointcloud_based_validator::ObstaclePointCloudBasedValidator)
autoware::detected_object_validation::obstacle_pointcloud::ObstaclePointCloudBasedValidator)
Original file line number Diff line number Diff line change
Expand Up @@ -13,17 +13,17 @@
// limitations under the License.

// NOLINTNEXTLINE(whitespace/line_length)
#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_
#ifndef OBSTACLE_POINTCLOUD__OBSTACLE_POINTCLOUD_VALIDATOR_HPP_
// NOLINTNEXTLINE(whitespace/line_length)
#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_
#define OBSTACLE_POINTCLOUD__OBSTACLE_POINTCLOUD_VALIDATOR_HPP_

#include "detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp"
#include "autoware/universe_utils/ros/debug_publisher.hpp"
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
#include "debugger.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>

#include <message_filters/subscriber.h>
Expand All @@ -42,7 +42,10 @@
#include <memory>
#include <optional>
#include <vector>
namespace obstacle_pointcloud_based_validator

namespace autoware::detected_object_validation
{
namespace obstacle_pointcloud
{

struct PointsNumThresholdParam
Expand Down Expand Up @@ -91,14 +94,17 @@ class Validator2D : public Validator

pcl::PointCloud<pcl::PointXYZ>::Ptr convertToXYZ(
const pcl::PointCloud<pcl::PointXY>::Ptr & pointcloud_xy);
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud()
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud() override
{
return convertToXYZ(neighbor_pointcloud_);
}

bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud);
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object);
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object);
bool setKdtreeInputCloud(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) override;
bool validate_object(
const autoware_perception_msgs::msg::DetectedObject & transformed_object) override;
std::optional<float> getMaxRadius(
const autoware_perception_msgs::msg::DetectedObject & object) override;
std::optional<size_t> getPointCloudWithinObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const pcl::PointCloud<pcl::PointXY>::Ptr neighbor_pointcloud);
Expand All @@ -112,13 +118,16 @@ class Validator3D : public Validator

public:
explicit Validator3D(PointsNumThresholdParam & points_num_threshold_param);
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud()
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud() override
{
return neighbor_pointcloud_;
}
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud);
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object);
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object);
bool setKdtreeInputCloud(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) override;
bool validate_object(
const autoware_perception_msgs::msg::DetectedObject & transformed_object) override;
std::optional<float> getMaxRadius(
const autoware_perception_msgs::msg::DetectedObject & object) override;
std::optional<size_t> getPointCloudWithinObject(
const autoware_perception_msgs::msg::DetectedObject & object,
const pcl::PointCloud<pcl::PointXYZ>::Ptr neighbor_pointcloud);
Expand Down Expand Up @@ -154,7 +163,9 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects,
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_obstacle_pointcloud);
};
} // namespace obstacle_pointcloud_based_validator

} // namespace obstacle_pointcloud
} // namespace autoware::detected_object_validation

// NOLINTNEXTLINE(whitespace/line_length)
#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_
#endif // OBSTACLE_POINTCLOUD__OBSTACLE_POINTCLOUD_VALIDATOR_HPP_
Loading

0 comments on commit f28ccd8

Please sign in to comment.