Skip to content

Commit

Permalink
chore(traffic_light_occlusion_predictor): created Schema file and upd…
Browse files Browse the repository at this point in the history
…ated ReadME file for parameters setting and deleted default parameter from the node.cpp file (#9998)

* feat(traffic_light_occlusion_predictor): Created Schema file and updated ReadME file for parameters setting and deleted default parameter from the node.cpp file

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

* style(pre-commit): autofix

* feat: modified the json schema and readme file as per comments

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

---------

Signed-off-by: vish0012 <[email protected]>
Co-authored-by: Masato Saeki <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
3 people authored Feb 4, 2025
1 parent bd84834 commit fd7db7b
Show file tree
Hide file tree
Showing 3 changed files with 72 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,4 @@ If no point cloud is received or all point clouds have very large stamp differen

## Node parameters

| Parameter | Type | Description |
| ------------------------------------ | ------ | ------------------------------------------------------------- |
| `azimuth_occlusion_resolution_deg` | double | azimuth resolution of LiDAR point cloud (degree) |
| `elevation_occlusion_resolution_deg` | double | elevation resolution of LiDAR point cloud (degree) |
| `max_valid_pt_dist` | double | The points within this distance would be used for calculation |
| `max_image_cloud_delay` | double | The maximum delay between LiDAR point cloud and camera image |
| `max_wait_t` | double | The maximum time waiting for the LiDAR point cloud |
| `max_occlusion_ratio` | int | The maximum occlusion ratio for setting signal as unknown |
{{ json_to_markdown("perception/autoware_traffic_light_occlusion_predictor/schema/traffic_light_occlusion_predictor.schema.json") }}
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "autoware_traffic_light_occlusion_predictor parameter",
"type": "object",
"definitions": {
"autoware_traffic_light_occlusion_predictor": {
"type": "object",
"properties": {
"azimuth_occlusion_resolution_deg": {
"type": "number",
"description": "Azimuth resolution of LiDAR point cloud (degree).",
"default": 0.15
},
"elevation_occlusion_resolution_deg": {
"type": "number",
"description": "Elevation resolution of LiDAR point cloud (degree).",
"default": 0.08
},
"max_valid_pt_dist": {
"type": "number",
"description": "The points within this distance would be used for calculation.",
"default": 50.0
},
"max_image_cloud_delay": {
"type": "number",
"description": "The maximum delay between LiDAR point cloud and camera image.",
"default": 0.5
},
"max_wait_t": {
"type": "number",
"description": "The maximum time waiting for the LiDAR point cloud.",
"default": 0.05
},
"max_occlusion_ratio": {
"type": "integer",
"description": "Maximum occlusion ratio for traffic lights.",
"default": 50
}
},
"required": [
"azimuth_occlusion_resolution_deg",
"elevation_occlusion_resolution_deg",
"max_valid_pt_dist",
"max_image_cloud_delay",
"max_wait_t",
"max_occlusion_ratio"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/autoware_traffic_light_occlusion_predictor"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,13 @@ TrafficLightOcclusionPredictorNode::TrafficLightOcclusionPredictorNode(

// configuration parameters
config_.azimuth_occlusion_resolution_deg =
declare_parameter<double>("azimuth_occlusion_resolution_deg", 0.15);
declare_parameter<double>("azimuth_occlusion_resolution_deg");
config_.elevation_occlusion_resolution_deg =
declare_parameter<double>("elevation_occlusion_resolution_deg", 0.08);
config_.max_valid_pt_dist = declare_parameter<double>("max_valid_pt_dist", 50.0);
config_.max_image_cloud_delay = declare_parameter<double>("max_image_cloud_delay", 1.0);
config_.max_wait_t = declare_parameter<double>("max_wait_t", 0.02);
config_.max_occlusion_ratio = declare_parameter<int>("max_occlusion_ratio", 50);
declare_parameter<double>("elevation_occlusion_resolution_deg");
config_.max_valid_pt_dist = declare_parameter<double>("max_valid_pt_dist");
config_.max_image_cloud_delay = declare_parameter<double>("max_image_cloud_delay");
config_.max_wait_t = declare_parameter<double>("max_wait_t");
config_.max_occlusion_ratio = declare_parameter<int>("max_occlusion_ratio");

cloud_occlusion_predictor_ = std::make_shared<CloudOcclusionPredictor>(
this, config_.max_valid_pt_dist, config_.azimuth_occlusion_resolution_deg,
Expand Down

0 comments on commit fd7db7b

Please sign in to comment.