Skip to content

Commit

Permalink
refactor(lidar_apollo_instance_segmentation)!: fix namespace and dire…
Browse files Browse the repository at this point in the history
…ctory structure (#7995)

* refactor: add autoware namespace prefix

Signed-off-by: ktro2828 <[email protected]>

* chore: update CODEOWNERS

Signed-off-by: ktro2828 <[email protected]>

* refactor: add `autoware` prefix

Signed-off-by: ktro2828 <[email protected]>

---------

Signed-off-by: ktro2828 <[email protected]>
  • Loading branch information
ktro2828 authored Jul 24, 2024
1 parent 28f9e7e commit 3e501cf
Show file tree
Hide file tree
Showing 27 changed files with 117 additions and 62 deletions.
4 changes: 3 additions & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,9 @@ perception/elevation_map_loader/** [email protected] shintaro.tomie@tier4
perception/autoware_euclidean_cluster/** [email protected] [email protected]
perception/autoware_ground_segmentation/** [email protected] [email protected] [email protected] [email protected] [email protected]
perception/autoware_image_projection_based_fusion/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
perception/lidar_apollo_instance_segmentation/** [email protected] [email protected]
perception/autowar_lidar_apollo_instance_segmentation/** [email protected] [email protected]
perception/lidar_apollo_segmentation_tvm/** [email protected] [email protected]
perception/lidar_apollo_segmentation_tvm_nodes/** [email protected] [email protected]
perception/autoware_lidar_centerpoint/** [email protected] [email protected]
perception/occupancy_grid_map_outlier_filter/** [email protected] [email protected] [email protected]
perception/probabilistic_occupancy_grid_map/** [email protected] [email protected] [email protected]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@
<group if="$(eval &quot;'$(var lidar_detection_model)'=='apollo'&quot;)">
<push-ros-namespace namespace="apollo"/>
<group>
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml">
<include file="$(find-pkg-share autoware_lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="output/objects" value="labeled_clusters"/>
</include>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_perception_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<exec_depend>autoware_euclidean_cluster</exec_depend>
<exec_depend>autoware_ground_segmentation</exec_depend>
<exec_depend>autoware_image_projection_based_fusion</exec_depend>
<exec_depend>autoware_lidar_apollo_instance_segmentation</exec_depend>
<exec_depend>autoware_map_based_prediction</exec_depend>
<exec_depend>autoware_multi_object_tracker</exec_depend>
<exec_depend>autoware_object_merger</exec_depend>
Expand All @@ -37,7 +38,6 @@
<exec_depend>autoware_tracking_object_merger</exec_depend>
<exec_depend>elevation_map_loader</exec_depend>
<exec_depend>image_transport_decompressor</exec_depend>
<exec_depend>lidar_apollo_instance_segmentation</exec_depend>
<exec_depend>occupancy_grid_map_outlier_filter</exec_depend>
<exec_depend>pointcloud_to_laserscan</exec_depend>
<exec_depend>probabilistic_occupancy_grid_map</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.17)
project(lidar_apollo_instance_segmentation)
project(autoware_lidar_apollo_instance_segmentation)

find_package(ament_cmake REQUIRED)
find_package(autoware_perception_msgs REQUIRED)
Expand Down Expand Up @@ -74,7 +74,7 @@ install(TARGETS ${PROJECT_NAME}
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "lidar_apollo_instance_segmentation::LidarInstanceSegmentationNode"
PLUGIN "autoware::lidar_apollo_instance_segmentation::LidarInstanceSegmentationNode"
EXECUTABLE ${PROJECT_NAME}_node
)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# lidar_apollo_instance_segmentation
# autoware_lidar_apollo_instance_segmentation

![Peek 2020-04-07 00-17](https://user-images.githubusercontent.com/8327598/78574862-92507d80-7865-11ea-9a2d-56d3453bdb7a.gif)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@
* limitations under the License.
*****************************************************************************/

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__CLUSTER2D_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__CLUSTER2D_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__CLUSTER2D_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__CLUSTER2D_HPP_

#include "disjoint_set.hpp"
#include "util.hpp"
Expand All @@ -60,6 +60,8 @@
#include <memory>
#include <vector>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
enum MetaType {
Expand Down Expand Up @@ -161,5 +163,6 @@ class Cluster2D
void traverse(Node * x);
};
} // namespace lidar_apollo_instance_segmentation
} // namespace autoware

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

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__DEBUGGER_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__DEBUGGER_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DEBUGGER_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DEBUGGER_HPP_

