Skip to content

Commit

Permalink
feat(map_tf_generator)!: launching planning_simulator without pointcl…
Browse files Browse the repository at this point in the history
…oud map (tier4#1216)

* feat(map_tf_generator): add vector map tf generator

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(ad_service_state_monitor): rm unused cofig param

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* chore: change launching vector_map_tf_generator

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs: update readme

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* refactor: rename map_tf_generator -> pcd_map_tf_generator

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: build error

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* Update map/map_tf_generator/Readme.md

Co-authored-by: Kenji Miyake <[email protected]>

* Update map/map_tf_generator/src/vector_map_tf_generator_node.cpp

Co-authored-by: Kenji Miyake <[email protected]>

* Update map/map_tf_generator/Readme.md

Co-authored-by: Kenji Miyake <[email protected]>

* Update map/map_tf_generator/Readme.md

Co-authored-by: Kenji Miyake <[email protected]>

Co-authored-by: Kenji Miyake <[email protected]>
  • Loading branch information
2 people authored and boyali committed Oct 3, 2022
1 parent 99d4bfb commit 753e74a
Show file tree
Hide file tree
Showing 9 changed files with 146 additions and 28 deletions.
4 changes: 2 additions & 2 deletions launch/tier4_map_launch/launch/map.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,8 @@ def launch_setup(context, *args, **kwargs):

map_tf_generator = ComposableNode(
package="map_tf_generator",
plugin="MapTFGeneratorNode",
name="map_tf_generator",
plugin="VectorMapTFGeneratorNode",
name="vector_map_tf_generator",
parameters=[
{
"map_frame": "map",
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_map_launch/launch/map.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
</node>

<include file="$(find-pkg-share map_tf_generator)/launch/map_tf_generator.launch.xml">
<arg name="input_map_points_topic" value="/map/pointcloud_map"/>
<arg name="input_vector_map_topic" value="/map/vector_map"/>
</include>
</group>
</launch>
26 changes: 20 additions & 6 deletions map/map_tf_generator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,16 +6,30 @@ autoware_package()

find_package(PCL REQUIRED)

ament_auto_add_library(map_tf_generator_node SHARED
src/map_tf_generator_node.cpp
include_directories(
include
SYSTEM
${PCL_INCLUDE_DIRS}
)
target_link_libraries(map_tf_generator_node ${PCL_LIBRARIES})

rclcpp_components_register_node(map_tf_generator_node
PLUGIN "MapTFGeneratorNode"
EXECUTABLE map_tf_generator
ament_auto_add_library(pcd_map_tf_generator_node SHARED
src/pcd_map_tf_generator_node.cpp
)
target_link_libraries(pcd_map_tf_generator_node ${PCL_LIBRARIES})

rclcpp_components_register_node(pcd_map_tf_generator_node
PLUGIN "PcdMapTFGeneratorNode"
EXECUTABLE pcd_map_tf_generator
)

ament_auto_add_library(vector_map_tf_generator_node SHARED
src/vector_map_tf_generator_node.cpp
)

rclcpp_components_register_node(vector_map_tf_generator_node
PLUGIN "VectorMapTFGeneratorNode"
EXECUTABLE vector_map_tf_generator
)

if(BUILD_TESTING)
function(add_testcase filepath)
Expand Down
18 changes: 15 additions & 3 deletions map/map_tf_generator/Readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,33 @@

## Purpose

This node broadcasts `viewer` frames for visualization of pointcloud map in Rviz.
The position of `viewer` frames is the geometric center of input pointclouds.
The nodes in this package broadcast the `viewer` frame for visualization of the map in RViz.

Note that there is no module to need `viewer` frames and this is used only for visualization.
Note that there is no module to need the `viewer` frame and this is used only for visualization.

The following are the supported methods to calculate the position of the `viewer` frame:

- `pcd_map_tf_generator_node` outputs the geometric center of all points in the PCD.
- `vector_map_tf_generator_node` outputs the geometric center of all points in the point layer.

## Inner-workings / Algorithms

## Inputs / Outputs

### Input

#### pcd_map_tf_generator

| Name | Type | Description |
| --------------------- | ------------------------------- | ----------------------------------------------------------------- |
| `/map/pointcloud_map` | `sensor_msgs::msg::PointCloud2` | Subscribe pointcloud map to calculate position of `viewer` frames |

#### vector_map_tf_generator

| Name | Type | Description |
| ----------------- | -------------------------------------------- | ------------------------------------------------------------- |
| `/map/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Subscribe vector map to calculate position of `viewer` frames |

### Output

| Name | Type | Description |
Expand Down
6 changes: 3 additions & 3 deletions map/map_tf_generator/launch/map_tf_generator.launch.xml
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
<launch>
<arg name="input_map_points_topic" default="/map/pointcloud_map"/>
<arg name="input_vector_map_topic" default="/map/vector_map"/>

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

<node pkg="map_tf_generator" exec="map_tf_generator" name="map_tf_generator">
<remap from="pointcloud_map" to="$(var input_map_points_topic)"/>
<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)"/>
Expand Down
1 change: 1 addition & 0 deletions map/map_tf_generator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

<build_depend>autoware_cmake</build_depend>

<depend>lanelet2_extension</depend>
<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,19 +29,19 @@

constexpr size_t N_SAMPLES = 20;

class MapTFGeneratorNode : public rclcpp::Node
class PcdMapTFGeneratorNode : public rclcpp::Node
{
public:
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
explicit MapTFGeneratorNode(const rclcpp::NodeOptions & options)
: Node("map_tf_generator", options)
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");

sub_ = create_subscription<sensor_msgs::msg::PointCloud2>(
"pointcloud_map", rclcpp::QoS{1}.transient_local(),
std::bind(&MapTFGeneratorNode::onPointCloud, this, std::placeholders::_1));
std::bind(&PcdMapTFGeneratorNode::onPointCloud, this, std::placeholders::_1));

static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
}
Expand Down Expand Up @@ -97,4 +97,4 @@ class MapTFGeneratorNode : public rclcpp::Node
};

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(MapTFGeneratorNode)
RCLCPP_COMPONENTS_REGISTER_NODE(PcdMapTFGeneratorNode)
99 changes: 99 additions & 0 deletions map/map_tf_generator/src/vector_map_tf_generator_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/Point.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/static_transform_broadcaster.h>

#include <memory>
#include <string>

class VectorMapTFGeneratorNode : public rclcpp::Node
{
public:
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");

sub_ = create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
"vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&VectorMapTFGeneratorNode::onVectorMap, this, std::placeholders::_1));

static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
}

private:
std::string map_frame_;
std::string viewer_frame_;
rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr sub_;

std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
std::shared_ptr<lanelet::LaneletMap> lanelet_map_ptr_;

void onVectorMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg)
{
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr_);
std::vector<double> points_x;
std::vector<double> points_y;
std::vector<double> points_z;

for (const lanelet::Point3d & point : lanelet_map_ptr_->pointLayer) {
const double point_x = point.x();
const double point_y = point.y();
const double point_z = point.z();
points_x.push_back(point_x);
points_y.push_back(point_y);
points_z.push_back(point_z);
}
const double coordinate_x =
std::accumulate(points_x.begin(), points_x.end(), 0.0) / points_x.size();
const double coordinate_y =
std::accumulate(points_y.begin(), points_y.end(), 0.0) / points_y.size();
const double coordinate_z =
std::accumulate(points_z.begin(), points_z.end(), 0.0) / points_z.size();

geometry_msgs::msg::TransformStamped static_transformStamped;
static_transformStamped.header.stamp = this->now();
static_transformStamped.header.frame_id = map_frame_;
static_transformStamped.child_frame_id = viewer_frame_;
static_transformStamped.transform.translation.x = coordinate_x;
static_transformStamped.transform.translation.y = coordinate_y;
static_transformStamped.transform.translation.z = coordinate_z;
tf2::Quaternion quat;
quat.setRPY(0, 0, 0);
static_transformStamped.transform.rotation.x = quat.x();
static_transformStamped.transform.rotation.y = quat.y();
static_transformStamped.transform.rotation.z = quat.z();
static_transformStamped.transform.rotation.w = quat.w();

static_broadcaster_->sendTransform(static_transformStamped);

RCLCPP_INFO_STREAM(
get_logger(), "broadcast static tf. map_frame:"
<< map_frame_ << ", viewer_frame:" << viewer_frame_ << ", x:" << coordinate_x
<< ", y:" << coordinate_y << ", z:" << coordinate_z);
}
};

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(VectorMapTFGeneratorNode)
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
topic_configs:
names: [
"/map/vector_map",
"/map/pointcloud_map",
"/perception/object_recognition/objects",
"/initialpose2d",
"/planning/mission_planning/route",
Expand All @@ -43,13 +42,6 @@
type: "autoware_auto_mapping_msgs/msg/HADMapBin"
transient_local: True

/map/pointcloud_map:
module: "map"
timeout: 0.0
warn_rate: 0.0
type: "sensor_msgs/msg/PointCloud2"
transient_local: True

/perception/object_recognition/objects:
module: "perception"
timeout: 1.0
Expand Down

0 comments on commit 753e74a

Please sign in to comment.