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(dummy_perception_publisher): rework parameters #8660

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
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
1 change: 1 addition & 0 deletions simulator/dummy_perception_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,4 +69,5 @@ endif()
ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
11 changes: 1 addition & 10 deletions simulator/dummy_perception_publisher/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,16 +25,7 @@ This node publishes the result of the dummy detection with the type of perceptio

## 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 |
| `use_base_link_z` | bool | true | if True, node uses z coordinate of ego base_link |
| `publish_ground_truth` | bool | false | if True, publish ground truth objects |
| `use_fixed_random_seed` | bool | false | if True, use fixed random seed |
| `random_seed` | int | 0 | random seed |
{{json_to_markdown("simulator/dummy_perception_publisher/schema/dummy_perception_publisher.schema.json")}}

### Node Parameters

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
/**:
ros__parameters:
visible_range: 100.0 # m
detection_successful_rate: 0.8
enable_ray_tracing: true
use_object_recognition: true
use_base_link_z: true
object_centric_pointcloud: false
publish_ground_truth: false
random_seed: 0
use_fixed_random_seed: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Dummy Perception Publisher",
"type": "object",
"definitions": {
"dummy_perception_publisher_params": {
"type": "object",
"properties": {
"visible_range": {
"type": "number",
"default": 100.0,
"description": "sensor visible range [m]"
},
"detection_successful_rate": {
"type": "number",
"default": 0.8,
"minimum": 0.0,
"maximum": 1.0,
"description": "sensor detection rate."
},
"enable_ray_tracing": {
"type": "boolean",
"default": true,
"description": "if True, use ray tracing"
},
"use_object_recognition": {
"type": "boolean",
"default": true,
"description": "if True, publish objects topic"
},
"use_base_link_z": {
"type": "boolean",
"default": true,
"description": "if True, node uses z coordinate of ego base_link"
},
"object_centric_pointcloud": {
"type": "boolean",
"default": false,
"description": "if True, use object-centric point cloud for detection."
},
"publish_ground_truth": {
"type": "boolean",
"default": false,
"description": "if True, publish ground truth objects"
},
"random_seed": {
"type": "integer",
"default": 0,
"description": "random seed"
},
"use_fixed_random_seed": {
"type": "boolean",
"default": false,
"description": "if True, use fixed random seed"
}
},
"required": [
"visible_range",
"detection_successful_rate",
"enable_ray_tracing",
"use_object_recognition",
"use_base_link_z",
"object_centric_pointcloud",
"publish_ground_truth",
"random_seed",
"use_fixed_random_seed"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/dummy_perception_publisher_params"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
19 changes: 9 additions & 10 deletions simulator/dummy_perception_publisher/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,17 +127,16 @@ TrackedObject ObjectInfo::toTrackedObject(
DummyPerceptionPublisherNode::DummyPerceptionPublisherNode()
: Node("dummy_perception_publisher"), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_)
{
visible_range_ = this->declare_parameter("visible_range", 100.0);
detection_successful_rate_ = this->declare_parameter("detection_successful_rate", 0.8);
enable_ray_tracing_ = this->declare_parameter("enable_ray_tracing", true);
use_object_recognition_ = this->declare_parameter("use_object_recognition", true);
use_base_link_z_ = this->declare_parameter("use_base_link_z", true);
const bool object_centric_pointcloud =
this->declare_parameter("object_centric_pointcloud", false);
publish_ground_truth_objects_ = this->declare_parameter("publish_ground_truth", false);
visible_range_ = this->declare_parameter("visible_range");
detection_successful_rate_ = this->declare_parameter("detection_successful_rate");
enable_ray_tracing_ = this->declare_parameter("enable_ray_tracing");
use_object_recognition_ = this->declare_parameter("use_object_recognition");
use_base_link_z_ = this->declare_parameter("use_base_link_z");
const bool object_centric_pointcloud = this->declare_parameter("object_centric_pointcloud");
publish_ground_truth_objects_ = this->declare_parameter("publish_ground_truth");
const unsigned int random_seed =
static_cast<unsigned int>(this->declare_parameter("random_seed", 0));
const bool use_fixed_random_seed = this->declare_parameter("use_fixed_random_seed", false);
static_cast<unsigned int>(this->declare_parameter("random_seed"));
const bool use_fixed_random_seed = this->declare_parameter("use_fixed_random_seed");
Comment on lines +130 to +139
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

declare_parameter needs to explicitly specify the type like following.

visible_range_ = this->declare_parameter<double>("visible_range");
detection_successful_rate_ = this->declare_parameter<double>("detection_successful_rate");
enable_ray_tracing_ = this->declare_parameter<bool>("enable_ray_tracing");
use_object_recognition_ = this->declare_parameter<bool>("use_object_recognition");
use_base_link_z_ = this->declare_parameter<bool>("use_base_link_z");
const bool object_centric_pointcloud = this->declare_parameter<bool>("object_centric_pointcloud");
publish_ground_truth_objects_ = this->declare_parameter<bool>("publish_ground_truth");
const unsigned int random_seed =
  static_cast<unsigned int>(this->declare_parameter<int>("random_seed"));
const bool use_fixed_random_seed = this->declare_parameter<bool>("use_fixed_random_seed");


if (object_centric_pointcloud) {
pointcloud_creator_ =
Expand Down
Loading