Skip to content

Commit

Permalink
refactor(radar_static_pointcloud_filter): fix namespace and directory…
Browse files Browse the repository at this point in the history
… structure (#7914)

refactor: update include paths and namespace for radar_static_pointcloud_filter
  • Loading branch information
technolojin authored Jul 10, 2024
1 parent 0db8f67 commit f2fa715
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 16 deletions.
8 changes: 4 additions & 4 deletions sensing/radar_static_pointcloud_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_static_pointcloud_filter_node_component SHARED
src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/radar_static_pointcloud_filter_node.cpp
)

rclcpp_components_register_node(radar_static_pointcloud_filter_node_component
PLUGIN "radar_static_pointcloud_filter::RadarStaticPointcloudFilterNode"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::radar_static_pointcloud_filter::RadarStaticPointcloudFilterNode"
EXECUTABLE radar_static_pointcloud_filter_node
)

Expand Down
3 changes: 0 additions & 3 deletions sensing/radar_static_pointcloud_filter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,6 @@
<depend>radar_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>

<test_depend>ament_clang_format</test_depend>
<test_depend>ament_lint_auto</test_depend>
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_static_pointcloud_filter/radar_static_pointcloud_filter_node.hpp"
#include "radar_static_pointcloud_filter_node.hpp"

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <geometry_msgs/msg/twist_with_covariance.hpp>
Expand Down Expand Up @@ -75,7 +75,7 @@ geometry_msgs::msg::Vector3 compensateEgoVehicleTwist(
}
} // namespace

namespace radar_static_pointcloud_filter
namespace autoware::radar_static_pointcloud_filter
{
using nav_msgs::msg::Odometry;
using radar_msgs::msg::RadarReturn;
Expand Down Expand Up @@ -167,7 +167,8 @@ bool RadarStaticPointcloudFilterNode::isStaticPointcloud(
(compensated_velocity.x < node_param_.doppler_velocity_sd);
}

} // namespace radar_static_pointcloud_filter
} // namespace autoware::radar_static_pointcloud_filter

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(radar_static_pointcloud_filter::RadarStaticPointcloudFilterNode)
RCLCPP_COMPONENTS_REGISTER_NODE(
autoware::radar_static_pointcloud_filter::RadarStaticPointcloudFilterNode)
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_STATIC_POINTCLOUD_FILTER__RADAR_STATIC_POINTCLOUD_FILTER_NODE_HPP_
#define RADAR_STATIC_POINTCLOUD_FILTER__RADAR_STATIC_POINTCLOUD_FILTER_NODE_HPP_
#ifndef RADAR_STATIC_POINTCLOUD_FILTER_NODE_HPP_
#define RADAR_STATIC_POINTCLOUD_FILTER_NODE_HPP_

#include "autoware/universe_utils/ros/transform_listener.hpp"

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

namespace radar_static_pointcloud_filter
namespace autoware::radar_static_pointcloud_filter
{
using nav_msgs::msg::Odometry;
using radar_msgs::msg::RadarReturn;
Expand Down Expand Up @@ -77,6 +77,6 @@ class RadarStaticPointcloudFilterNode : public rclcpp::Node
const RadarReturn & radar_return, const Odometry::ConstSharedPtr & odom_msg,
geometry_msgs::msg::TransformStamped::ConstSharedPtr transform);
};
} // namespace radar_static_pointcloud_filter
} // namespace autoware::radar_static_pointcloud_filter

#endif // RADAR_STATIC_POINTCLOUD_FILTER__RADAR_STATIC_POINTCLOUD_FILTER_NODE_HPP_
#endif // RADAR_STATIC_POINTCLOUD_FILTER_NODE_HPP_

0 comments on commit f2fa715

Please sign in to comment.