@@ -88,9 +88,9 @@ class PolylineTypeMap
88
88
}
89
89
}
90
90
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,
92
92
// return `-1`.
93
- int getTypeID (const std::string & type) const
93
+ int type_to_id (const std::string & type) const
94
94
{
95
95
return label_map_.count (type) == 0 ? -1 : label_map_.at (type);
96
96
}
@@ -112,35 +112,34 @@ class MTRNode : public rclcpp::Node
112
112
void callback (const TrackedObjects::ConstSharedPtr object_msg);
113
113
114
114
// 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);
116
116
117
117
// 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);
119
119
120
120
// Convert Lanelet to `PolylineData`.
121
- bool convertLaneletToPolyline ();
121
+ bool lanelet_to_polyline ();
122
122
123
123
// Remove ancient agent histories.
124
- void removeAncientAgentHistory (
124
+ void remove_ancient_history (
125
125
const float current_time, const TrackedObjects::ConstSharedPtr objects_msg);
126
126
127
127
// 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);
130
129
131
130
// 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 ;
133
132
134
133
// Extract target agents and return corresponding indices.
135
134
// 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);
137
136
138
137
// Return the timestamps relative from the first element.Return the timestamps relative from the
139
138
// first element.
140
- std::vector<float > getRelativeTimestamps () const ;
139
+ std::vector<float > get_relative_timestamps () const ;
141
140
142
141
// Generate `PredictedObject` from `PredictedTrajectory`.
143
- PredictedObject generatePredictedObject (
142
+ PredictedObject to_predicted_object (
144
143
const TrackedObject & object, const PredictedTrajectory & trajectory);
145
144
146
145
// ROS Publisher and Subscriber
0 commit comments