diff --git a/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc b/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc index 5ce7e38a6d1f544bb02c4b580971a23d29754d06..1c2390635a3e5da9a00da12517f9adab60320f9c 100644 --- a/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc +++ b/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc @@ -79,9 +79,6 @@ bool LidarExChecker::GetExtrinsics() { tf2_buffer.lookupTransform("novatel", "velodyne64", ros::Time(0)); tf::transformMsgToEigen(transform_stamped.transform, extrinsics_); - std::cout << "velodyne64 extrinsics: " << std::endl; - std::cout << extrinsics_.matrix() << std::endl; - return true; } @@ -164,7 +161,6 @@ void LidarExChecker::OnPointCloud(const sensor_msgs::PointCloud2& message) { if (clouds_.size() < cloud_count_) { last_position_ = position; clouds_.push_back(cld); - std::cout << "take " << clouds_.size() << " cloud(s)." << std::endl; } if (clouds_.size() >= cloud_count_) { diff --git a/modules/calibration/republish_msg/republish_msg.cc b/modules/calibration/republish_msg/republish_msg.cc index 83afd0b6df54620570361311c882b29f8c567e0e..bf08654af296da8ff0555c66c39c70ec44a096f0 100644 --- a/modules/calibration/republish_msg/republish_msg.cc +++ b/modules/calibration/republish_msg/republish_msg.cc @@ -32,8 +32,6 @@ std::string RepublishMsg::Name() const { } Status RepublishMsg::Init() { - std::cout << FLAGS_adapter_config_path << std::endl; - AdapterManager::Init(FLAGS_adapter_config_path); CHECK(AdapterManager::GetInsStat()) << "INS status is not initialized."; diff --git a/modules/canbus/can_client/can_client_tool.cc b/modules/canbus/can_client/can_client_tool.cc index c781180efd02f08a6c91590f982ab92c25b76592..f489667171e5a652b9a86aa2b649d91b15a275e2 100644 --- a/modules/canbus/can_client/can_client_tool.cc +++ b/modules/canbus/can_client/can_client_tool.cc @@ -60,13 +60,12 @@ struct TestCanParam { TestCanParam() = default; void print() { - std::cout << "conf: " << conf.ShortDebugString() - << ", total send: " << send_cnt + send_err_cnt << "/" - << FLAGS_agent_mutual_send_frames << ", send_ok: " << send_cnt - << " , send_err_cnt: " << send_err_cnt - << ", send_lost_cnt: " << send_lost_cnt - << ", recv_cnt: " << recv_cnt << ", send_time: " << send_time - << ", recv_time: " << recv_time << std::endl; + AINFO << "conf: " << conf.ShortDebugString() + << ", total send: " << send_cnt + send_err_cnt << "/" + << FLAGS_agent_mutual_send_frames << ", send_ok: " << send_cnt + << " , send_err_cnt: " << send_err_cnt + << ", send_lost_cnt: " << send_lost_cnt << ", recv_cnt: " << recv_cnt + << ", send_time: " << send_time << ", recv_time: " << recv_time; } }; @@ -74,9 +73,13 @@ class CanAgent { public: explicit CanAgent(TestCanParam *param_ptr) : param_ptr_(param_ptr) {} - TestCanParam *param_ptr() { return param_ptr_; } + TestCanParam *param_ptr() { + return param_ptr_; + } - CanAgent *other_agent() { return other_agent_; } + CanAgent *other_agent() { + return other_agent_; + } bool Start() { thread_recv_.reset(new std::thread([this] { RecvThreadFunc(); })); @@ -167,15 +170,25 @@ class CanAgent { return; } - void AddOtherAgent(CanAgent *agent) { other_agent_ = agent; } + void AddOtherAgent(CanAgent *agent) { + other_agent_ = agent; + } - bool is_receiving() { return is_receiving_; } + bool is_receiving() { + return is_receiving_; + } - void is_receiving(bool val) { is_receiving_ = val; } + void is_receiving(bool val) { + is_receiving_ = val; + } - bool is_sending_finish() { return is_sending_finish_; } + bool is_sending_finish() { + return is_sending_finish_; + } - void is_sending_finish(bool val) { is_sending_finish_ = val; } + void is_sending_finish(bool val) { + is_sending_finish_ = val; + } void RecvThreadFunc() { using ::apollo::common::time::Clock; diff --git a/modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc b/modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc index 55a41b3f582860a0d97e123743e0537c8ed6ae18..24ccfcc69d81f8d50dd265e1173b5953b2cd8bbd 100644 --- a/modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc +++ b/modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc @@ -33,8 +33,6 @@ TEST(Gps6dTest, General) { EXPECT_DOUBLE_EQ(cd.basic().latitude(), -244.245646); EXPECT_DOUBLE_EQ(cd.basic().longitude(), -61.779717); - std::cout << cd.DebugString() << std::endl; - EXPECT_EQ(data[0], 0b01010110); EXPECT_EQ(data[1], 0b01010010); EXPECT_EQ(data[2], 0b01010011); diff --git a/modules/common/time/time.h b/modules/common/time/time.h index 298e3781b2e2135c1aaee78b22e006c80b7e6f75..ece015081e021816fa358009f09df6a2d19c5b0d 100644 --- a/modules/common/time/time.h +++ b/modules/common/time/time.h @@ -268,8 +268,8 @@ inline Clock::Clock() [block_start_time]() { \ double now = Clock::NowInSecond(); \ if (now - block_start_time > (threshold)) { \ - std::cout << std::fixed << (message) << ": " \ - << now - block_start_time << std::endl; \ + ADEBUG << std::fixed << (message) << ": " \ + << now - block_start_time; \ } \ }()) diff --git a/modules/perception/obstacle/common/hungarian_bigraph_matcher.cc b/modules/perception/obstacle/common/hungarian_bigraph_matcher.cc index 980482e1fd60deb7eac6a2abddf2f967e6702fba..76f9b50d360430ff90ac3031928a72a1059b45e3 100644 --- a/modules/perception/obstacle/common/hungarian_bigraph_matcher.cc +++ b/modules/perception/obstacle/common/hungarian_bigraph_matcher.cc @@ -276,7 +276,6 @@ void HungarianOptimizer::do_munkres() { (this->*_state)(); ++iter_num; } - // std::cout << "do_munkres iterations: " << iter_num << std::endl; if (iter_num >= max_iter) { check_star(); } diff --git a/modules/perception/obstacle/lidar/object_builder/min_box/min_box.cc b/modules/perception/obstacle/lidar/object_builder/min_box/min_box.cc index 58855b9815f1c029bf8fd6262628753d55a901c6..994524ac088620b96f61ee8fcbcc72a29061345d 100644 --- a/modules/perception/obstacle/lidar/object_builder/min_box/min_box.cc +++ b/modules/perception/obstacle/lidar/object_builder/min_box/min_box.cc @@ -204,10 +204,8 @@ void MinBoxObjectBuilder::ReconstructPolygon( p_j[2] = obj->polygon.points[j].z; Eigen::Vector3d ray = p - min_point; if (line[0] * ray[1] - ray[0] * line[1] < 0) { - // std::cout << "in :" << std::endl; } else { // outline - // std::cout << "out :" << std::endl; has_out = true; } } else if (j == min_point_index || j == max_point_index) { diff --git a/modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc b/modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc index a03ff24a686178d4bf431f1218465586e9a7d749..7709e591f2ad738882b9e1c8f5a90c212b8b9b87 100644 --- a/modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc +++ b/modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc @@ -133,7 +133,6 @@ void HdmapROIFilterTest::filter() { TEST_F(HdmapROIFilterTest, test_filter) { init(); - std::cout << "Successfully init." << std::endl; filter(); } diff --git a/modules/perception/obstacle/lidar/tracker/hm_tracker/object_track.cc b/modules/perception/obstacle/lidar/tracker/hm_tracker/object_track.cc index fdafccd32d956668ae264f9aca6fdacce8ae0534..5efde8ec3f2308cdb1cf01644fbe02006d212b8a 100644 --- a/modules/perception/obstacle/lidar/tracker/hm_tracker/object_track.cc +++ b/modules/perception/obstacle/lidar/tracker/hm_tracker/object_track.cc @@ -125,7 +125,7 @@ void ObjectTrack::UpdateWithObject(TrackedObjectPtr* new_object, filter_->UpdateWithObject((*new_object), current_object_, time_diff); filter_->GetState(&belief_anchor_point_, &belief_velocity_); } else { - /* Here, we only update belief anchor point with anchor point of new detected object. In + /* Here, we only update belief anchor point with anchor point of new detected object. In * the future, new method that handle outlier could be designed to handle more complicated * strategies. */ belief_anchor_point_ = (*new_object)->anchor_point; @@ -140,7 +140,7 @@ void ObjectTrack::UpdateWithObject(TrackedObjectPtr* new_object, belief_velocity_accelaration_ = ((*new_object)->velocity - current_object_->velocity) / time_diff; - /* Currently, we only considered outliers' influence on motion estimation. Track level + /* Currently, we only considered outliers' influence on motion estimation. Track level * smoothness of orientation & class idx may also take into acount it in the future. */ // 1.4 update track info @@ -161,7 +161,7 @@ void ObjectTrack::UpdateWithObject(TrackedObjectPtr* new_object, * is more reasonable to be used in the smoothing of orientation & type. */ /* Previously, track static hypothesis is checked before smoothing strategies. Now, it has been - * moved in the method of smooth track velocity. This is more reasonable, as track static + * moved in the method of smooth track velocity. This is more reasonable, as track static * hypothesis is decided by velocity more directly when velocity estimation improved. */ /* 2. smooth object track */ @@ -396,9 +396,7 @@ ObjectTrackSet::ObjectTrackSet(): age_threshold_(5), } ObjectTrackSet::~ObjectTrackSet() { - std::cout << "Release ObjectTrackSet...\n"; clear(); - std::cout << "Release ObjectTrackSet End\n"; } void ObjectTrackSet::clear() { diff --git a/modules/planning/math/smoothing_spline/spline_1d_kernel_test.cc b/modules/planning/math/smoothing_spline/spline_1d_kernel_test.cc index 829e758f470ba67c53d6befe18e226fbf0a949ef..873baf43bca7ba9e2d87003fc8372312d1541b7e 100644 --- a/modules/planning/math/smoothing_spline/spline_1d_kernel_test.cc +++ b/modules/planning/math/smoothing_spline/spline_1d_kernel_test.cc @@ -31,15 +31,11 @@ TEST(Spline1dKernel, add_reference_line_kernel) { Spline1dKernel kernel(x_knots, spline_order); Eigen::IOFormat OctaveFmt(Eigen::StreamPrecision, 0, ", ", ";\n", "", "", "[", "]"); - std::cout << kernel.kernel_matrix().format(OctaveFmt) << std::endl; std::vector x_coord = {0.0, 1.0, 2.0, 3.0}; std::vector ref_x = {0.0, 0.5, 0.6, 2.0}; kernel.add_reference_line_kernel_matrix(x_coord, ref_x, 1.0); - std::cout << kernel.kernel_matrix().format(OctaveFmt) << std::endl; - std::cout << kernel.offset().format(OctaveFmt) << std::endl; - Eigen::MatrixXd ref_kernel_matrix = Eigen::MatrixXd::Zero(15, 15); ref_kernel_matrix << 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,