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(map_tf_generator): rework parameters #6233

Merged
Show file tree
Hide file tree
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
4 changes: 2 additions & 2 deletions launch/tier4_map_launch/launch/map.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<!-- Parameter files -->
<arg name="pointcloud_map_loader_param_path"/>
<arg name="lanelet2_map_loader_param_path"/>
<arg name="map_tf_generator_param_path"/>

<!-- whether use intra-process -->
<arg name="use_intra_process" default="false"/>
Expand Down Expand Up @@ -47,8 +48,7 @@
</composable_node>

<composable_node pkg="map_tf_generator" plugin="VectorMapTFGeneratorNode" name="vector_map_tf_generator">
<param name="map_frame" value="map"/>
<param name="viewer_frame" value="viewer"/>
<param from="$(var map_tf_generator_param_path)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</node_container>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,7 @@ None

### Core Parameters

| Name | Type | Default Value | Explanation |
| -------------- | ------ | ------------- | ------------------------------------- |
| `viewer_frame` | string | viewer | Name of `viewer` frame |
| `map_frame` | string | map | The parent frame name of viewer frame |
{{ json_to_markdown("map/map_tf_generator/schema/map_tf_generator.schema.json") }}

## Assumptions / Known limits

Expand Down
4 changes: 4 additions & 0 deletions map/map_tf_generator/config/map_tf_generator.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
map_frame: map
viewer_frame: viewer
8 changes: 3 additions & 5 deletions map/map_tf_generator/launch/map_tf_generator.launch.xml
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
<launch>
<arg name="input_vector_map_topic" default="/map/vector_map"/>
<arg name="param_file" default="$(find-pkg-share map_tf_generator)/config/map_tf_generator.param.yaml"/>

<arg name="map_frame" default="map"/>
<arg name="viewer_frame" default="viewer"/>
<arg name="input_vector_map_topic" default="/map/vector_map"/>

<node pkg="map_tf_generator" exec="vector_map_tf_generator" name="vector_map_tf_generator">
<remap from="vector_map" to="$(var input_vector_map_topic)"/>

<param name="map_frame" value="$(var map_frame)"/>
<param name="viewer_frame" value="$(var viewer_frame)"/>
<param from="$(var param_file)"/>
</node>
</launch>
38 changes: 38 additions & 0 deletions map/map_tf_generator/schema/map_tf_generator.schema.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Map Tf Generator",
"type": "object",
"definitions": {
"map_tf_generator": {
"type": "object",
"properties": {
"map_frame": {
"type": "string",
"description": "The parent frame name of viewer frame",
"default": "map"
},
"viewer_frame": {
"type": "string",
"description": "Name of `viewer` frame",
"default": "viewer"
}
},
"required": ["map_frame", "viewer_frame"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/map_tf_generator"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
4 changes: 2 additions & 2 deletions map/map_tf_generator/src/pcd_map_tf_generator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ class PcdMapTFGeneratorNode : public rclcpp::Node
explicit PcdMapTFGeneratorNode(const rclcpp::NodeOptions & options)
: Node("pcd_map_tf_generator", options)
{
map_frame_ = declare_parameter("map_frame", "map");
viewer_frame_ = declare_parameter("viewer_frame", "viewer");
map_frame_ = declare_parameter<std::string>("map_frame");
viewer_frame_ = declare_parameter<std::string>("viewer_frame");

sub_ = create_subscription<sensor_msgs::msg::PointCloud2>(
"pointcloud_map", rclcpp::QoS{1}.transient_local(),
Expand Down
4 changes: 2 additions & 2 deletions map/map_tf_generator/src/vector_map_tf_generator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ class VectorMapTFGeneratorNode : public rclcpp::Node
explicit VectorMapTFGeneratorNode(const rclcpp::NodeOptions & options)
: Node("vector_map_tf_generator", options)
{
map_frame_ = declare_parameter("map_frame", "map");
viewer_frame_ = declare_parameter("viewer_frame", "viewer");
map_frame_ = declare_parameter<std::string>("map_frame");
viewer_frame_ = declare_parameter<std::string>("viewer_frame");

sub_ = create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
"vector_map", rclcpp::QoS{1}.transient_local(),
Expand Down
Loading