From 606690c73dbeaa18a9a7b8868ee4910502011fe9 Mon Sep 17 00:00:00 2001 From: Xiangquan Xiao Date: Thu, 4 Apr 2019 11:36:12 -0700 Subject: [PATCH] Robot: Code clean. (#7655) --- modules/canbus/README.md | 8 ++--- modules/dreamview/README.md | 4 +-- modules/localization/README.md | 6 ++-- modules/localization/README_cn.md | 2 +- modules/localization/msf/README.md | 2 +- .../msf/common/util/frame_transform.cc | 4 +-- .../msf/local_map/ndt_map/ndt_map_matrix.cc | 4 +-- modules/localization/ndt/README.md | 2 +- .../ndt/ndt_locator/lidar_locator_ndt.cc | 2 +- .../ndt/ndt_locator/ndt_solver_test.cc | 2 +- .../ndt_locator/ndt_voxel_grid_covariance.h | 6 ++-- modules/perception/README.md | 4 +-- modules/perception/camera/common/timer.h | 4 +-- .../camera/lib/lane/common/common_functions.h | 4 +-- .../camera/test/camera_common_undistortion.cc | 8 ++--- .../camera/test/camera_common_undistortion.h | 8 ++--- .../camera/test/camera_lib_interface_test.cc | 32 ++++++++--------- .../camera_lib_lane_common_functions_test.cc | 4 +-- ...b_traffic_light_detector_detection_test.cc | 6 ++-- ...traffic_light_detector_recognition_test.cc | 18 +++++----- .../obstacle_detection/obstacle_detection.cc | 2 +- modules/planning/README.md | 10 +++--- modules/planning/README_cn.md | 4 +-- .../distance_approach_ipopt_cuda_interface.cc | 10 +++--- ...ance_approach_ipopt_cuda_interface_test.cc | 4 +-- .../distance_approach_ipopt_interface.cc | 10 +++--- .../distance_approach_ipopt_interface_test.cc | 4 +-- ...ual_variable_warm_start_ipopt_interface.cc | 10 +++--- ..._variable_warm_start_ipopt_qp_interface.cc | 8 ++--- modules/prediction/README.md | 4 +-- modules/routing/README.md | 2 +- .../tools/localization/evaluate_compare.py | 4 +-- modules/tools/mapviewers/README.md | 6 ++-- modules/tools/navigation/config/README.md | 4 +-- modules/tools/navigator/README.md | 34 +++++++++---------- modules/tools/navigator/dbmap/README.md | 4 +-- .../hybrid_a_star_visualizer.py | 2 +- .../common/online_to_offline.py | 4 +-- .../data_pipelines/common/trajectory.py | 2 +- .../multiple_gpu_estimator/mlp_main.py | 2 +- .../evaluate_prediction_result.py | 2 +- modules/tools/record_analyzer/README.md | 10 +++--- modules/tools/record_analyzer/main.py | 6 ++-- .../module_planning_analyzer.py | 16 ++++----- .../record_analyzer/tools/dump_message.py | 6 ++-- modules/tools/record_play/README.md | 2 +- modules/tools/rosbag/stat_static_info.py | 2 +- 47 files changed, 152 insertions(+), 152 deletions(-) diff --git a/modules/canbus/README.md b/modules/canbus/README.md index eb380201c24..757ceb33e50 100644 --- a/modules/canbus/README.md +++ b/modules/canbus/README.md @@ -17,15 +17,15 @@ The major components in canbus module are: * **CAN Client** - CAN client has been moved to `/modules/drivers/canbus` since it is shared by different sensors utilizing the canbus protocol -You can implement your own CAN client in the folder `can_client` by inheriting from the `CanClient` class. - +You can implement your own CAN client in the folder `can_client` by inheriting from the `CanClient` class. + ``` Note: Do not forget to register your CAN client in `CanClientFactory`. ``` -You can also implement your own vehicle controller and message manager in the folder `vehicle` by inheriting from `VehicleController` and `MessageManager`. - +You can also implement your own vehicle controller and message manager in the folder `vehicle` by inheriting from `VehicleController` and `MessageManager`. + ``` Note: Do not forget to register your vehicle in `VehicleFactory`. diff --git a/modules/dreamview/README.md b/modules/dreamview/README.md index 0b49994b042..f5281e22e3f 100644 --- a/modules/dreamview/README.md +++ b/modules/dreamview/README.md @@ -2,7 +2,7 @@ # Dreamview ## Introduction -Dreamview or Apollo's HMI module provides a web application that helps developers visualize the output of other relevant autonomous driving modules, e.g. the vehicle's planning trajectory, car localization, chassis status etc. +Dreamview or Apollo's HMI module provides a web application that helps developers visualize the output of other relevant autonomous driving modules, e.g. the vehicle's planning trajectory, car localization, chassis status etc. ## Input Currently Dreamview monitors the following messages: @@ -13,7 +13,7 @@ Dreamview or Apollo's HMI module provides a web application that helps developer * Perception Obstacles, defined by Protobuf message `PerceptionObstacles`, which can be found in file `perception/proto/perception_obstacle.proto`. * Prediction, defined by Protobuf message `PredictionObstacles`, which can be found in file `prediction/proto/prediction_obstacle.proto`. * Routing, defined by Protobuf message `RoutingResponse`, which can be found in file `routing/proto/routing.proto`. - + ## Output A web-based dynamic 3D rendering of the monitored messages in a simulated world. diff --git a/modules/localization/README.md b/modules/localization/README.md index b855af28e9f..4886c78bea1 100644 --- a/modules/localization/README.md +++ b/modules/localization/README.md @@ -9,7 +9,7 @@ In the provided RTK localization method, there are two inputs: - GPS - The Global Positioning System - IMU - Inertial Measurement Unit - + In the multi-sensor fusion localization method, there are three inputs: - GPS - The Global Positioning System - IMU - Inertial Measurement Unit @@ -20,7 +20,7 @@ Guowei Wan, Xiaolong Yang, Renlan Cai, Hao Li, Yao Zhou, Hao Wang, Shiyu Song. "Robust and Precise Vehicle Localization Based on Multi-Sensor Fusion in Diverse City Scenes," 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, QLD, 2018, pp. 4670-4677. doi: 10.1109/ICRA.2018.8461224. [link](https://ieeexplore.ieee.org/document/8461224) -## Output +## Output An object instance defined by Protobuf message `LocalizationEstimate`, which can be found in file `localization/proto/localization.proto`. ## Implementing Localization @@ -35,7 +35,7 @@ An object instance defined by Protobuf message `LocalizationEstimate`, which can ``` localization_factory_.Register(LocalizationConfig::FOO, []()->LocalizationBase* { return new FooLocalization(); }); ``` - + 4. Make sure your code compiles by including the header files that defines class `FooLocalization` 1. Now you can go back to the `apollo` root directory and build your code with command `bash apollo.sh build` diff --git a/modules/localization/README_cn.md b/modules/localization/README_cn.md index 87085a01bc5..0778d5ca7f3 100644 --- a/modules/localization/README_cn.md +++ b/modules/localization/README_cn.md @@ -28,7 +28,7 @@ 1. 在`proto/localization_config.proto`的`LocalizationType enum type`中添加Foo。 1. 转到`modules/localization`目录,并创建一个Foo目录。在Foo目录中,根据rtk目录中的`RTKLocalization`类增加`FooLocalization`类。`FooLocalization`必须是`LocalizationBase`的子类。根据`rtk/BUILD`还需创建文件`foo/BUILD`。 - + 1. 您需要在函数`Localization::RegisterLocalizationMethods()`中注册`FooLocalization`,它位于CPP文件`localization.cc`中。您可以通过在函数的末尾插入以下代码来注册: ``` localization_factory_.Register(LocalizationConfig::FOO, []()->LocalizationBase* { return new FooLocalization(); }); diff --git a/modules/localization/msf/README.md b/modules/localization/msf/README.md index 2458c00d277..ac2ddf8df58 100644 --- a/modules/localization/msf/README.md +++ b/modules/localization/msf/README.md @@ -4,7 +4,7 @@ The goal of multi-sensor localization is to provide a robust method which can achieve high localization accuracy and resilience in challenging scenes, such as urban downtown, highways, and tunnels. It adaptively uses information from complementary sensors such as GNSS, LiDAR and IMU. If you want to know more details, please refer to our paper *Guowei Wan, Xiaolong Yang, Renlan Cai, Hao Li, Yao Zhou, Hao Wang, Shiyu Song. "Robust and Precise Vehicle Localization Based on Multi-Sensor Fusion in Diverse City Scenes," 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, QLD, 2018, pp. 4670-4677. doi: 10.1109/ICRA.2018.8461224.* [link](https://ieeexplore.ieee.org/document/8461224) - + Currently this localization method only works for x86_64 platform diff --git a/modules/localization/msf/common/util/frame_transform.cc b/modules/localization/msf/common/util/frame_transform.cc index bbead216623..bde1d7b45a6 100644 --- a/modules/localization/msf/common/util/frame_transform.cc +++ b/modules/localization/msf/common/util/frame_transform.cc @@ -40,7 +40,7 @@ bool FrameTransform::LatlonToUtmXY(double lon_rad, double lat_rad, } double longitude = lon_rad; double latitude = lat_rad; - pj_transform(pj_latlon, pj_utm, 1, 1, &longitude, &latitude, NULL); + pj_transform(pj_latlon, pj_utm, 1, 1, &longitude, &latitude, nullptr); utm_xy->x = longitude; utm_xy->y = latitude; pj_free(pj_latlon); @@ -61,7 +61,7 @@ bool FrameTransform::UtmXYToLatlon(double x, double y, int zone, bool southhemi, if (!(pj_utm = pj_init_plus(utm_dst.str().c_str()))) { return false; } - pj_transform(pj_utm, pj_latlon, 1, 1, &x, &y, NULL); + pj_transform(pj_utm, pj_latlon, 1, 1, &x, &y, nullptr); latlon->log = x; latlon->lat = y; pj_free(pj_latlon); diff --git a/modules/localization/msf/local_map/ndt_map/ndt_map_matrix.cc b/modules/localization/msf/local_map/ndt_map/ndt_map_matrix.cc index c355f08025c..37d31662d7b 100644 --- a/modules/localization/msf/local_map/ndt_map/ndt_map_matrix.cc +++ b/modules/localization/msf/local_map/ndt_map/ndt_map_matrix.cc @@ -319,7 +319,7 @@ void NdtMapCells::Reduce(NdtMapCells* cell, const NdtMapCells& cell_new) { NdtMapMatrix::NdtMapMatrix() { rows_ = 0; cols_ = 0; - map3d_cells_ = NULL; + map3d_cells_ = nullptr; } NdtMapMatrix::~NdtMapMatrix() { @@ -352,7 +352,7 @@ void NdtMapMatrix::Init(unsigned int rows, unsigned int cols) { if (map3d_cells_) { delete[] map3d_cells_; } - map3d_cells_ = NULL; + map3d_cells_ = nullptr; map3d_cells_ = new NdtMapCells[rows * cols]; rows_ = rows; cols_ = cols; diff --git a/modules/localization/ndt/README.md b/modules/localization/ndt/README.md index 7c404805607..1b767e88aa9 100644 --- a/modules/localization/ndt/README.md +++ b/modules/localization/ndt/README.md @@ -15,7 +15,7 @@ * Localization result defined by Protobuf message `LocalizationEstimate`, which can be found in file `localization/proto/localization.proto`. ( `/apollo/localization/pose`) ### NDT Localization Setting -under some circumstance, we need to balance the speed and accuracy of the algorithm. So we expose some parameters of NDT matching process, It includes `online_resolution` for online pointcloud, `ndt_max_iterations` for iterative optimization of NDT matching, `ndt_target_resolution` for target resolution, `ndt_line_search_step_size` for searching step size of iteration and `ndt_transformation_epsilon` for convergence condition. +under some circumstance, we need to balance the speed and accuracy of the algorithm. So we expose some parameters of NDT matching process, It includes `online_resolution` for online pointcloud, `ndt_max_iterations` for iterative optimization of NDT matching, `ndt_target_resolution` for target resolution, `ndt_line_search_step_size` for searching step size of iteration and `ndt_transformation_epsilon` for convergence condition. ## Generate NDT Localization Map NDT Localization map is used for NDT-based localization, which is a voxel-grid representation of the environment. Each cell stores the centroid and relative covariance of the points in the cell. The map is organized as a group of map nodes. For more information, please refer to `apollo/modules/localization/msf/local_map/ndt_map`. diff --git a/modules/localization/ndt/ndt_locator/lidar_locator_ndt.cc b/modules/localization/ndt/ndt_locator/lidar_locator_ndt.cc index 54c3850c418..14f5302c84e 100644 --- a/modules/localization/ndt/ndt_locator/lidar_locator_ndt.cc +++ b/modules/localization/ndt/ndt_locator/lidar_locator_ndt.cc @@ -428,7 +428,7 @@ void LidarLocatorNdt::ComposeMapCells( if (map_nodes_zones[y * 3 + x][2] - map_nodes_zones[y * 3 + x][0] >= 0 && map_nodes_zones[y * 3 + x][3] - map_nodes_zones[y * 3 + x][1] >= 0) { // get map node - NdtMapNode* map_node_ptr = NULL; + NdtMapNode* map_node_ptr = nullptr; if (x == 0 && y == 0) { map_node_ptr = map_node_lt; } else { diff --git a/modules/localization/ndt/ndt_locator/ndt_solver_test.cc b/modules/localization/ndt/ndt_locator/ndt_solver_test.cc index d13767b0e63..56be2576f07 100644 --- a/modules/localization/ndt/ndt_locator/ndt_solver_test.cc +++ b/modules/localization/ndt/ndt_locator/ndt_solver_test.cc @@ -111,7 +111,7 @@ TEST_F(NdtSolverTestSuite, NdtSolver) { for (auto itr = buf.begin(); itr != buf.end(); ++itr, ++index) { msf::NdtMapNode* ndt_map_node = static_cast(ndt_map.GetMapNodeSafe(*itr)); - if (ndt_map_node == NULL) { + if (ndt_map_node == nullptr) { AERROR << "index: " << index << " is a NULL pointer!" << std::endl; continue; } diff --git a/modules/localization/ndt/ndt_locator/ndt_voxel_grid_covariance.h b/modules/localization/ndt/ndt_locator/ndt_voxel_grid_covariance.h index d7600308ab1..0ebc3f05097 100644 --- a/modules/localization/ndt/ndt_locator/ndt_voxel_grid_covariance.h +++ b/modules/localization/ndt/ndt_locator/ndt_voxel_grid_covariance.h @@ -161,7 +161,7 @@ class VoxelGridCovariance { inline LeafConstPtr GetLeaf(int index) { typename std::map::iterator leaf_iter = leaves_.find(index); if (leaf_iter == leaves_.end()) { - return NULL; + return nullptr; } LeafConstPtr ret(&(leaf_iter->second)); return ret; @@ -189,7 +189,7 @@ class VoxelGridCovariance { // Find leaf associated with index typename std::map::iterator leaf_iter = leaves_.find(idx); if (leaf_iter == leaves_.end()) { - return NULL; + return nullptr; } // If such a leaf exists return the pointer to the leaf structure LeafConstPtr ret(&(leaf_iter->second)); @@ -216,7 +216,7 @@ class VoxelGridCovariance { // Find leaf associated with index typename std::map::iterator leaf_iter = leaves_.find(idx); if (leaf_iter == leaves_.end()) { - return NULL; + return nullptr; } // If such a leaf exists return the pointer to the leaf structure LeafConstPtr ret(&(leaf_iter->second)); diff --git a/modules/perception/README.md b/modules/perception/README.md index 61e84f879da..845725a29ab 100644 --- a/modules/perception/README.md +++ b/modules/perception/README.md @@ -44,7 +44,7 @@ The perception module outputs are: 1. Set up the general settings in the configuration file `modules/perception/conf/perception_lowcost.conf`. 2. Run the command `./scripts/bootstrap.sh` to launch the web GUI. 3. Select the vehicle model in the web GUI. -4. Launch the perception module using the command `./scripts/perception_lowcost_vis.sh start` or by enabling the perception button on the *Module Controller* page of the web GUI. The command for stopping perception is `./scripts/perception_lowcost_vis.sh stop`. Note: please do not try to use GUI to enable perception but use script to stop it, vice versa. +4. Launch the perception module using the command `./scripts/perception_lowcost_vis.sh start` or by enabling the perception button on the *Module Controller* page of the web GUI. The command for stopping perception is `./scripts/perception_lowcost_vis.sh stop`. Note: please do not try to use GUI to enable perception but use script to stop it, vice versa. 5. Download the demo data from the Apollo [Open Data Platform](http://data.apollo.auto). ``` @@ -59,7 +59,7 @@ Note: See [How to Run Perception Module on Your Local Computer](https://github.com/ApolloAuto/apollo/blob/master/docs/howto/how_to_run_perception_module_on_your_local_computer.md). -3. This module contains a redistribution in binary form of a modified version of [caffe](https://github.com/BVLC/caffe). +3. This module contains a redistribution in binary form of a modified version of [caffe](https://github.com/BVLC/caffe). A copy of the caffe's original copyright statement is included below: ``` diff --git a/modules/perception/camera/common/timer.h b/modules/perception/camera/common/timer.h index c316d92ab65..75ad1d03a4b 100644 --- a/modules/perception/camera/common/timer.h +++ b/modules/perception/camera/common/timer.h @@ -24,10 +24,10 @@ namespace camera { class Timer { public: Timer() { Tic(); } - void Tic() { gettimeofday(&start_tv_, NULL); } + void Tic() { gettimeofday(&start_tv_, nullptr); } uint64_t Toc() { struct timeval end_tv; - gettimeofday(&end_tv, NULL); + gettimeofday(&end_tv, nullptr); uint64_t elapsed = (end_tv.tv_sec - start_tv_.tv_sec) * 1000000 + (end_tv.tv_usec - start_tv_.tv_usec); Tic(); diff --git a/modules/perception/camera/lib/lane/common/common_functions.h b/modules/perception/camera/lib/lane/common/common_functions.h index a5d63d7bfb3..77bdd0e5e73 100644 --- a/modules/perception/camera/lib/lane/common/common_functions.h +++ b/modules/perception/camera/lib/lane/common/common_functions.h @@ -46,7 +46,7 @@ bool PolyFit(const std::vector>& pos_vec, const int& order, Eigen::Matrix* coeff, const bool& is_x_axis = true) { - if (coeff == NULL) { + if (coeff == nullptr) { AERROR << "The coefficient pointer is NULL."; return false; } @@ -110,7 +110,7 @@ template bool RansacFitting(std::vector>* pos_vec, Eigen::Matrix* coeff, const int max_iters = 100, const int N = 5, Dtype inlier_thres = 0.1) { - if (coeff == NULL) { + if (coeff == nullptr) { AERROR << "The coefficient pointer is NULL."; return false; } diff --git a/modules/perception/camera/test/camera_common_undistortion.cc b/modules/perception/camera/test/camera_common_undistortion.cc index b59aca42158..812c3ff953e 100644 --- a/modules/perception/camera/test/camera_common_undistortion.cc +++ b/modules/perception/camera/test/camera_common_undistortion.cc @@ -135,19 +135,19 @@ int ImageGpuPreprocessHandler::handle(uint8_t *src, uint8_t *dst) { int ImageGpuPreprocessHandler::release(void) { if (_d_mapy) { BASE_CUDA_CHECK(cudaFree(_d_mapy)); - _d_mapy = NULL; + _d_mapy = nullptr; } if (_d_mapx) { BASE_CUDA_CHECK(cudaFree(_d_mapx)); - _d_mapx = NULL; + _d_mapx = nullptr; } if (_d_dst) { BASE_CUDA_CHECK(cudaFree(_d_dst)); - _d_dst = NULL; + _d_dst = nullptr; } if (_d_rgb) { BASE_CUDA_CHECK(cudaFree(_d_rgb)); - _d_rgb = NULL; + _d_rgb = nullptr; } _inited = false; return 0; diff --git a/modules/perception/camera/test/camera_common_undistortion.h b/modules/perception/camera/test/camera_common_undistortion.h index 6f5245cf549..7e498abda77 100644 --- a/modules/perception/camera/test/camera_common_undistortion.h +++ b/modules/perception/camera/test/camera_common_undistortion.h @@ -43,10 +43,10 @@ class ImageGpuPreprocessHandler { int *height, std::vector *D, std::vector *K); - float *_d_mapx = NULL; - float *_d_mapy = NULL; - uint8_t *_d_rgb = NULL; - uint8_t *_d_dst = NULL; + float *_d_mapx = nullptr; + float *_d_mapy = nullptr; + uint8_t *_d_rgb = nullptr; + uint8_t *_d_dst = nullptr; int _width = 0; // image cols int _height = 0; // image rows diff --git a/modules/perception/camera/test/camera_lib_interface_test.cc b/modules/perception/camera/test/camera_lib_interface_test.cc index e6f5e8329f8..15b2566eb4e 100644 --- a/modules/perception/camera/test/camera_lib_interface_test.cc +++ b/modules/perception/camera/test/camera_lib_interface_test.cc @@ -59,7 +59,7 @@ REGISTER_INFERENCE_ENGINE(MyInferenceEngine); TEST(ObstacleInterfaceTest, test_inference_engine) { BaseInferenceEngine* inference_engine = BaseInferenceEngineRegisterer::GetInstanceByName("MyInferenceEngine"); - EXPECT_TRUE(inference_engine != NULL); + EXPECT_TRUE(inference_engine != nullptr); EXPECT_EQ(inference_engine->Name(), "MyInferenceEngine"); } @@ -86,7 +86,7 @@ REGISTER_OBSTACLE_DETECTOR(MyObstacleDetector); TEST(ObstacleInterfaceTest, test_camera_detector) { BaseObstacleDetector* camera_detector = BaseObstacleDetectorRegisterer::GetInstanceByName("MyObstacleDetector"); - EXPECT_TRUE(camera_detector != NULL); + EXPECT_TRUE(camera_detector != nullptr); EXPECT_EQ(camera_detector->Name(), "MyObstacleDetector"); } @@ -125,7 +125,7 @@ REGISTER_OBSTACLE_TRACKER(MyObstacleTracker); TEST(ObstacleInterfaceTest, test_camera_tracker) { BaseObstacleTracker* camera_tracker = BaseObstacleTrackerRegisterer::GetInstanceByName("MyObstacleTracker"); - EXPECT_TRUE(camera_tracker != NULL); + EXPECT_TRUE(camera_tracker != nullptr); EXPECT_EQ(camera_tracker->Name(), "MyObstacleTracker"); } @@ -152,7 +152,7 @@ TEST(ObstacleInterfaceTest, test_camera_transformer) { BaseObstacleTransformer* camera_transformer = BaseObstacleTransformerRegisterer::GetInstanceByName( "MyObstacleTransformer"); - EXPECT_TRUE(camera_transformer != NULL); + EXPECT_TRUE(camera_transformer != nullptr); EXPECT_EQ(camera_transformer->Name(), "MyObstacleTransformer"); } @@ -180,7 +180,7 @@ TEST(ObstacleInterfaceTest, test_camera_postprocessor) { BaseObstaclePostprocessor* camera_postprocessor = BaseObstaclePostprocessorRegisterer::GetInstanceByName( "MyObstaclePostprocessor"); - EXPECT_TRUE(camera_postprocessor != NULL); + EXPECT_TRUE(camera_postprocessor != nullptr); EXPECT_EQ(camera_postprocessor->Name(), "MyObstaclePostprocessor"); } @@ -208,7 +208,7 @@ TEST(TrafficLightInterfaceTest, test_traffic_light_detector) { BaseTrafficLightDetector* traffic_light_detector = BaseTrafficLightDetectorRegisterer::GetInstanceByName( "MyTrafficLightDetector"); - EXPECT_TRUE(traffic_light_detector != NULL); + EXPECT_TRUE(traffic_light_detector != nullptr); EXPECT_EQ(traffic_light_detector->Name(), "MyTrafficLightDetector"); } @@ -236,7 +236,7 @@ TEST(TrafficLightInterfaceTest, test_traffic_light_tracker) { BaseTrafficLightTracker* traffic_light_tracker = BaseTrafficLightTrackerRegisterer::GetInstanceByName( "MyTrafficLightTracker"); - EXPECT_TRUE(traffic_light_tracker != NULL); + EXPECT_TRUE(traffic_light_tracker != nullptr); EXPECT_EQ(traffic_light_tracker->Name(), "MyTrafficLightTracker"); } @@ -263,7 +263,7 @@ REGISTER_LANDMARK_DETECTOR(MyLandmarkDetector); TEST(LandmarkDetectorInterfaceTest, test_landmark_detector) { BaseLandmarkDetector* landmark_detector = BaseLandmarkDetectorRegisterer::GetInstanceByName("MyLandmarkDetector"); - EXPECT_TRUE(landmark_detector != NULL); + EXPECT_TRUE(landmark_detector != nullptr); EXPECT_EQ(landmark_detector->Name(), "MyLandmarkDetector"); } @@ -287,7 +287,7 @@ REGISTER_LANE_DETECTOR(MyLaneDetector); TEST(LaneInterfaceTest, test_lane_detector) { BaseLaneDetector* lane_detector = BaseLaneDetectorRegisterer::GetInstanceByName("MyLaneDetector"); - EXPECT_TRUE(lane_detector != NULL); + EXPECT_TRUE(lane_detector != nullptr); EXPECT_EQ(lane_detector->Name(), "MyLaneDetector"); } @@ -311,7 +311,7 @@ REGISTER_LANE_TRACKER(MyLaneTracker); TEST(LaneInterfaceTest, test_lane_tracker) { BaseLaneTracker* lane_tracker = BaseLaneTrackerRegisterer::GetInstanceByName("MyLaneTracker"); - EXPECT_TRUE(lane_tracker != NULL); + EXPECT_TRUE(lane_tracker != nullptr); EXPECT_EQ(lane_tracker->Name(), "MyLaneTracker"); } @@ -342,7 +342,7 @@ REGISTER_LANE_POSTPROCESSOR(MyLanePostprocessor); TEST(LaneInterfaceTest, test_lane_postprocessor) { BaseLanePostprocessor* lane_postprocessor = BaseLanePostprocessorRegisterer::GetInstanceByName("MyLanePostprocessor"); - EXPECT_TRUE(lane_postprocessor != NULL); + EXPECT_TRUE(lane_postprocessor != nullptr); EXPECT_EQ(lane_postprocessor->Name(), "MyLanePostprocessor"); } @@ -369,7 +369,7 @@ REGISTER_FEATURE_EXTRACTOR(MyFeatureExtractor); TEST(FeatureExtractorInterfaceTest, test_feature_extractor) { BaseFeatureExtractor* feature_extractor = BaseFeatureExtractorRegisterer::GetInstanceByName("MyFeatureExtractor"); - EXPECT_TRUE(feature_extractor != NULL); + EXPECT_TRUE(feature_extractor != nullptr); EXPECT_EQ(feature_extractor->Name(), "MyFeatureExtractor"); const int image_width = 200; @@ -419,7 +419,7 @@ REGISTER_SCENE_PARSER(MySceneParser); TEST(SceneInterfaceTest, test_scene_parser) { BaseSceneParser* scene_parser = BaseSceneParserRegisterer::GetInstanceByName("MySceneParser"); - EXPECT_TRUE(scene_parser != NULL); + EXPECT_TRUE(scene_parser != nullptr); EXPECT_EQ(scene_parser->Name(), "MySceneParser"); } @@ -444,7 +444,7 @@ REGISTER_CALIBRATOR(MyCalibrator); TEST(CalibratorInterfaceTest, test_calibrator) { BaseCalibrator* calibrator = BaseCalibratorRegisterer::GetInstanceByName("MyCalibrator"); - EXPECT_TRUE(calibrator != NULL); + EXPECT_TRUE(calibrator != nullptr); EXPECT_EQ(calibrator->Name(), "MyCalibrator"); } @@ -469,7 +469,7 @@ TEST(CalibrationServiceInterfaceTest, test_calibrator) { BaseCalibrationService* calibrator = BaseCalibrationServiceRegisterer::GetInstanceByName( "MyCalibrationService"); - EXPECT_TRUE(calibrator != NULL); + EXPECT_TRUE(calibrator != nullptr); EXPECT_EQ(calibrator->Name(), "MyCalibrationService"); } @@ -494,7 +494,7 @@ PERCEPTION_REGISTER_CAMERA_PERCEPTION(MyCameraPerception); TEST(CameraPerceptionInterfaceTest, test_camera_perception) { BaseCameraPerception* camera_perception = BaseCameraPerceptionRegisterer::GetInstanceByName("MyCameraPerception"); - EXPECT_TRUE(camera_perception != NULL); + EXPECT_TRUE(camera_perception != nullptr); EXPECT_EQ(camera_perception->Name(), "MyCameraPerception"); } diff --git a/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc b/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc index d366354590e..61b7c463625 100644 --- a/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc +++ b/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc @@ -27,13 +27,13 @@ namespace camera { TEST(CommonFunctions, poly_fit_error_test) { { - Eigen::Matrix *coeff = NULL; + Eigen::Matrix *coeff = nullptr; std::vector > pos_vec; int order = max_poly_order; EXPECT_FALSE(PolyFit(pos_vec, order, coeff)); } { - Eigen::Matrix *coeff = NULL; + Eigen::Matrix *coeff = nullptr; std::vector > pos_vec; int order = max_poly_order + 1; EXPECT_FALSE(PolyFit(pos_vec, order, coeff)); diff --git a/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc index bcc41cb2e81..fc2960cb5b6 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc @@ -66,7 +66,7 @@ TEST(DetectionTest, all) { "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/detection/img/img.png"); cv::cvtColor(origin_image, origin_image, cv::COLOR_BGR2RGB); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -151,7 +151,7 @@ TEST(DetectionTest, no_light) { "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/detection/img/img.png"); cv::cvtColor(origin_image, origin_image, cv::COLOR_BGR2RGB); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -201,7 +201,7 @@ TEST(DetectionTest, out_of_img_light) { "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/detection/img/img.png"); cv::cvtColor(origin_image, origin_image, cv::COLOR_BGR2RGB); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); diff --git a/modules/perception/camera/test/camera_lib_traffic_light_detector_recognition_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_detector_recognition_test.cc index 73d0428bbe1..d1a219233c2 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_detector_recognition_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_detector_recognition_test.cc @@ -30,7 +30,7 @@ TEST(RecognizeTest, yellow) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/yellow.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -86,7 +86,7 @@ TEST(RecognizeTest, red) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/red.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -142,7 +142,7 @@ TEST(RecognizeTest, green) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/green.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -194,7 +194,7 @@ TEST(RecognizeTest, black) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/black.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -250,7 +250,7 @@ TEST(RecognizeTest, no_detection) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/black.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -302,7 +302,7 @@ TEST(RecognizeTest, unknown_class) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/yellow.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -356,7 +356,7 @@ TEST(RecognizeTest, quadrate) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/green.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -412,7 +412,7 @@ TEST(RecognizeTest, horizontal) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/horizontal.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); @@ -474,7 +474,7 @@ TEST(RecognizeTest, no_light) { cv::Mat origin_image = cv::imread( "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/detector/recognition/img/horizontal.jpg"); - ASSERT_FALSE(origin_image.data == NULL); + ASSERT_FALSE(origin_image.data == nullptr); std::shared_ptr img_gpu_data; int size = origin_image.cols * origin_image.rows * origin_image.channels(); diff --git a/modules/perception/camera/tools/obstacle_detection/obstacle_detection.cc b/modules/perception/camera/tools/obstacle_detection/obstacle_detection.cc index 578561cb143..5e9b0a6e18c 100644 --- a/modules/perception/camera/tools/obstacle_detection/obstacle_detection.cc +++ b/modules/perception/camera/tools/obstacle_detection/obstacle_detection.cc @@ -236,7 +236,7 @@ int main() { EXPECT_TRUE(transformer->Transform(transformer_options, &frame)); FILE *fp = fopen(result_path.c_str(), "w"); - if (fp == NULL) { + if (fp == nullptr) { AINFO << "Failed to open " << result_path; return -1; } diff --git a/modules/planning/README.md b/modules/planning/README.md index 819348c5c7f..6ae0952a589 100644 --- a/modules/planning/README.md +++ b/modules/planning/README.md @@ -10,7 +10,7 @@ There are 3 main driving scenarios that we will focus on in Apollo 3.5, namely: ### Lane Follow - Default -As seen in the figure below, the lane-follow scenario, our default driving scenario, includes but is not limited to driving in a single lane (like cruising) or changing lane, following basic traffic convention or basic turning. +As seen in the figure below, the lane-follow scenario, our default driving scenario, includes but is not limited to driving in a single lane (like cruising) or changing lane, following basic traffic convention or basic turning. ![](images/Planning_default.png) @@ -31,7 +31,7 @@ In this scenario, if there is a static vehicle or a static obstacle in the lane There are two separate driving scenarios for STOP signs: -- Unprotected: In this scenario, the car is expected to navigate through a crossroad having a two-way STOP. Our ADC therefore has to creep through and gauge the crossroad's traffic density before continuing onto its path. +- Unprotected: In this scenario, the car is expected to navigate through a crossroad having a two-way STOP. Our ADC therefore has to creep through and gauge the crossroad's traffic density before continuing onto its path. ![](images/unprotected1.png) @@ -43,19 +43,19 @@ There are two separate driving scenarios for STOP signs: In order to safely pass through a STOP sign, both protected and unprotected, the following steps are performed: -- Arriving at the STOP sign: Perceive all other cars or obstacles that are currently waiting at the other stop signs +- Arriving at the STOP sign: Perceive all other cars or obstacles that are currently waiting at the other stop signs - Come to a complete stop: Monitor to see if the cars that were previously stationary at other STOP signs have moved or not. It is essential that the cars that arrived before have all left - Move forward slightly (Creep): Check to see if any other car is moving or in the case of unprotected stop, check to see if there are any oncoming vehicles on either side of the lane - Safely move through the crossroad ``` -Note: The team is working to add additional driving scenarios into our planner. One such example is handling Traffic Lights. +Note: The team is working to add additional driving scenarios into our planner. One such example is handling Traffic Lights. ``` ## Planning Module Architecture The architecture of the planning module has changed in Apollo 3.5 to reflect our modular approach towards different driving scenarios. -As seen in the figure below, in the planner, are individual driving scenarios discussed above along with their handlers. +As seen in the figure below, in the planner, are individual driving scenarios discussed above along with their handlers. Each driving scenario has its set of driving parameters that are unique to that scenario making it safer, efficient, easier to customize and debug and more flexible. Each stage is also configurable as it is divided into tasks and each task can be moved or created by editing the `config` file of that scenario. Some of the key features include: diff --git a/modules/planning/README_cn.md b/modules/planning/README_cn.md index c15c9acf424..0c302800d19 100644 --- a/modules/planning/README_cn.md +++ b/modules/planning/README_cn.md @@ -44,7 +44,7 @@ Apollo3.5主要聚焦在三个主要驾驶场景,即: - 安全通过十字路口 ``` -Note: +Note: Apollo团队正在努力增加额外的驾驶场景到规划器。其中一个例子是处理交通灯。 ``` @@ -59,7 +59,7 @@ Apollo 3.5 Planning模块的架构已经改变,以反映我们针对不同驾 部分重要特性包含如下: - Apollo FSM(finite state machine):一个有限状态机,与高清地图确定车辆状态给定其位置和路线。 - Planning Dispatcher: 根据车辆的状态和其他相关信息,调用合适的Planner -- Planner:获取所需的上下文数据和其他信息,确定相应的车辆意图,执行该意图所需的规划任务并生成规划轨迹。它还将更新未来作业的上下文。 +- Planner:获取所需的上下文数据和其他信息,确定相应的车辆意图,执行该意图所需的规划任务并生成规划轨迹。它还将更新未来作业的上下文。 - Deciders & Optimizers :一组实现决策任务和各种优化的无状态库。优化器特别优化车辆的轨迹和速度。决策者是基于规则的分类决策者,他们建议何时换车道、何时停车、何时爬行(慢速行进)或爬行何时完成。 - 黄色框:这些框被包含在未来的场景和/或开发人员中,以便基于现实世界的驱动用例贡献他们自己的场景 diff --git a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface.cc b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface.cc index 24a27f212a9..e4f7da52618 100644 --- a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface.cc +++ b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface.cc @@ -487,7 +487,7 @@ bool DistanceApproachIPOPTCUDAInterface::eval_grad_f_hand(int n, int time_index = time_start_index_; int state_index = state_start_index_; - if (grad_f == NULL) { + if (grad_f == nullptr) { AERROR << "grad_f pt is nullptr"; return false; } else { @@ -2292,7 +2292,7 @@ bool DistanceApproachIPOPTCUDAInterface::eval_h(int n, const double* x, bool new_lambda, int nele_hess, int* iRow, int* jCol, double* values) { - if (values == NULL) { + if (values == nullptr) { // return the structure. This is a symmetric matrix, fill the lower left // triangle only. #ifdef USE_GPU @@ -2891,10 +2891,10 @@ void DistanceApproachIPOPTCUDAInterface::generate_tapes(int n, int m, trace_off(); - rind_L = NULL; - cind_L = NULL; + rind_L = nullptr; + cind_L = nullptr; - hessval = NULL; + hessval = nullptr; options_L[0] = 0; options_L[1] = 1; diff --git a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface_test.cc b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface_test.cc index c506bc76432..1e14dabf412 100644 --- a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface_test.cc +++ b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_cuda_interface_test.cc @@ -143,7 +143,7 @@ TEST_F(DistanceApproachIPOPTCUDAInterfaceTest, eval_jac_g_par) { double values_ser[kNnzJac]; std::fill_n(values_ser, n, 0.0); bool res2 = ptop_->eval_jac_g_ser(n, x, new_x, m, kNnzJac, i_row_ser, - j_col_ser, NULL); + j_col_ser, nullptr); EXPECT_TRUE(res2); bool res3 = ptop_->eval_jac_g_ser(n, x, new_x, m, kNnzJac, i_row_ser, j_col_ser, values_ser); @@ -154,7 +154,7 @@ TEST_F(DistanceApproachIPOPTCUDAInterfaceTest, eval_jac_g_par) { double values_par[kNnzJac]; std::fill_n(values_par, n, 0.0); bool res4 = ptop_->eval_jac_g_par(n, x, new_x, m, kNnzJac, i_row_par, - j_col_par, NULL); + j_col_par, nullptr); EXPECT_TRUE(res4); for (int i = 0; i < kNnzJac; ++i) { EXPECT_EQ(i_row_ser[i], i_row_par[i]) << "iRow differ at index " << i; diff --git a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface.cc b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface.cc index 58eb16b503b..ccb52c8e982 100644 --- a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface.cc +++ b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface.cc @@ -481,7 +481,7 @@ bool DistanceApproachIPOPTInterface::eval_grad_f_hand(int n, const double* x, int time_index = time_start_index_; int state_index = state_start_index_; - if (grad_f == NULL) { + if (grad_f == nullptr) { AERROR << "grad_f pt is nullptr"; return false; } else { @@ -2284,7 +2284,7 @@ bool DistanceApproachIPOPTInterface::eval_h(int n, const double* x, bool new_x, bool new_lambda, int nele_hess, int* iRow, int* jCol, double* values) { - if (values == NULL) { + if (values == nullptr) { // return the structure. This is a symmetric matrix, fill the lower left // triangle only. @@ -2877,10 +2877,10 @@ void DistanceApproachIPOPTInterface::generate_tapes(int n, int m, trace_off(); - rind_L = NULL; - cind_L = NULL; + rind_L = nullptr; + cind_L = nullptr; - hessval = NULL; + hessval = nullptr; options_L[0] = 0; options_L[1] = 1; diff --git a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface_test.cc b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface_test.cc index f4619868bce..8e63c15d4a5 100644 --- a/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface_test.cc +++ b/modules/planning/open_space/trajectory_smoother/distance_approach_ipopt_interface_test.cc @@ -143,7 +143,7 @@ TEST_F(DistanceApproachIPOPTInterfaceTest, eval_jac_g_par) { double values_ser[kNnzJac]; std::fill_n(values_ser, n, 0.0); bool res2 = ptop_->eval_jac_g_ser(n, x, new_x, m, kNnzJac, i_row_ser, - j_col_ser, NULL); + j_col_ser, nullptr); EXPECT_TRUE(res2); bool res3 = ptop_->eval_jac_g_ser(n, x, new_x, m, kNnzJac, i_row_ser, j_col_ser, values_ser); @@ -154,7 +154,7 @@ TEST_F(DistanceApproachIPOPTInterfaceTest, eval_jac_g_par) { double values_par[kNnzJac]; std::fill_n(values_par, n, 0.0); bool res4 = ptop_->eval_jac_g_par(n, x, new_x, m, kNnzJac, i_row_par, - j_col_par, NULL); + j_col_par, nullptr); EXPECT_TRUE(res4); for (int i = 0; i < kNnzJac; ++i) { EXPECT_EQ(i_row_ser[i], i_row_par[i]) << "iRow differ at index " << i; diff --git a/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_interface.cc b/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_interface.cc index 902c64dea2d..bf59e23bde7 100644 --- a/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_interface.cc +++ b/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_interface.cc @@ -258,7 +258,7 @@ bool DualVariableWarmStartIPOPTInterface::eval_jac_g(int n, const double* x, int nele_jac, int* iRow, int* jCol, double* values) { - // if (values == NULL) { + // if (values == nullptr) { // // return the structure of the jacobian // for (int idx = 0; idx < nnz_jac; idx++) { @@ -524,7 +524,7 @@ bool DualVariableWarmStartIPOPTInterface::eval_h(int n, const double* x, bool new_lambda, int nele_hess, int* iRow, int* jCol, double* values) { - if (values == NULL) { + if (values == nullptr) { // return the structure. This is a symmetric matrix, fill the lower left // triangle only. for (int idx = 0; idx < nnz_L; idx++) { @@ -756,10 +756,10 @@ void DualVariableWarmStartIPOPTInterface::generate_tapes(int n, int m, trace_off(); - rind_L = NULL; - cind_L = NULL; + rind_L = nullptr; + cind_L = nullptr; - hessval = NULL; + hessval = nullptr; options_L[0] = 0; options_L[1] = 1; diff --git a/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_qp_interface.cc b/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_qp_interface.cc index 354dbab5ef8..44ea35ff400 100644 --- a/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_qp_interface.cc +++ b/modules/planning/open_space/trajectory_smoother/dual_variable_warm_start_ipopt_qp_interface.cc @@ -452,7 +452,7 @@ bool DualVariableWarmStartIPOPTQPInterface::eval_h( int n, const double* x, bool new_x, double obj_factor, int m, const double* lambda, bool new_lambda, int nele_hess, int* iRow, int* jCol, double* values) { - if (values == NULL) { + if (values == nullptr) { // return the structure. This is a symmetric matrix, fill the lower left // triangle only. for (int idx = 0; idx < nnz_L; idx++) { @@ -694,10 +694,10 @@ void DualVariableWarmStartIPOPTQPInterface::generate_tapes(int n, int m, trace_off(); - rind_L = NULL; - cind_L = NULL; + rind_L = nullptr; + cind_L = nullptr; - hessval = NULL; + hessval = nullptr; options_L[0] = 0; options_L[1] = 1; diff --git a/modules/prediction/README.md b/modules/prediction/README.md index 72cab62f745..4ab816a3851 100644 --- a/modules/prediction/README.md +++ b/modules/prediction/README.md @@ -1,7 +1,7 @@ # Prediction ## Introduction -The Prediction module studies and predicts the behavior of all the obstacles detected by the perception module. +The Prediction module studies and predicts the behavior of all the obstacles detected by the perception module. Prediction receives obstacle data along with basic perception information including positions, headings, velocities, accelerations, and then generates predicted trajectories with probabilities for those obstacles. ``` @@ -9,7 +9,7 @@ Note: The Prediction module only predicts the behavior of obstacles and not the EGO car. The Planning module plans the trajectory of the EGO car. ``` - + ## Input * Obstacles information from the perception module * Localization information from the localization module diff --git a/modules/routing/README.md b/modules/routing/README.md index 59f108fd1c6..d10860fb1c7 100644 --- a/modules/routing/README.md +++ b/modules/routing/README.md @@ -4,7 +4,7 @@ The Routing module generates high level navigation information based on requests. The Routing module depends on a routing topology file, usually named `routing_map.*` in apollo. - + The routing map can be genreated using this command: ``` bash scripts/generate_routing_topo_graph.sh diff --git a/modules/tools/localization/evaluate_compare.py b/modules/tools/localization/evaluate_compare.py index 83f7b3f09b1..3aff3819523 100644 --- a/modules/tools/localization/evaluate_compare.py +++ b/modules/tools/localization/evaluate_compare.py @@ -26,7 +26,7 @@ def get_stat2_from_data(data): than 30cm, 20cm and 10cm Arguments: - data: error array + data: error array Returns: stat: array of max number of continuous frames """ @@ -66,7 +66,7 @@ def get_angle_stat2_from_data(data): than 1.0d, 0.6d and 0.3d Arguments: - data: error array + data: error array Returns: stat: array of max number of continuous frames """ diff --git a/modules/tools/mapviewers/README.md b/modules/tools/mapviewers/README.md index 5af2a94bb75..9d758953c8a 100644 --- a/modules/tools/mapviewers/README.md +++ b/modules/tools/mapviewers/README.md @@ -1,6 +1,6 @@ # MapViewers -MapViewers folder contains a set of tools for plotting map related data. +MapViewers folder contains a set of tools for plotting map related data. ### gmapviewer.py @@ -9,7 +9,7 @@ Gmapviewer is a tool to display HDMap on Google map through Google map javascrip You need to install yattag before running the script ``` -pip install yattag +pip install yattag ``` Inside docker, run the following command from your Apollo root dir: @@ -45,7 +45,7 @@ Inside docker, run the following command from Apollo root dir: python modules/tools/mapviewer/hdmapviwer.py -m map_path_and_file ``` -An output file +An output file ``` hdmap.html diff --git a/modules/tools/navigation/config/README.md b/modules/tools/navigation/config/README.md index 7f8c8793b20..98f07ec6836 100644 --- a/modules/tools/navigation/config/README.md +++ b/modules/tools/navigation/config/README.md @@ -28,9 +28,9 @@ planner_type = EM speed_limit = 5 ``` -In **PerceptionConf** section, the *perception* parameter is to specify the perception solution. Currently there are three supported in Apollo Navigation Mode: mobileye based, camera based and lidar based. +In **PerceptionConf** section, the *perception* parameter is to specify the perception solution. Currently there are three supported in Apollo Navigation Mode: mobileye based, camera based and lidar based. -In the **LocalizationConf** section, utm_zone need to be specified based on location of the road test. +In the **LocalizationConf** section, utm_zone need to be specified based on location of the road test. In the **PlanningConf** section, three planner are supported: EM, Lattice, and Navi. Select one for the planner_type parameter. speed_limt, which is the planner upper speed limit, is also configurable in this seciton, which unit is meter per second. diff --git a/modules/tools/navigator/README.md b/modules/tools/navigator/README.md index c8dca33829d..b2ee21d8e5b 100644 --- a/modules/tools/navigator/README.md +++ b/modules/tools/navigator/README.md @@ -1,42 +1,42 @@ -# Steps for +# Steps for -- Generating navigation data from bag and -- Manually sending the data to /apollo/navigation topic +- Generating navigation data from bag and +- Manually sending the data to /apollo/navigation topic ### Step 1: In dev docker, extract path data from bags ``` -dev_docker:/apollo$cd /modules/tools/navigator -dev_docker:/apollo/modules/tools/navigator$python extractor.py path-to-bags/*.bag +dev_docker:/apollo$cd /modules/tools/navigator +dev_docker:/apollo/modules/tools/navigator$python extractor.py path-to-bags/*.bag ``` -A path file will be generated in +A path file will be generated in ``` -dev_docker:/apollo/modules/tools/navigator$ +dev_docker:/apollo/modules/tools/navigator$ ``` -With format of +With format of ``` -path_[first_bag_name].bag.txt +path_[first_bag_name].bag.txt ``` -### Step2: (Optional) Verify the extracted path is correct +### Step2: (Optional) Verify the extracted path is correct -dev_docker:/apollo/modules/tools/navigator$python viewer_raw.py path_[bag_name].bag.txt +dev_docker:/apollo/modules/tools/navigator$python viewer_raw.py path_[bag_name].bag.txt -### Step3: Smooth the path +### Step3: Smooth the path ``` dev_docker:/apollo/modules/tools/navigator$./smooth.sh /apollo/modules/tools/navigator/path_[first_bag_name].bag.txt 200 ``` -200 is the parameter for smooth length. If the smooth is failed, try to change this parameter to make the smooth pass. The prefered number is between 150 and 200. +200 is the parameter for smooth length. If the smooth is failed, try to change this parameter to make the smooth pass. The prefered number is between 150 and 200. -A smoothed data file, path_[first_bag_name].bag.txt.smoothed, is generated under folder +A smoothed data file, path_[first_bag_name].bag.txt.smoothed, is generated under folder ``` dev_docker:/apollo/modules/tools/navigator$ @@ -45,14 +45,14 @@ dev_docker:/apollo/modules/tools/navigator$ ### Step4: (Optional) Verify the smoothed data ``` -dev_docker:/apollo/modules/tools/navigator$ python viewer_smooth.py path[first_bag_name].bag.txt path[first_bag_name].bag.txt.smoothed +dev_docker:/apollo/modules/tools/navigator$ python viewer_smooth.py path[first_bag_name].bag.txt path[first_bag_name].bag.txt.smoothed ``` -### Step5: Send /apollo/navigation topic +### Step5: Send /apollo/navigation topic -Run follow command to send /apollo/navigation data +Run follow command to send /apollo/navigation data ``` dev_docker:/apollo/modules/tools/navigator$python navigator.py path_[first_bag_name].bag.txt.smoothed diff --git a/modules/tools/navigator/dbmap/README.md b/modules/tools/navigator/dbmap/README.md index 5e92485bf7b..36bf5894cb1 100644 --- a/modules/tools/navigator/dbmap/README.md +++ b/modules/tools/navigator/dbmap/README.md @@ -1,5 +1,5 @@ -# Driving Behavior Map (DBMap) +# Driving Behavior Map (DBMap) -DBMap is learned and generated based on human driving behaviors. +DBMap is learned and generated based on human driving behaviors. diff --git a/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py b/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py index 58e36ff8b89..b36c4a23713 100755 --- a/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py +++ b/modules/tools/open_space_visualization/hybrid_a_star_visualizer.py @@ -102,7 +102,7 @@ def HybridAStarPlan(visualize_flag): v_out.append(float(v[i])) a_out.append(float(a[i])) steer_out.append(float(steer[i])) - + # plot fig1 = plt.figure(1) ax = fig1.add_subplot(111) diff --git a/modules/tools/prediction/data_pipelines/common/online_to_offline.py b/modules/tools/prediction/data_pipelines/common/online_to_offline.py index 7b4a2bf920f..740dfe97efe 100644 --- a/modules/tools/prediction/data_pipelines/common/online_to_offline.py +++ b/modules/tools/prediction/data_pipelines/common/online_to_offline.py @@ -154,7 +154,7 @@ def ObserveAllFeatureSequences(self): @input idx_curr: The index of the current Feature to be labelled. We will look at the subsequent Features following this one to complete labeling. - @output: All saved as class variables in observation_dict, + @output: All saved as class variables in observation_dict, including: its trajectory info and its lane changing info. ''' def ObserveFeatureSequence(self, feature_sequence, idx_curr): @@ -384,7 +384,7 @@ def LabelSingleLane(self, period_of_interest=3.0): lane_sequence.label = -1 lane_sequence.time_to_lane_edge = -1.0 lane_sequence.time_to_lane_center = -1.0 - + for lane_sequence in feature.lane.lane_graph.lane_sequence: lane_sequence_dict[lane_sequence.lane_sequence_id] = [lane_sequence.label, \ lane_sequence.time_to_lane_center, lane_sequence.time_to_lane_edge] diff --git a/modules/tools/prediction/data_pipelines/common/trajectory.py b/modules/tools/prediction/data_pipelines/common/trajectory.py index bf4685c9a40..66ca93ff2b2 100644 --- a/modules/tools/prediction/data_pipelines/common/trajectory.py +++ b/modules/tools/prediction/data_pipelines/common/trajectory.py @@ -270,7 +270,7 @@ def label_cruise(cls, feature_sequence): assign a label and a finish_time. -10: Lane jittering - + -1: False Cut-in 1: True Cut-in but not to lane_center 3: True Cut-in and reached lane_center diff --git a/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py b/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py index 70d9ad36384..bbf118c7470 100644 --- a/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py +++ b/modules/tools/prediction/multiple_gpu_estimator/mlp_main.py @@ -469,7 +469,7 @@ def main(job_dir, data_dir, num_gpus, variable_strategy, log_device_placement, type=str, default=None, help="""\ - If not set, the data format best for the training device is used. + If not set, the data format best for the training device is used. Allowed values: channels_first (NCHW) channels_last (NHWC).\ """) parser.add_argument( diff --git a/modules/tools/prediction/prediction_evaluation/evaluate_prediction_result.py b/modules/tools/prediction/prediction_evaluation/evaluate_prediction_result.py index dcc5b3788ec..e90fcf3bfd0 100644 --- a/modules/tools/prediction/prediction_evaluation/evaluate_prediction_result.py +++ b/modules/tools/prediction/prediction_evaluation/evaluate_prediction_result.py @@ -115,7 +115,7 @@ def Evaluate(dirpath, time_range): list_prediction_result.ParseFromString(f.read()) for prediction_result in list_prediction_result.prediction_result: portion_correct_predicted, num_obstacle, num_trajectory = \ - CorrectlyPredictePortion(prediction_result, future_status_dict, + CorrectlyPredictePortion(prediction_result, future_status_dict, time_range) portion_correct_predicted_sum += portion_correct_predicted num_obstacle_sum += num_obstacle diff --git a/modules/tools/record_analyzer/README.md b/modules/tools/record_analyzer/README.md index f6ad5d4147c..e684429e313 100644 --- a/modules/tools/record_analyzer/README.md +++ b/modules/tools/record_analyzer/README.md @@ -3,13 +3,13 @@ ## Offline Record files analysis ### Functions -Record analyzer is a tool for analyzing the .record file created by cyber_recorder tool. +Record analyzer is a tool for analyzing the .record file created by cyber_recorder tool. -It currently supports statistical analysis for +It currently supports statistical analysis for * Control module latency * Planning module latency - * End to end system latency - + * End to end system latency + And distribution analysis for * Control error code * Control error message @@ -32,7 +32,7 @@ This API is used for simulation to grade planning trajectories. It currently supports following scores: * frechet_dist: calculate the frechet_dist for two consecutive planning trajectories * hard_brake_cycle_num: number of planning cycles that acceleration is less than -2.0 m/s^2 - * overall_score: aggregated score for above metrics + * overall_score: aggregated score for above metrics ### Usage diff --git a/modules/tools/record_analyzer/main.py b/modules/tools/record_analyzer/main.py index 3f0bbd12351..c8e3e4e8465 100644 --- a/modules/tools/record_analyzer/main.py +++ b/modules/tools/record_analyzer/main.py @@ -61,7 +61,7 @@ def process(control_analyzer, planning_analyzer, lidar_endtoend_analyzer, adc_trajectory.ParseFromString(msg.message) planning_analyzer.put(adc_trajectory) lidar_endtoend_analyzer.put_planning(adc_trajectory) - + if plot_planning_path: planning_analyzer.plot_path(plt, adc_trajectory) if plot_planning_refpath: @@ -100,7 +100,7 @@ def process(control_analyzer, planning_analyzer, lidar_endtoend_analyzer, parser.add_argument( "-f", "--file", action="store", type=str, required=True, help="Specify the record file for analysis.") - + parser.add_argument( "-s", "--simulation", action="store_const", const=True, help="For simulation API call") @@ -115,7 +115,7 @@ def process(control_analyzer, planning_analyzer, lidar_endtoend_analyzer, parser.add_argument( "-refpath", "--planningrefpath", action="store_const", const=True, help="plot planing reference paths in cartesian coordinate.") - + parser.add_argument( "-a", "--alldata", action="store_const", const=True, help="Analyze all data (both auto and manual), otherwise auto data only without this option.") diff --git a/modules/tools/record_analyzer/module_planning_analyzer.py b/modules/tools/record_analyzer/module_planning_analyzer.py index 57fabfe649d..cfc9891af32 100644 --- a/modules/tools/record_analyzer/module_planning_analyzer.py +++ b/modules/tools/record_analyzer/module_planning_analyzer.py @@ -58,12 +58,12 @@ def __init__(self, is_simulation, is_sim): self.centripetal_jerk_list = [] self.centripetal_accel_list = [] self.jerk_list = [] - + # [2, 4) unit m/s^2 - self.ACCEL_M_LB = 2 + self.ACCEL_M_LB = 2 self.ACCEL_M_UB = 4 self.accel_medium_cnt = 0 - + # [4, ) unit m/s^2 self.ACCEL_H_LB = 4 self.accel_high_cnt = 0 @@ -100,7 +100,7 @@ def __init__(self, is_simulation, is_sim): self.LAT_ACCEL_H_LB_P = 2 self.LAT_ACCEL_H_UB_N = -2 self.lat_accel_high_cnt = 0 - + # [0.5,1) [-1, -0.5) self.LAT_JERK_M_LB_P = 0.5 self.LAT_JERK_M_UB_P = 1 @@ -156,7 +156,7 @@ def put(self, adc_trajectory): self.init_point_accel.append(accel) elif accel < 0: self.init_point_decel.append(abs(accel)) - + if self.DECEL_M_LB < accel <= self.DECEL_M_UB: self.decel_medium_cnt += 1 if accel <= self.DECEL_H_UB: @@ -185,7 +185,7 @@ def put(self, adc_trajectory): * init_point.path_point.kappa + init_point.v \ * init_point.v * init_point.path_point.dkappa self.centripetal_jerk_list.append(centripetal_jerk) - + if self.LAT_JERK_M_LB_P <= centripetal_jerk < self.LAT_JERK_M_UB_P \ or self.LAT_JERK_M_LB_N < centripetal_jerk <= self.LAT_JERK_M_UB_N: self.lat_jerk_medium_cnt += 1 @@ -331,7 +331,7 @@ def print_simulation_results(self): else: results["jerk_max"] = 0 results["jerk_avg"] = 0 - + results['jerk_medium_cnt'] = self.jerk_medium_cnt results['jerk_high_cnt'] = self.jerk_high_cnt @@ -375,7 +375,7 @@ def print_sim_results(self): v2_results["accel"]["avg"] = 0.0 v2_results["accel"]["medium_cnt"] = self.accel_medium_cnt v2_results["accel"]["high_cnt"] = self.accel_high_cnt - + # deceleration v2_results["decel"] = {} if len(self.init_point_decel) > 0: diff --git a/modules/tools/record_analyzer/tools/dump_message.py b/modules/tools/record_analyzer/tools/dump_message.py index 2d4c0615511..da9525214c6 100644 --- a/modules/tools/record_analyzer/tools/dump_message.py +++ b/modules/tools/record_analyzer/tools/dump_message.py @@ -46,7 +46,7 @@ record_file = args.file reader = RecordReader(record_file) - + for msg in reader.read_messages(): timestamp = msg.timestamp / float(1e9) if msg.topic == args.message and abs(timestamp - args.timestamp) <=1: @@ -55,6 +55,6 @@ perception_obstacle_pb2.PerceptionObstacles() perception_obstacles.ParseFromString(msg.message) with open('perception_obstacles.txt', 'w') as f: - f.write(str(perception_obstacles)) - print str(perception_obstacles) + f.write(str(perception_obstacles)) + print str(perception_obstacles) break diff --git a/modules/tools/record_play/README.md b/modules/tools/record_play/README.md index 8a52db6f520..fa389a573db 100644 --- a/modules/tools/record_play/README.md +++ b/modules/tools/record_play/README.md @@ -25,7 +25,7 @@ Default enable recorder and play under `/apollo` utilizing: bash scripts/rtk_recorder.sh ``` -and +and ```bash bash scripts/rtk_player.sh diff --git a/modules/tools/rosbag/stat_static_info.py b/modules/tools/rosbag/stat_static_info.py index 489cd652f5b..c0d64e84883 100755 --- a/modules/tools/rosbag/stat_static_info.py +++ b/modules/tools/rosbag/stat_static_info.py @@ -43,7 +43,7 @@ def __init__(self): def process_file(self, record_file): """ - Extract information from record file. + Extract information from record file. Return True if we are done collecting all information. """ try: