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

refactor(radar_fusion_to_detected_object)!: fix namespace and directory structure #7650

Merged
Changes from 1 commit
Commits
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
Next Next commit
refactor: refactor radar fusion to detected object node and related f…
…iles

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
  • Loading branch information
technolojin committed Jun 24, 2024
commit 85bd107079a923bedf66e331a40c5d547e6a57e8
10 changes: 5 additions & 5 deletions perception/radar_fusion_to_detected_object/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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 ${PROJECT_NAME}_node
)

# Tests
Original file line number Diff line number Diff line change
@@ -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 AUTOWARE__RADAR_FUSION_TO_DETECTED_OBJECT__NODE_HPP_
#define AUTOWARE__RADAR_FUSION_TO_DETECTED_OBJECT__NODE_HPP_

#include "autoware/radar_fusion_to_detected_object/radar_fusion_to_detected_object.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 "rclcpp/rclcpp.hpp"

#include "autoware_perception_msgs/msg/detected_objects.hpp"
@@ -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;
@@ -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 // AUTOWARE__RADAR_FUSION_TO_DETECTED_OBJECT__NODE_HPP_
Original file line number Diff line number Diff line change
@@ -12,12 +12,14 @@
// 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 AUTOWARE__RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_
#define AUTOWARE__RADAR_FUSION_TO_DETECTED_OBJECT__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>

@@ -30,7 +32,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;
@@ -113,6 +115,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 // AUTOWARE__RADAR_FUSION_TO_DETECTED_OBJECT__RADAR_FUSION_TO_DETECTED_OBJECT_HPP_
Original file line number Diff line number Diff line change
@@ -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)"/>
Original file line number Diff line number Diff line change
@@ -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 "autoware/radar_fusion_to_detected_object/node.hpp"

#include "rclcpp/rclcpp.hpp"

#include <memory>
@@ -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;
@@ -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
@@ -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 "autoware/radar_fusion_to_detected_object/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>

@@ -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;
@@ -358,4 +358,4 @@ LinearRing2d RadarFusionToDetectedObject::createObject2dWithMargin(

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