diff --git a/src/navigation/navigation.cc b/src/navigation/navigation.cc index 7dd2c2a..3ca2c9b 100644 --- a/src/navigation/navigation.cc +++ b/src/navigation/navigation.cc @@ -831,7 +831,7 @@ vector Navigation::GetPlanPath() { return plan_path_; } -bool Navigation::Run(const double& time, +bool Navigation::RunInternal(const double& time, Vector2f& cmd_vel, float& cmd_angle_vel) { const bool kDebug = FLAGS_v > 0; @@ -956,4 +956,18 @@ bool Navigation::Run(const double& time, return true; } -} // namespace navigation +bool Navigation::Run(const double& time, Vector2f& cmd_vel, float& cmd_angle_vel) { + auto start_run_loop = std::chrono::system_clock::now(); + bool retval = Navigation::RunInternal(time, cmd_vel, cmd_angle_vel); + auto end_run_loop = std::chrono::system_clock::now(); + std::chrono::duration time_diff = end_run_loop - start_run_loop; + + printf( + "LOOP: %ld,%f\n", + std::chrono::duration_cast(start_run_loop.time_since_epoch()).count(), + time_diff.count() + ); + return retval; +} + +} // namespace navigation \ No newline at end of file diff --git a/src/navigation/navigation.h b/src/navigation/navigation.h index d1600d0..6683ae1 100644 --- a/src/navigation/navigation.h +++ b/src/navigation/navigation.h @@ -91,6 +91,8 @@ class Navigation { double time); void ObserveImage(cv::Mat image, double time); bool Run(const double& time, Eigen::Vector2f& cmd_vel, float& cmd_angle_vel); + bool RunInternal(const double& time, Eigen::Vector2f& cmd_vel, float& cmd_angle_vel); + void GetStraightFreePathLength(float* free_path_length, float* clearance); void GetFreePathLength(float curvature,