Skip to content

Commit

Permalink
fix(dummy_perception_publisher): independent of pointcloud from detec…
Browse files Browse the repository at this point in the history
…tion_successful_rate (backport #527, #926, #1166) (#290)

* feat(dummy_perception_publisher): publish realistic dummy pointcloud using raymarchig (#527)

* Create pointcloud by raycasting from vehicle

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* [after-review] Use vector of ObjectInfo

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* [after-review] Implemented by strategy pattern

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* [after-review] split files

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Use pcl raytracing

Tmp

Tmp

Tmp

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Add signed distance function lib

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Use sdf library

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Remove no longer used functions

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Refactor

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Simplify getPoint

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Raytracing considering inter object relation

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Add random noise

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Default is object centric

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Return if no objects are detected

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Change definition of tf_global_to_local (same as other autoware codes)

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Remove create method

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Reaname: VehicleCentric -> EgoCentric

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Refactor a bit

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Tune parameter

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Fix: Even if selected_idices is zero, pointclouds must be published

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Fix launch file

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Fix typo

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Fix: create merged pointcloud when no idx is selected

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Use ray-maching by default

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* perf(dummy_perception_publisher): tune ego-centric pointcloud generation of dummy perception publisher (#926)

* Take advantage of visible range

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Tune

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Fix: typo

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>

* Use hypot

* fix(dummy_perception_publisher): independent of pointcloud from detection_successful_rate (#1166)

* fix(dummy_perception_publisher): independent of pointcloud from detection_success_rate

Signed-off-by: Shumpei Wakabayashi <shumpei.wakabayashi@tier4.jp>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

---------

Signed-off-by: Hirokazu Ishida <h-ishida@jsk.imi.i.u-tokyo.ac.jp>
Co-authored-by: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com>
Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
4 people authored Feb 28, 2023
1 parent ab09954 commit e9ebd09
Show file tree
Hide file tree
Showing 8 changed files with 683 additions and 228 deletions.
20 changes: 19 additions & 1 deletion simulator/dummy_perception_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

# Dependencies for messages
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_auto REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(autoware_auto_perception_msgs REQUIRED)
find_package(tier4_perception_msgs REQUIRED)
Expand Down Expand Up @@ -43,9 +43,18 @@ set(${PROJECT_NAME}_DEPENDENCIES
tf2_ros
)

ament_auto_add_library(signed_distance_function SHARED
src/signed_distance_function.cpp
)

ament_auto_add_executable(dummy_perception_publisher_node
src/main.cpp
src/node.cpp
src/pointcloud_creator.cpp
)

target_link_libraries(dummy_perception_publisher_node
signed_distance_function
)

ament_target_dependencies(dummy_perception_publisher_node ${${PROJECT_NAME}_DEPENDENCIES})
Expand Down Expand Up @@ -79,6 +88,15 @@ ament_auto_add_executable(empty_objects_publisher
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)

ament_add_gtest(signed_distance_function-test
test/src/test_signed_distance_function.cpp
)
target_link_libraries(signed_distance_function-test
signed_distance_function
)
endif()

ament_auto_package(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,69 @@
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <random>
#include <vector>

struct ObjectInfo
{
ObjectInfo(
const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time);
double length;
double width;
double height;
double std_dev_x;
double std_dev_y;
double std_dev_z;
double std_dev_yaw;
tf2::Transform tf_map2moved_object;
};

class PointCloudCreator
{
public:
virtual ~PointCloudCreator() {}

virtual std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const = 0;
};

class ObjectCentricPointCloudCreator : public PointCloudCreator
{
public:
explicit ObjectCentricPointCloudCreator(bool enable_ray_tracing)
: enable_ray_tracing_(enable_ray_tracing)
{
}

std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const override;

private:
void create_object_pointcloud(
const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud) const;

bool enable_ray_tracing_;
};

class EgoCentricPointCloudCreator : public PointCloudCreator
{
public:
explicit EgoCentricPointCloudCreator(double visible_range) : visible_range_(visible_range) {}
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const override;

private:
double visible_range_;
};

class DummyPerceptionPublisherNode : public rclcpp::Node
{
private:
Expand All @@ -52,13 +112,12 @@ class DummyPerceptionPublisherNode : public rclcpp::Node
bool enable_ray_tracing_;
bool use_object_recognition_;
bool use_real_param_;
std::unique_ptr<PointCloudCreator> pointcloud_creator_;

double angle_increment_;

std::mt19937 random_generator_;
void timerCallback();
void createObjectPointcloud(
const double length, const double width, const double height, const double std_dev_x,
const double std_dev_y, const double std_dev_z,
const tf2::Transform & tf_base_link2moved_object,
pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud_ptr);
void objectCallback(const dummy_perception_publisher::msg::Object::ConstSharedPtr msg);

public:
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
// 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.

#ifndef DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_
#define DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_

#include <tf2/LinearMath/Transform.h>

#include <limits>
#include <memory>
#include <stdexcept>
#include <utility>
#include <vector>

namespace signed_distance_function
{

class AbstractSignedDistanceFunction
{
public:
virtual double operator()(double x, double y) const = 0;
double getSphereTracingDist(
double x_start, double y_start, double angle,
double max_dist = std::numeric_limits<double>::infinity(), double eps = 1e-2) const;
virtual ~AbstractSignedDistanceFunction() {}
};

class BoxSDF : public AbstractSignedDistanceFunction
{
public:
BoxSDF(double length, double width, tf2::Transform tf_global_to_local)
: length_(length), width_(width), tf_local_to_global_(tf_global_to_local.inverse())
{
}
double operator()(double x, double y) const override;

private:
double length_;
double width_;
tf2::Transform tf_local_to_global_;
};

class CompositeSDF : public AbstractSignedDistanceFunction
{
public:
explicit CompositeSDF(std::vector<std::shared_ptr<AbstractSignedDistanceFunction>> sdf_ptrs)
: sdf_ptrs_(std::move(sdf_ptrs))
{
if (sdf_ptrs_.empty()) {
throw std::runtime_error("sdf_ptrs must not be empty");
}
}
double operator()(double x, double y) const override;

size_t nearest_sdf_index(double x, double y) const;

private:
std::vector<std::shared_ptr<AbstractSignedDistanceFunction>> sdf_ptrs_;
};

} // namespace signed_distance_function

#endif // DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<param name="detection_successful_rate" value="0.999"/>
<param name="enable_ray_tracing" value="false"/>
<param name="use_object_recognition" value="$(var use_object_recognition)"/>
<param name="object_centric_pointcloud" value="false"/>
</node>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="input/objects" value="/perception/object_recognition/detection/labeled_clusters"/>
Expand Down
Loading

0 comments on commit e9ebd09

Please sign in to comment.