提交 453a025d 编写于 作者: Y Yifei Jiang 提交者: Calvin Miao

tools: added more planning metrics.

上级 c24b5bc9
#!/usr/bin/env python
###############################################################################
# Copyright 2019 The Apollo Authors. All Rights Reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
###############################################################################
import numpy as np
class Curvature:
def __init__(self):
self.curvature_list = []
self.curvature_derivative_list = []
def put(self, adc_trajectory):
init_point = adc_trajectory.debug.planning_data.init_point
self.curvature.append(abs(init_point.path_point.kappa))
self.curvature_derivative.append(abs(init_point.path_point.dkappa))
def get_curvature(self):
curvature = {}
if len(self.curvature_list) == 0:
curvature["max"] = 0
curvature["avg"] = 0
return curvature
curvature["max"] = max(self.curvature_list, key=abs)
curvature["avg"] = np.average(np.absolute(self.curvature_list))
return curvature
def get_curvature_derivative(self):
curvature_derivative = {}
if len(self.curvature_derivative_list) == 0:
curvature_derivative["max"] = 0
curvature_derivative["avg"] = 0
curvature_derivative["max"] = max(self.curvature_derivative_list, key=abs)
curvature_derivative["avg"] = np.average(np.absolute(self.curvature_derivative_list))
return curvature_derivative
#!/usr/bin/env python
###############################################################################
# Copyright 2019 The Apollo Authors. All Rights Reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
###############################################################################
class FrameCount:
def __init__(self):
self.count = 0
def put(self, adc_trajectory):
self.count += 1
def get(self):
frame_count = {}
frame_count["total"] = self.count
return frame_count
#!/usr/bin/env python
###############################################################################
# Copyright 2019 The Apollo Authors. All Rights Reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
###############################################################################
class LonAcceleration:
def __init__(self):
self.last_velocity = None
self.last_timestamp = None
self.last_acceleration = None
self.acceleration = []
self.deceleration = []
self.acc_jerk = []
self.dec_jerk = []
def put(self, adc_trajectory):
init_point = adc_trajectory.debug.planning_data.init_point
current_timestamp = adc_trajectory.header.timestamp_sec + init_point.relative_time
current_velocity = init_point.v
if self.last_timestamp is not None and self.last_velocity is not None:
duration = current_timestamp - self.last_timestamp
if duration > 0.03:
acc = (current_velocity - self.last_velocity) / duration
if acc > 0:
self.acceleration.append(acc)
elif acc < 0:
self.deceleration.append(acc)
self.last_timestamp = current_timestamp
self.last_velocity = current_velocity
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册