Skip to content

Commit

Permalink
refactor(radar_fusion_to_detected_object)!: fix namespace and directo…
Browse files Browse the repository at this point in the history
…ry structure (autowarefoundation#7650)

* refactor: refactor radar fusion to detected object node and related files

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* refactor: fix the node name

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* refactor: move header files to src

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

---------

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
Signed-off-by: palas21 <palas21@itu.edu.tr>
  • Loading branch information
technolojin authored and palas21 committed Jul 12, 2024
1 parent ac244a4 commit 636c002
Show file tree
Hide file tree
Showing 7 changed files with 30 additions and 29 deletions.
10 changes: 5 additions & 5 deletions perception/radar_fusion_to_detected_object/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@ find_package(autoware_cmake REQUIRED)
autoware_package()

# Targets
ament_auto_add_library(radar_object_fusion_to_detected_object_node_component SHARED
src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/node.cpp
src/radar_fusion_to_detected_object.cpp
)

rclcpp_components_register_node(radar_object_fusion_to_detected_object_node_component
PLUGIN "radar_fusion_to_detected_object::RadarObjectFusionToDetectedObjectNode"
EXECUTABLE radar_object_fusion_to_detected_object_node
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::radar_fusion_to_detected_object::RadarObjectFusionToDetectedObjectNode"
EXECUTABLE radar_fusion_to_detected_object_node
)

# Tests
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="config_file" default="$(find-pkg-share radar_fusion_to_detected_object)/config/radar_object_fusion_to_detected_object.param.yaml"/>

<!-- Node -->
<node pkg="radar_fusion_to_detected_object" exec="radar_object_fusion_to_detected_object_node" name="radar_object_fusion_to_detected_object" output="screen">
<node pkg="radar_fusion_to_detected_object" exec="radar_fusion_to_detected_object_node" name="radar_object_fusion_to_detected_object" output="screen">
<remap from="~/input/objects" to="$(var input/objects)"/>
<remap from="~/input/radars" to="$(var input/radars)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
Expand Down
1 change: 0 additions & 1 deletion perception/radar_fusion_to_detected_object/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
<depend>message_filters</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>

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

#ifndef RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_NODE_HPP_
#define RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_NODE_HPP_
#ifndef NODE_HPP_
#define NODE_HPP_

#include "message_filters/subscriber.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/synchronizer.h"
#include "radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp"
#include "radar_fusion_to_detected_object.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_perception_msgs/msg/detected_objects.hpp"
Expand All @@ -29,7 +29,7 @@
#include <string>
#include <vector>

namespace radar_fusion_to_detected_object
namespace autoware::radar_fusion_to_detected_object
{
using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
Expand Down Expand Up @@ -87,6 +87,6 @@ class RadarObjectFusionToDetectedObjectNode : public rclcpp::Node
const DetectedObject & radar_object, const std_msgs::msg::Header & header_);
};

} // namespace radar_fusion_to_detected_object
} // namespace autoware::radar_fusion_to_detected_object

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

#ifndef RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_
#define RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_
#ifndef RADAR_FUSION_TO_DETECTED_OBJECT_HPP_
#define RADAR_FUSION_TO_DETECTED_OBJECT_HPP_

#define EIGEN_MPL2_ONLY

#include "autoware/universe_utils/geometry/boost_geometry.hpp"
#include "rclcpp/logger.hpp"
#define EIGEN_MPL2_ONLY

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

#include "autoware_perception_msgs/msg/detected_objects.hpp"
#include "geometry_msgs/msg/pose_with_covariance.hpp"
#include "geometry_msgs/msg/twist_with_covariance.hpp"
// #include "std_msgs/msg/header.hpp"

#include <memory>
#include <string>
#include <vector>

namespace radar_fusion_to_detected_object
namespace autoware::radar_fusion_to_detected_object
{
using autoware::universe_utils::LinearRing2d;
using autoware::universe_utils::Point2d;
Expand Down Expand Up @@ -113,6 +114,6 @@ class RadarFusionToDetectedObject
double getTwistNorm(const Twist & twist);
LinearRing2d createObject2dWithMargin(const Point2d object_size, const double margin);
};
} // namespace radar_fusion_to_detected_object
} // namespace autoware::radar_fusion_to_detected_object

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

#include "radar_fusion_to_detected_object/radar_fusion_to_detected_object_node.hpp"
#include "include/node.hpp"

#include "rclcpp/rclcpp.hpp"

#include <memory>
Expand Down Expand Up @@ -46,7 +47,7 @@ bool update_param(
}
} // namespace

namespace radar_fusion_to_detected_object
namespace autoware::radar_fusion_to_detected_object
{
using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
Expand Down Expand Up @@ -217,8 +218,8 @@ RadarFusionToDetectedObject::RadarInput RadarObjectFusionToDetectedObjectNode::s
return output;
}

} // namespace radar_fusion_to_detected_object
} // namespace autoware::radar_fusion_to_detected_object

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(
radar_fusion_to_detected_object::RadarObjectFusionToDetectedObjectNode)
autoware::radar_fusion_to_detected_object::RadarObjectFusionToDetectedObjectNode)
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp"
#include "include/radar_fusion_to_detected_object.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/math/normalization.hpp>
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/math/normalization.hpp"

#include <boost/geometry.hpp>

Expand All @@ -27,7 +27,7 @@
#include <string>
#include <vector>

namespace radar_fusion_to_detected_object
namespace autoware::radar_fusion_to_detected_object
{
using autoware::universe_utils::LinearRing2d;
using autoware::universe_utils::Point2d;
Expand Down Expand Up @@ -358,4 +358,4 @@ LinearRing2d RadarFusionToDetectedObject::createObject2dWithMargin(

return box;
}
} // namespace radar_fusion_to_detected_object
} // namespace autoware::radar_fusion_to_detected_object

0 comments on commit 636c002

Please sign in to comment.