#include <rclcpp/rclcpp.hpp>

#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
class Debugger
Expand All @@ -33,5 +35,6 @@ class Debugger
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr instance_pointcloud_pub_;
};
} // namespace lidar_apollo_instance_segmentation
} // namespace autoware

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__DEBUGGER_HPP_
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DEBUGGER_HPP_
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.

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__DETECTOR_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__DETECTOR_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DETECTOR_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DETECTOR_HPP_

#include "cluster2d.hpp"
#include "feature_generator.hpp"
#include "lidar_apollo_instance_segmentation/node.hpp"
#include "autoware/lidar_apollo_instance_segmentation/cluster2d.hpp"
#include "autoware/lidar_apollo_instance_segmentation/feature_generator.hpp"
#include "autoware/lidar_apollo_instance_segmentation/node.hpp"

#include <autoware/universe_utils/transform/transforms.hpp>
#include <cuda_utils/cuda_unique_ptr.hpp>
Expand All @@ -31,6 +31,8 @@
#include <memory>
#include <string>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
using cuda_utils::CudaUniquePtr;
Expand Down Expand Up @@ -72,5 +74,6 @@ class LidarApolloInstanceSegmentation : public LidarInstanceSegmentationInterfac
StreamUniquePtr stream_{makeCudaStream()};
};
} // namespace lidar_apollo_instance_segmentation
} // namespace autoware

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__DETECTOR_HPP_
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DETECTOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,11 @@
* limitations under the License.
*****************************************************************************/

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
template <class T>
Expand Down Expand Up @@ -74,5 +76,5 @@ void DisjointSetUnion(T * x, T * y)
}
}
} // namespace lidar_apollo_instance_segmentation

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_
} // namespace autoware
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_GENERATOR_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_GENERATOR_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_GENERATOR_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_GENERATOR_HPP_

#include "lidar_apollo_instance_segmentation/feature_map.hpp"
#include "autoware/lidar_apollo_instance_segmentation/feature_map.hpp"
#include "util.hpp"

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

#include <memory>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
class FeatureGenerator
Expand All @@ -44,5 +46,5 @@ class FeatureGenerator
const pcl::PointCloud<pcl::PointXYZI>::Ptr & pc_ptr);
};
} // namespace lidar_apollo_instance_segmentation

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_GENERATOR_HPP_
} // namespace autoware
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_GENERATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_MAP_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_MAP_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_MAP_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_MAP_HPP_

#include <memory>
#include <vector>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
struct FeatureMapInterface
Expand Down Expand Up @@ -69,5 +71,5 @@ struct FeatureMapWithConstantAndIntensity : public FeatureMapInterface
void resetMap(std::vector<float> & map) override;
};
} // namespace lidar_apollo_instance_segmentation

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_MAP_HPP_
} // namespace autoware
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__FEATURE_MAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__LOG_TABLE_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__LOG_TABLE_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__LOG_TABLE_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__LOG_TABLE_HPP_

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
float calcApproximateLog(float num);
} // namespace lidar_apollo_instance_segmentation

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

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__NODE_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__NODE_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__NODE_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__NODE_HPP_

#include "lidar_apollo_instance_segmentation/debugger.hpp"
#include "autoware/lidar_apollo_instance_segmentation/debugger.hpp"

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

