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

feat(map_height_fitter): componentize MapHeightFitter #7192

Merged
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
12 changes: 8 additions & 4 deletions map/map_height_fitter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,20 +5,24 @@ find_package(autoware_cmake REQUIRED)
find_package(PCL REQUIRED COMPONENTS common)
autoware_package()

ament_auto_add_library(map_height_fitter SHARED
ament_auto_add_library(${PROJECT_NAME} SHARED
src/map_height_fitter.cpp
src/map_height_fitter_node.cpp
)
target_link_libraries(map_height_fitter ${PCL_LIBRARIES})

# When adding `<depend>lanelet2_extension</depend>` to package.xml, many warnings are generated.
# These are treated as errors in compile, so pedantic warnings are disabled for this package.
target_compile_options(map_height_fitter PRIVATE -Wno-pedantic)

ament_auto_add_executable(node
src/node.cpp
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "MapHeightFitterNode"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR MultiThreadedExecutor
)

ament_auto_package(
INSTALL_TO_SHARE
launch
config)
config
)
2 changes: 1 addition & 1 deletion map/map_height_fitter/launch/map_height_fitter.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<group>
<push-ros-namespace namespace="map"/>
<node pkg="map_height_fitter" exec="node" name="map_height_fitter">
<node pkg="map_height_fitter" exec="map_height_fitter_node" output="both">
<param from="$(var param_path)"/>
<remap from="~/pointcloud_map" to="/map/pointcloud_map"/>
<remap from="~/partial_map_load" to="/map/get_partial_pointcloud_map"/>
Expand Down
1 change: 1 addition & 0 deletions map/map_height_fitter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>libpcl-common</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ using tier4_localization_msgs::srv::PoseWithCovarianceStamped;
class MapHeightFitterNode : public rclcpp::Node
{
public:
MapHeightFitterNode() : Node("map_height_fitter"), fitter_(this)
explicit MapHeightFitterNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("map_height_fitter", options), fitter_(this)
{
const auto on_service = [this](
const PoseWithCovarianceStamped::Request::SharedPtr req,
Expand All @@ -46,13 +47,5 @@ class MapHeightFitterNode : public rclcpp::Node
rclcpp::Service<PoseWithCovarianceStamped>::SharedPtr srv_;
};

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor executor;
auto node = std::make_shared<MapHeightFitterNode>();
executor.add_node(node);
executor.spin();
executor.remove_node(node);
rclcpp::shutdown();
}
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(MapHeightFitterNode)
Loading