Skip to content

Commit

Permalink
change ros parameter name
Browse files Browse the repository at this point in the history
Signed-off-by: MasatoSaeki <masato.saeki@tier4.jp>
  • Loading branch information
MasatoSaeki committed Dec 24, 2024
1 parent ac94a44 commit 227d539
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion perception/autoware_traffic_light_arbiter/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ The table below outlines how the matching process determines the output based on

| Name | Type | Default Value | Description |
| --------------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| `external_current_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with current time |
| `external_delay_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with current time |
| `external_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with a timestamp of perception message |
| `perception_time_tolerance` | double | 1.0 | The duration in seconds a perception message is considered valid for merging in comparison with a timestamp of external message |
| `external_priority` | bool | false | Whether or not externals signals take precedence over perception-based ones. If false, the merging uses confidence as a criteria |
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**:
ros__parameters:
external_current_time_tolerance: 5.0
external_delay_tolerance: 5.0
external_time_tolerance: 5.0
perception_time_tolerance: 1.0
external_priority: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class TrafficLightArbiter : public rclcpp::Node

std::unique_ptr<std::unordered_set<lanelet::Id>> map_regulatory_elements_set_;

double external_current_time_tolerance_;
double external_delay_tolerance_;
double external_time_tolerance_;
double perception_time_tolerance_;
bool external_priority_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,8 @@ namespace autoware
TrafficLightArbiter::TrafficLightArbiter(const rclcpp::NodeOptions & options)
: Node("traffic_light_arbiter", options)
{
external_current_time_tolerance_ =
this->declare_parameter<double>("external_current_time_tolerance", 5.0);
external_delay_tolerance_ =
this->declare_parameter<double>("external_delay_tolerance", 5.0);
external_time_tolerance_ = this->declare_parameter<double>("external_time_tolerance", 5.0);
perception_time_tolerance_ = this->declare_parameter<double>("perception_time_tolerance", 1.0);
external_priority_ = this->declare_parameter<bool>("external_priority", false);
Expand Down Expand Up @@ -131,7 +131,7 @@ void TrafficLightArbiter::onPerceptionMsg(const TrafficSignalArray::ConstSharedP

void TrafficLightArbiter::onExternalMsg(const TrafficSignalArray::ConstSharedPtr msg)
{
if ((this->now() - rclcpp::Time(msg->stamp)).seconds() > external_current_time_tolerance_) {
if ((this->now() - rclcpp::Time(msg->stamp)).seconds() > external_delay_tolerance_) {
RCLCPP_WARN_THROTTLE(
get_logger(), *get_clock(), 5000, "Received outdated V2X traffic signal messages");
return;
Expand Down

0 comments on commit 227d539

Please sign in to comment.