#include <memory>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
class LidarInstanceSegmentationInterface
Expand Down Expand Up @@ -54,5 +56,5 @@ class LidarInstanceSegmentationNode : public rclcpp::Node
explicit LidarInstanceSegmentationNode(const rclcpp::NodeOptions & node_options);
};
} // namespace lidar_apollo_instance_segmentation

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__NODE_HPP_
} // namespace autoware
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,13 @@
* limitations under the License.
*****************************************************************************/

#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_
#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_
#ifndef AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_
#define AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_

#include <cmath>
#include <string>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
// project point cloud to 2d map. calc in which grid point is.
Expand All @@ -58,5 +59,5 @@ inline float Pixel2Pc(int in_pixel, float in_size, float out_range)
return out_range - (static_cast<float>(in_pixel) + 0.5f) * res;
}
} // namespace lidar_apollo_instance_segmentation

#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_
} // namespace autoware
#endif // AUTOWARE__LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,14 @@

<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="trained_onnx_file" default="$(var data_path)/lidar_apollo_instance_segmentation/$(var base_name).onnx"/>
<arg name="param_file" default="$(find-pkg-share lidar_apollo_instance_segmentation)/config/$(var base_name).param.yaml"/>
<arg name="param_file" default="$(find-pkg-share autoware_lidar_apollo_instance_segmentation)/config/$(var base_name).param.yaml"/>

<arg name="target_frame" default="base_link"/>
<arg name="z_offset" default="-2.0"/>

<arg name="precision" default="fp32"/>

<node pkg="lidar_apollo_instance_segmentation" exec="lidar_apollo_instance_segmentation_node" name="lidar_apollo_instance_segmentation" output="screen">
<node pkg="autoware_lidar_apollo_instance_segmentation" exec="autoware_lidar_apollo_instance_segmentation_node" name="lidar_apollo_instance_segmentation" output="screen">
<remap from="input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="output/labeled_clusters" to="$(var output/objects)"/>
<param name="onnx_file" value="$(var trained_onnx_file)"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>lidar_apollo_instance_segmentation</name>
<name>autoware_lidar_apollo_instance_segmentation</name>
<version>0.1.0</version>
<description>lidar_apollo_instance_segmentation</description>
<description>autoware_lidar_apollo_instance_segmentation</description>
<maintainer email="[email protected]">Yoshi Ri</maintainer>
<maintainer email="[email protected]">Yukihiro Saito</maintainer>
<license>Apache License 2.0</license>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
* limitations under the License.
*****************************************************************************/

#include "lidar_apollo_instance_segmentation/cluster2d.hpp"
#include "autoware/lidar_apollo_instance_segmentation/cluster2d.hpp"

#include <autoware_perception_msgs/msg/detected_object_kinematics.hpp>
#include <autoware_perception_msgs/msg/object_classification.hpp>
Expand All @@ -54,8 +54,15 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include <algorithm>
#include <cmath>
#include <vector>

#endif

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
geometry_msgs::msg::Quaternion getQuaternionFromRPY(const double r, const double p, const double y)
Expand Down Expand Up @@ -377,3 +384,4 @@ void Cluster2D::getObjects(
objects.header = in_header;
}
} // namespace lidar_apollo_instance_segmentation
} // namespace autoware
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "lidar_apollo_instance_segmentation/debugger.hpp"
#include "autoware/lidar_apollo_instance_segmentation/debugger.hpp"

#include <autoware_perception_msgs/msg/object_classification.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand All @@ -21,6 +21,8 @@
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>

namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
Debugger::Debugger(rclcpp::Node * node)
Expand Down Expand Up @@ -101,3 +103,4 @@ void Debugger::publishColoredPointCloud(
instance_pointcloud_pub_->publish(output_msg);
}
} // namespace lidar_apollo_instance_segmentation
} // namespace autoware
Loading

0 comments on commit 3e501cf

Please sign in to comment.