Skip to content

Commit f50f4e9

Browse files
committed
fix typo
1 parent d90ff4d commit f50f4e9

File tree

2 files changed

+18
-18
lines changed

2 files changed

+18
-18
lines changed

simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -138,7 +138,7 @@ class ActionNode : public BT::ActionNodeBase
138138
auto isOtherEntityAtConsideredAltitude(
139139
const traffic_simulator::CanonicalizedEntityStatus & entity_status) const -> bool;
140140

141-
std::shared_ptr<EuclideanDistancesMap> euclidean_distances_map_;
141+
std::shared_ptr<EuclideanDistancesMap> euclidean_distances_map_;
142142
};
143143
} // namespace entity_behavior
144144

simulation/behavior_tree_plugin/src/action_node.cpp

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -53,28 +53,28 @@ auto ActionNode::executeTick() -> BT::NodeStatus { return BT::ActionNodeBase::ex
5353

5454
auto ActionNode::getBlackBoardValues() -> void
5555
{
56-
if (!getInput<traffic_simulator::behavior::Request>("request_", request_)) {
57-
THROW_SIMULATION_ERROR("failed to get input request_ in ActionNode");
56+
if (!getInput<traffic_simulator::behavior::Request>("request", request_)) {
57+
THROW_SIMULATION_ERROR("failed to get input request in ActionNode");
5858
}
59-
if (!getInput<double>("step_time_", step_time_)) {
60-
THROW_SIMULATION_ERROR("failed to get input step_time_ in ActionNode");
59+
if (!getInput<double>("step_time", step_time_)) {
60+
THROW_SIMULATION_ERROR("failed to get input step_time in ActionNode");
6161
}
62-
if (!getInput<double>("current_time_", current_time_)) {
63-
THROW_SIMULATION_ERROR("failed to get input current_time_ in ActionNode");
62+
if (!getInput<double>("current_time", current_time_)) {
63+
THROW_SIMULATION_ERROR("failed to get input current_time in ActionNode");
6464
}
65-
if (!getInput<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils_", hdmap_utils_)) {
66-
THROW_SIMULATION_ERROR("failed to get input hdmap_utils_ in ActionNode");
65+
if (!getInput<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils", hdmap_utils_)) {
66+
THROW_SIMULATION_ERROR("failed to get input hdmap_utils in ActionNode");
6767
}
6868
if (!getInput<std::shared_ptr<traffic_simulator::TrafficLightsBase>>(
69-
"traffic_lights_", traffic_lights_)) {
70-
THROW_SIMULATION_ERROR("failed to get input traffic_lights_ in ActionNode");
69+
"traffic_lights", traffic_lights_)) {
70+
THROW_SIMULATION_ERROR("failed to get input traffic_lights in ActionNode");
7171
}
7272
if (!getInput<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>(
73-
"canonicalized_entity_status_", canonicalized_entity_status_)) {
74-
THROW_SIMULATION_ERROR("failed to get input canonicalized_entity_status_ in ActionNode");
73+
"canonicalized_entity_status", canonicalized_entity_status_)) {
74+
THROW_SIMULATION_ERROR("failed to get input canonicalized_entity_status in ActionNode");
7575
}
7676

77-
if (!getInput<std::optional<double>>("target_speed_", target_speed_)) {
77+
if (!getInput<std::optional<double>>("target_speed", target_speed_)) {
7878
target_speed_ = std::nullopt;
7979
}
8080

@@ -85,18 +85,18 @@ auto ActionNode::getBlackBoardValues() -> void
8585
"failed to get input matching_distance_for_lanelet_pose_calculation in ActionNode");
8686
}
8787

88-
if (!getInput<EntityStatusDict>("other_entity_status_", other_entity_status_)) {
88+
if (!getInput<EntityStatusDict>("other_entity_status", other_entity_status_)) {
8989
THROW_SIMULATION_ERROR("failed to get input other_entity_status_ in ActionNode");
9090
}
91-
if (!getInput<lanelet::Ids>("route_lanelets_", route_lanelets_)) {
91+
if (!getInput<lanelet::Ids>("route_lanelets", route_lanelets_)) {
9292
THROW_SIMULATION_ERROR("failed to get input route_lanelets_ in ActionNode");
9393
}
9494
if (!getInput<std::shared_ptr<EuclideanDistancesMap>>(
95-
"euclidean_distances_map_", euclidean_distances_map_)) {
95+
"euclidean_distances_map", euclidean_distances_map_)) {
9696
euclidean_distances_map_ = std::make_shared<EuclideanDistancesMap>();
9797
}
9898
if (!getInput<traffic_simulator_msgs::msg::BehaviorParameter>(
99-
"behavior_parameter_", behavior_parameter_)) {
99+
"behavior_parameter", behavior_parameter_)) {
100100
behavior_parameter_ = traffic_simulator_msgs::msg::BehaviorParameter();
101101
}
102102
}

0 commit comments

Comments
 (0)