Skip to content

Commit 3d947af

Browse files
committed
refactor: apply lower_camel
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
1 parent 434262c commit 3d947af

File tree

3 files changed

+63
-61
lines changed

3 files changed

+63
-61
lines changed

perception/autoware_mtr/config/mtr.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@
1212
intention_point_filepath: "$(var data_path)/intention_point.csv"
1313
num_intention_point_cluster: 64
1414
polyline_label_path: "$(var data_path)/polyline_label.txt"
15+
static_inference:
16+
num_target: 2
17+
num_agent: 7
1518
build_params:
1619
is_dynamic: false
1720
precision: "FP32"

perception/autoware_mtr/include/autoware/mtr/node.hpp

+11-12
Original file line numberDiff line numberDiff line change
@@ -88,9 +88,9 @@ class PolylineTypeMap
8888
}
8989
}
9090

91-
// Return the ID of the corresponding label type. If specified type is not contained in map,
91+
// Return the ID corresponding to the label type. If specified type is not contained in map,
9292
// return `-1`.
93-
int getTypeID(const std::string & type) const
93+
int type_to_id(const std::string & type) const
9494
{
9595
return label_map_.count(type) == 0 ? -1 : label_map_.at(type);
9696
}
@@ -112,35 +112,34 @@ class MTRNode : public rclcpp::Node
112112
void callback(const TrackedObjects::ConstSharedPtr object_msg);
113113

114114
// Callback being invoked when the HD map topic is subscribed.
115-
void onMap(const LaneletMapBin::ConstSharedPtr map_msg);
115+
void on_map(const LaneletMapBin::ConstSharedPtr map_msg);
116116

117117
// Callback being invoked when the Ego's odometry topic is subscribed.
118-
void onEgo(const Odometry::ConstSharedPtr ego_msg);
118+
void on_ego(const Odometry::ConstSharedPtr ego_msg);
119119

120120
// Convert Lanelet to `PolylineData`.
121-
bool convertLaneletToPolyline();
121+
bool lanelet_to_polyline();
122122

123123
// Remove ancient agent histories.
124-
void removeAncientAgentHistory(
124+
void remove_ancient_history(
125125
const float current_time, const TrackedObjects::ConstSharedPtr objects_msg);
126126

127127
// Appends new states to history.
128-
void updateAgentHistory(
129-
const float current_time, const TrackedObjects::ConstSharedPtr objects_msg);
128+
void update_history(const float current_time, const TrackedObjects::ConstSharedPtr objects_msg);
130129

131130
// Extract ego state stored in the buffer which has the nearest timestamp from current timestamp.
132-
AgentState extractNearestEgo(const float current_time) const;
131+
AgentState lookup_ego_state(const float current_time) const;
133132

134133
// Extract target agents and return corresponding indices.
135134
// NOTE: Extract targets in order of proximity, closest first.
136-
std::vector<size_t> extractTargetAgent(const std::vector<AgentHistory> & histories);
135+
std::vector<size_t> extract_target_agents(const std::vector<AgentHistory> & histories);
137136

138137
// Return the timestamps relative from the first element.Return the timestamps relative from the
139138
// first element.
140-
std::vector<float> getRelativeTimestamps() const;
139+
std::vector<float> get_relative_timestamps() const;
141140

142141
// Generate `PredictedObject` from `PredictedTrajectory`.
143-
PredictedObject generatePredictedObject(
142+
PredictedObject to_predicted_object(
144143
const TrackedObject & object, const PredictedTrajectory & trajectory);
145144

146145
// ROS Publisher and Subscriber

0 commit comments

Comments
 (0)