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_tracks_noise_filter)!: fix namespace and directory structure #7911

Merged
Show file tree
Hide file tree
Changes from all commits
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
14 changes: 7 additions & 7 deletions sensing/radar_tracks_noise_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ find_package(autoware_cmake REQUIRED)
autoware_package()

# Targets
ament_auto_add_library(radar_tracks_noise_filter_node_component SHARED
src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/radar_tracks_noise_filter_node.cpp
)

rclcpp_components_register_node(radar_tracks_noise_filter_node_component
PLUGIN "radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode"
EXECUTABLE radar_tracks_noise_filter_node
)

Expand All @@ -22,10 +22,10 @@ if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
file(GLOB_RECURSE test_files test/**/*.cpp)
ament_add_ros_isolated_gtest(radar_tracks_noise_filter ${test_files})
ament_add_ros_isolated_gtest(${PROJECT_NAME}_test ${test_files})

target_link_libraries(radar_tracks_noise_filter
radar_tracks_noise_filter_node_component
target_link_libraries(${PROJECT_NAME}_test
${PROJECT_NAME}
)
endif()

Expand Down
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 "radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp"
#include "radar_tracks_noise_filter_node.hpp"

#include <memory>
#include <string>
Expand All @@ -38,7 +38,7 @@ bool update_param(
}
} // namespace

namespace radar_tracks_noise_filter
namespace autoware::radar_tracks_noise_filter
{
using radar_msgs::msg::RadarTrack;
using radar_msgs::msg::RadarTracks;
Expand Down Expand Up @@ -116,7 +116,8 @@ bool RadarTrackCrossingNoiseFilterNode::isNoise(const RadarTrack & radar_track)
}
}

} // namespace radar_tracks_noise_filter
} // namespace autoware::radar_tracks_noise_filter

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

#ifndef RADAR_TRACKS_NOISE_FILTER__RADAR_TRACKS_NOISE_FILTER_NODE_HPP_
#define RADAR_TRACKS_NOISE_FILTER__RADAR_TRACKS_NOISE_FILTER_NODE_HPP_
#ifndef RADAR_TRACKS_NOISE_FILTER_NODE_HPP_
#define RADAR_TRACKS_NOISE_FILTER_NODE_HPP_

#include "rclcpp/rclcpp.hpp"

Expand All @@ -23,7 +23,7 @@
#include <memory>
#include <vector>

namespace radar_tracks_noise_filter
namespace autoware::radar_tracks_noise_filter
{
using radar_msgs::msg::RadarTrack;
using radar_msgs::msg::RadarTracks;
Expand Down Expand Up @@ -62,6 +62,6 @@ class RadarTrackCrossingNoiseFilterNode : public rclcpp::Node
bool isNoise(const RadarTrack & radar_track);
};

} // namespace radar_tracks_noise_filter
} // namespace autoware::radar_tracks_noise_filter

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

#include "radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp"
#include "../../src/radar_tracks_noise_filter_node.hpp"

#include <radar_msgs/msg/radar_scan.hpp>

#include <gtest/gtest.h>

std::shared_ptr<radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode> get_node(
std::shared_ptr<autoware::radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode> get_node(
float velocity_y_threshold)
{
rclcpp::NodeOptions node_options;
Expand All @@ -28,7 +28,8 @@ std::shared_ptr<radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode> ge
});

auto node =
std::make_shared<radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode>(node_options);
std::make_shared<autoware::radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode>(
node_options);
return node;
}

Expand All @@ -45,8 +46,8 @@ radar_msgs::msg::RadarTrack getRadarTrack(float velocity_x, float velocity_y)

TEST(RadarTracksNoiseFilter, isNoise)
{
using autoware::radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode;
using radar_msgs::msg::RadarTrack;
using radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode;
rclcpp::init(0, nullptr);
{
float velocity_node_threshold = 0.0;
Expand Down
Loading