Skip to content

Commit

Permalink
feat: add dummy perception publisher (autowarefoundation#90)
Browse files Browse the repository at this point in the history
* release v0.4.0

* add use_object_recognition flag in dummy_perception_publisher (autowarefoundation#696)

* remove ROS1 packages temporarily

Signed-off-by: mitsudome-r <[email protected]>

* add sample ros2 packages

Signed-off-by: mitsudome-r <[email protected]>

* remove ROS1 packages

Signed-off-by: mitsudome-r <[email protected]>

* Revert "remove ROS1 packages temporarily"

This reverts commit 2e9822586a3539a32653e6bcd378715674b519ca.

Signed-off-by: mitsudome-r <[email protected]>

* add COLCON_IGNORE to ros1 packages

Signed-off-by: mitsudome-r <[email protected]>

* Rename launch files to launch.xml (autowarefoundation#28)

* Port dummy_perception_publisher to ROS2 (autowarefoundation#90)

* Port dummy_perception_publisher to ROS2

* Uncrustify

* Lint

* Copyright

* Period

* Further ament_cpplint fixes

* Convert calls of Duration to Duration::from_seconds where appropriate (autowarefoundation#131)

* Use quotes for includes where appropriate (autowarefoundation#144)

* Use quotes for includes where appropriate

* Fix lint tests

* Make tests pass hopefully

* adding linters to dummy_perception_publisher (autowarefoundation#220)

* [dummy_perception_publisher] fix launch file and installation (autowarefoundation#215)

* [dummy_perception_publisher] fix launch file and installation

Signed-off-by: mitsudome-r <[email protected]>

* Apply suggestions from code review

Co-authored-by: Takamasa Horibe <[email protected]>

Co-authored-by: Takamasa Horibe <[email protected]>

* reduce terminal ouput for better error message visibility (autowarefoundation#200)

* reduce terminal ouput for better error message visibility

Signed-off-by: mitsudome-r <[email protected]>

* [costmap_generator] fix waiting for first transform

Signed-off-by: mitsudome-r <[email protected]>

* fix tests

Signed-off-by: mitsudome-r <[email protected]>

* fix test

Signed-off-by: mitsudome-r <[email protected]>

* modify launch file for making psim work (autowarefoundation#238)

* modify launch file for making psim work

Signed-off-by: kosuke murakami <[email protected]>

* remove unnecesary ns

Signed-off-by: kosuke murakami <[email protected]>

* Ros2 v0.8.0 dummy perception publisher (autowarefoundation#286)

* Remove "/" in frame_id (autowarefoundation#406)

Signed-off-by: Kenji Miyake <[email protected]>

* Fix transform (autowarefoundation#420)

* Replace rclcpp::Time(0) by tf2::TimePointZero() in lookupTransform

Signed-off-by: Kenji Miyake <[email protected]>

* Fix canTransform

Signed-off-by: Kenji Miyake <[email protected]>

* Fix test

Signed-off-by: Kenji Miyake <[email protected]>

* add use_sim-time option (autowarefoundation#454)

* Remove use_sim_time for set_parameter (autowarefoundation#1260)

Signed-off-by: wep21 <[email protected]>

* Diable dummy_perception_publisher if argument 'scenario_simulation' i… (autowarefoundation#1275)

* Diable dummy_perception_publisher if argument 'scenario_simulation' is true

* Rename argument to 'disable_dummy_perception_publisher_node' from 'scenario_simulation'

* change theta step for obj point cloud (autowarefoundation#1280)

* Revert changes of PR autowarefoundation#1275 (autowarefoundation#1377)

* Add pre-commit (autowarefoundation#1560)

* add pre-commit

* add pre-commit-config

* add additional settings for private repository

* use default pre-commit-config

* update pre-commit setting

* Ignore whitespace for line breaks in markdown

* Update .github/workflows/pre-commit.yml

Co-authored-by: Kazuki Miyahara <[email protected]>

* exclude svg

* remove pretty-format-json

* add double-quote-string-fixer

* consider COLCON_IGNORE file when seaching modified package

* format file

* pre-commit fixes

* Update pre-commit.yml

* Update .pre-commit-config.yaml

Co-authored-by: Kazuki Miyahara <[email protected]>
Co-authored-by: pre-commit <[email protected]>
Co-authored-by: Kenji Miyake <[email protected]>

* Fix dependency type of rosidl_default_generators (autowarefoundation#1801)

* Fix dependency type of rosidl_default_generators

Signed-off-by: Kenji Miyake <[email protected]>

* Remove unnecessary depends

Signed-off-by: Kenji Miyake <[email protected]>

* Use ament_cmake_auto

Signed-off-by: Kenji Miyake <[email protected]>

* Fix -Wunused-parameter (autowarefoundation#1836)

* Fix -Wunused-parameter

Signed-off-by: Kenji Miyake <[email protected]>

* Fix mistake

Signed-off-by: Kenji Miyake <[email protected]>

* fix spell

* Fix lint issues

Signed-off-by: Kenji Miyake <[email protected]>

* Ignore flake8 warnings

Signed-off-by: Kenji Miyake <[email protected]>

Co-authored-by: Hiroki OTA <[email protected]>

* fix topic namespace (autowarefoundation#2054)

Signed-off-by: Azumi Suzuki <[email protected]>

* add sort-package-xml hook in pre-commit (autowarefoundation#1881)

* add sort xml hook in pre-commit

* change retval to exit_status

* rename

* add prettier plugin-xml

* use early return

* add license note

* add tier4 license

* restore prettier

* change license order

* move local hooks to public repo

* move prettier-xml to pre-commit-hooks-ros

* update version for bug-fix

* apply pre-commit

* Feature/porting occlusion spot (autowarefoundation#1740)

* Feature/occlusion_spot safety planner public road (autowarefoundation#1594)

* add blind spot safety planner public road

* remove duplicated procesing

* remove unused private param

* renaming fix typo add comments

* fix spell check

* velocity -> relative velocity

* calc2d, To param, simplify search, To original

* add the num possible collision gurd

* computational cost reduction

* Cosmetic change for PossibleCollisionInfo

* add interpolation to possible collision value

* refactor codes

* fix details

* invalid point gurd

* To Param

* refacotor to occlusion spot util

* cosmetic change

* clean up blindspot

* To Occlusion Spot

* revise readme

* refactor drawing

* for better explanation

* fix velocity profile

* clean up details

* cosmetic change for debug marker

* use max velocity in obstacle info instead

* add gtest for Too Many Possible Collision case

* change case

* refactor readme

* minor fix

* add more occlusion spot explanation

* replace svg

* add gtest build path lanelet

* hotfix lateral distance and searching method

* update g test for lateral distance

* use faster search

* set more realistic param

* add lanelet subtype highway

* cosmetic change of reviews

* add occlusion spot module in private area (autowarefoundation#1640)

* add occlusion spot in private

* For debugging change

* add spline interpolation to path

* add review changes

* adding minor change

* cosmetic change

* Vector to retval

* Blindspot To OcclusionSpot1

* To Occlusion Spot 2

* To Occlusions spot3

* update gtest with unified anchor

* remove anchor

* add test slice

* simplify interpolation

* Too Occlusion spot4

* add test buffer

* To Occlusion spot

* namespace gurd

* correct slice and add interpolation first

* handle self crossing with check for invation

* to ros debug stream

* removed unused interpolation

* add readme to plant uml

* cosmetic change

* minor change

* update readme

* review change

* change occlusion spot text color

* To Offset no Throw

* better debug marker

* catch only inversion error

* skip return in case of inversion

* for better grid

* simplify path lanelet at first

* remove std::cout

* for better path

* limit ego path inside target lanelet location

* remove last points

* cosmetic change for markers

* apply module for limited scene

* fix interpolation gurd

* for better params

* do not includes path behind

* remove dummy perception publisher

* Revert "remove dummy perception publisher"

This reverts commit 4acad985fe31dd9befaa21a16631495de6c3a117.

* replace hard coded occupancy grid option in psim

* remove respawn

* add arg to params and remove redundunt launch

* fix spell check

* fix default value

Co-authored-by: tkimura4 <[email protected]>

* Feature/occlusion spot private slice size param (autowarefoundation#1703)

* add min slice size

* for a bit narrow lateral distance

* Update planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/config/occlusion_spot_param.yaml

Co-authored-by: Maxime CLEMENT <[email protected]>

Co-authored-by: Maxime CLEMENT <[email protected]>

* Rename files

Signed-off-by: wep21 <[email protected]>

* Porting to ros2

Signed-off-by: wep21 <[email protected]>

* pre-commit fixes

Signed-off-by: wep21 <[email protected]>

* Fix typo

Signed-off-by: wep21 <[email protected]>

* Fix launch namespace

Co-authored-by: tkimura4 <[email protected]>

* Fix parameter type

Co-authored-by: tkimura4 <[email protected]>

* Update planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp

Co-authored-by: tkimura4 <[email protected]>

Co-authored-by: taikitanaka3 <[email protected]>
Co-authored-by: tkimura4 <[email protected]>
Co-authored-by: Maxime CLEMENT <[email protected]>

* Change formatter to clang-format and black (autowarefoundation#2332)

* Revert "Temporarily comment out pre-commit hooks"

This reverts commit 748e9cdb145ce12f8b520bcbd97f5ff899fc28a3.

* Replace ament_lint_common with autoware_lint_common

Signed-off-by: Kenji Miyake <[email protected]>

* Remove ament_cmake_uncrustify and ament_clang_format

Signed-off-by: Kenji Miyake <[email protected]>

* Apply Black

Signed-off-by: Kenji Miyake <[email protected]>

* Apply clang-format

Signed-off-by: Kenji Miyake <[email protected]>

* Fix build errors

Signed-off-by: Kenji Miyake <[email protected]>

* Fix for cpplint

* Fix include double quotes to angle brackets

Signed-off-by: Kenji Miyake <[email protected]>

* Apply clang-format

Signed-off-by: Kenji Miyake <[email protected]>

* Fix build errors

Signed-off-by: Kenji Miyake <[email protected]>

* Add COLCON_IGNORE (autowarefoundation#500)

Signed-off-by: Kenji Miyake <[email protected]>

* port dummy perception publisher to auto (autowarefoundation#562)

* port dummy perception publisher to auto

* autoware_perception_msgs/DynamicObjectWithFeatureArray convert to autoware_perception_msgs/DetectedObjectsWithFeature

* change tracked objects to PREDICTED objects

* separate pub type with real

* Add README.md to dummy perception publisher (autowarefoundation#641)

* Added readme for dummy_perception_pub

* README update

* README update

* Fix pre-commit

* fix typo

* Update README.md

* Update README.md

* Update README.md

* Modified node.cpp

* Modified README.md

* change parameter name

* Update README.md

* [shape_estimation]change type (autowarefoundation#663)

* change output type of shape_estimation

* remove unused function

* add dynamic_object_converter

* rename

* fix typo

* fix dummy_perception_publisher

* update readme

* fix copyright

* rename package

* add readme

* fix launch name

* remove unused variable

* fix readme

* fix convert function

* change topic name of DynamicObjectsWithFeature

* Fix no ground pointcloud topic name (autowarefoundation#733)

Signed-off-by: j4tfwm6z <[email protected]>

Co-authored-by: j4tfwm6z <[email protected]>

* auto/fix occupancy grid name space in dummy perception publisher (autowarefoundation#739)

* fix name space

* change namespace: object_segmentation -> obstacle_segmentation

* feat: add use_traffic_light status

Co-authored-by: mitsudome-r <[email protected]>
Co-authored-by: Taichi Higashide <[email protected]>
Co-authored-by: Nikolai Morin <[email protected]>
Co-authored-by: nik-tier4 <[email protected]>
Co-authored-by: Ryohsuke Mitsudome <[email protected]>
Co-authored-by: Takamasa Horibe <[email protected]>
Co-authored-by: Kosuke Murakami <[email protected]>
Co-authored-by: Daisuke Nishimatsu <[email protected]>
Co-authored-by: Kenji Miyake <[email protected]>
Co-authored-by: tkimura4 <[email protected]>
Co-authored-by: Tatsuya Yamasaki <[email protected]>
Co-authored-by: taikitanaka3 <[email protected]>
Co-authored-by: Keisuke Shima <[email protected]>
Co-authored-by: Kazuki Miyahara <[email protected]>
Co-authored-by: pre-commit <[email protected]>
Co-authored-by: Hiroki OTA <[email protected]>
Co-authored-by: Azumi Suzuki <[email protected]>
Co-authored-by: Maxime CLEMENT <[email protected]>
Co-authored-by: Yohei Mishina <[email protected]>
Co-authored-by: j4tfwm6z <[email protected]>
Co-authored-by: Satoshi OTA <[email protected]>
  • Loading branch information
22 people authored Dec 2, 2021
1 parent 5cdd0a8 commit 15ec6ff
Show file tree
Hide file tree
Showing 10 changed files with 853 additions and 0 deletions.
87 changes: 87 additions & 0 deletions simulator/dummy_perception_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
cmake_minimum_required(VERSION 3.5)
project(dummy_perception_publisher)

### Compile options
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# Dependencies for messages
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(autoware_auto_perception_msgs REQUIRED)
find_package(autoware_perception_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(unique_identifier_msgs REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"msg/InitialState.msg"
"msg/Object.msg"
DEPENDENCIES autoware_auto_perception_msgs autoware_perception_msgs geometry_msgs std_msgs unique_identifier_msgs
)

# See ndt_omp package for documentation on why PCL is special
find_package(PCL REQUIRED COMPONENTS common filters)
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

set(${PROJECT_NAME}_DEPENDENCIES
autoware_auto_perception_msgs
autoware_perception_msgs
pcl_conversions
rclcpp
sensor_msgs
std_msgs
tf2
tf2_geometry_msgs
tf2_ros
)

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

ament_target_dependencies(dummy_perception_publisher_node ${${PROJECT_NAME}_DEPENDENCIES})

target_include_directories(dummy_perception_publisher_node
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)

# For using message definitions from the same package
rosidl_target_interfaces(dummy_perception_publisher_node
${PROJECT_NAME} "rosidl_typesupport_cpp")

# PCL dependencies – `ament_target_dependencies` doesn't respect the
# components/modules selected above and only links in `common` ,so we need
# to do this manually.
target_compile_definitions(dummy_perception_publisher_node PRIVATE ${PCL_DEFINITIONS})
target_include_directories(dummy_perception_publisher_node PRIVATE ${PCL_INCLUDE_DIRS})
# Unfortunately, this one can't be PRIVATE because only the plain or only the
# keyword (PRIVATE) signature of target_link_libraries can be used for one
# target, not both. The plain signature is already used inside
# `ament_target_dependencies` and possibly rosidl_target_interfaces.
target_link_libraries(dummy_perception_publisher_node ${PCL_LIBRARIES})
target_link_directories(dummy_perception_publisher_node PRIVATE ${PCL_LIBRARY_DIRS})


ament_auto_add_executable(empty_objects_publisher
src/empty_objects_publisher.cpp
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package(
INSTALL_TO_SHARE
launch
)
44 changes: 44 additions & 0 deletions simulator/dummy_perception_publisher/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# dummy_perception_publisher

## Purpose

This node publishes the result of the dummy detection with the type of perception.

## Inner-workings / Algorithms

## Inputs / Outputs

### Input

| Name | Type | Description |
| -------------- | ----------------------------------------- | ----------------------- |
| `/tf` | `tf2_msgs/TFMessage` | TF (self-pose) |
| `input/object` | `dummy_perception_publisher::msg::Object` | dummy detection objects |

### Output

| Name | Type | Description |
| ----------------------- | ----------------------------------------------------------- | ---------------------- |
| `output/dynamic_object` | `autoware_perception_msgs::msg::DetectedObjectsWithFeature` | Publishes objects |
| `output/points_raw` | `sensor_msgs::msg::PointCloud2` | point cloud of objects |

## Parameters

| Name | Type | Default Value | Explanation |
| --------------------------- | ------ | ------------- | ------------------------------------------- |
| `visible_range` | double | 100.0 | sensor visible range [m] |
| `detection_successful_rate` | double | 0.8 | sensor detection rate. (min) 0.0 - 1.0(max) |
| `enable_ray_tracing` | bool | true | if True, use ray tracking |
| `use_object_recognition` | bool | true | if True, publish objects topic |

### Node Parameters

None.

### Core Parameters

None.

## Assumptions / Known limits

TBD.
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
// Copyright 2020 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__NODE_HPP_
#define DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_

#include "dummy_perception_publisher/msg/object.hpp"

#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/detected_objects_with_feature.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

#include <pcl/common/distances.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <random>
#include <vector>

class DummyPerceptionPublisherNode : public rclcpp::Node
{
private:
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pointcloud_pub_;
rclcpp::Publisher<autoware_perception_msgs::msg::DetectedObjectsWithFeature>::SharedPtr
detected_object_with_feature_pub_;
rclcpp::Subscription<dummy_perception_publisher::msg::Object>::SharedPtr object_sub_;
rclcpp::TimerBase::SharedPtr timer_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
std::vector<dummy_perception_publisher::msg::Object> objects_;
double visible_range_;
double detection_successful_rate_;
bool enable_ray_tracing_;
bool use_object_recognition_;
bool use_real_param_;
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:
DummyPerceptionPublisherNode();
~DummyPerceptionPublisherNode() {}
};

#endif // DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
<?xml version="1.0" ?>

<launch>
<!-- dummy detection and sensor data -->
<arg name="visible_range" default="300.0" />
<arg name="real" default="true" />
<arg name="use_object_recognition" default="true" />
<arg name="use_traffic_light_recognition" default="false" />

<group>
<push-ros-namespace namespace="simulation"/>
<group if="$(var real)">
<node pkg="dummy_perception_publisher" exec="dummy_perception_publisher_node" name="dummy_perception_publisher" output="screen">
<remap from="output/dynamic_object" to="/perception/object_recognition/detection/labeled_clusters" />
<remap from="output/objects_pose" to="debug/object_pose" />
<remap from="output/points_raw" to="/perception/obstacle_segmentation/pointcloud" />
<remap from="input/object" to="dummy_perception_publisher/object_info" />
<remap from="input/reset" to="input/reset" />
<param name="visible_range" value="$(var visible_range)" />
<param name="detection_successful_rate" value="0.999" />
<param name="enable_ray_tracing" value="true" />
<param name="use_object_recognition" value="$(var use_object_recognition)" />
</node>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="input/objects" value="/perception/object_recognition/detection/labeled_clusters" />
<arg name="output/objects" value="/perception/object_recognition/detection/objects_with_feature" />
</include>
</group>
<group unless="$(var real)">
<node pkg="dummy_perception_publisher" exec="dummy_perception_publisher_node" name="dummy_perception_publisher" output="screen">
<remap from="output/dynamic_object" to="/perception/object_recognition/detection/objects_with_feature" />
<remap from="output/objects_pose" to="debug/object_pose" />
<remap from="output/points_raw" to="/perception/obstacle_segmentation/pointcloud" />
<remap from="input/object" to="dummy_perception_publisher/object_info" />
<remap from="input/reset" to="input/reset" />
<param name="visible_range" value="$(var visible_range)" />
<param name="detection_successful_rate" value="1.0" />
<param name="enable_ray_tracing" value="false" />
<param name="use_object_recognition" value="$(var use_object_recognition)" />
</node>
</group>

<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
<arg name="input" value="/perception/object_recognition/detection/objects_with_feature" />
<arg name="output" value="/perception/object_recognition/detection/objects" />
</include>

</group>

<!-- perception module -->
<group>
<push-ros-namespace namespace="perception"/>
<!-- object segmentation module -->
<group>
<push-ros-namespace namespace="obstacle_segmentation"/>
<!-- Occupancy Grid -->
<include file="$(find-pkg-share laserscan_to_occupancy_grid_map)/launch/laserscan_to_occupancy_grid_map.launch.py">
<arg name="input_obstacle_pointcloud" value="true" />
<arg name="input_obstacle_and_raw_pointcloud" value="false" />
<arg name="input/obstacle_pointcloud" value="/perception/obstacle_segmentation/pointcloud" />
</include>
</group>

<!-- object recognition module -->
<group if="$(var use_object_recognition)">
<push-ros-namespace namespace="object_recognition"/>
<!-- detection module -->
<!-- tracking module -->
<group>
<push-ros-namespace namespace="tracking"/>
<include file="$(find-pkg-share perception_launch)/launch/object_recognition/tracking/tracking.launch.xml">
</include>
</group>
<!-- prediction module -->
<group>
<push-ros-namespace namespace="prediction"/>
<include file="$(find-pkg-share perception_launch)/launch/object_recognition/prediction/prediction.launch.xml">
<arg name="use_vector_map" value="true" />
</include>
</group>
</group>

<group unless="$(var use_object_recognition)">
<push-ros-namespace namespace="object_recognition"/>
<node pkg="dummy_perception_publisher" exec="empty_objects_publisher" name="empty_objects_publisher" output="screen">
<remap from="~/output/objects" to="/perception/object_recognition/objects" />
</node>
</group>

<!-- traffic light module -->
<group if="$(var use_traffic_light_recognition)">
<push-ros-namespace namespace="traffic_light_recognition"/>
<include file="$(find-pkg-share perception_launch)/launch/traffic_light_recognition/traffic_light.launch.xml"></include>
</group>
</group>
</launch>
2 changes: 2 additions & 0 deletions simulator/dummy_perception_publisher/msg/InitialState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
geometry_msgs/PoseWithCovariance pose_covariance
geometry_msgs/TwistWithCovariance twist_covariance
11 changes: 11 additions & 0 deletions simulator/dummy_perception_publisher/msg/Object.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
std_msgs/Header header
unique_identifier_msgs/UUID id
dummy_perception_publisher/InitialState initial_state
autoware_auto_perception_msgs/ObjectClassification classification
autoware_auto_perception_msgs/Shape shape

uint8 ADD=0
uint8 MODIFY=1
uint8 DELETE=2
uint8 DELETEALL=3
int32 action
38 changes: 38 additions & 0 deletions simulator/dummy_perception_publisher/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dummy_perception_publisher</name>
<version>0.1.0</version>
<description>The dummy_perception_publisher package</description>

<maintainer email="[email protected]">Yukihiro Saito</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<build_depend>rosidl_default_generators</build_depend>

<exec_depend>rosidl_default_runtime</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>geometry_msgs</depend>
<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>unique_identifier_msgs</depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit 15ec6ff

Please sign in to comment.