Skip to content

Commit

Permalink
add: code to turn on loop time printing on/off conditionally
Browse files Browse the repository at this point in the history
  • Loading branch information
rohitdwivedula committed Sep 27, 2024
1 parent da99206 commit f5a08b8
Show file tree
Hide file tree
Showing 3 changed files with 26 additions and 7 deletions.
9 changes: 8 additions & 1 deletion automata_navigation_remapped.sh
Original file line number Diff line number Diff line change
@@ -1,4 +1,11 @@
#!/bin/bash
./bin/navigation \

if [ -z "$VERBOSE" ]; then
VERBOSE=0
fi

echo verbose=$VERBOSE

VERBOSE=$VERBOSE ./bin/navigation \
/velodyne_2dscan:=/scan \
/jackal_velocity_controller/odom:=/odom
21 changes: 16 additions & 5 deletions src/navigation/navigation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,15 @@ void Navigation::Initialize(const NavigationParameters& params,
exit(1);
}
evaluator_ = std::unique_ptr<PathEvaluatorBase>(evaluator);

const char* verbosity = std::getenv("VERBOSE");
if(verbosity == nullptr) verbose_logging = false;
else {
std::string verbosity_str = std::string(verbosity);
if(verbosity_str == "1") verbose_logging=true;
else verbose_logging=false;
}

}

bool Navigation::Enabled() const {
Expand Down Expand Up @@ -962,11 +971,13 @@ bool Navigation::Run(const double& time, Vector2f& cmd_vel, float& cmd_angle_vel
auto end_run_loop = std::chrono::system_clock::now();
std::chrono::duration<double, std::milli> time_diff = end_run_loop - start_run_loop;

printf(
"LOOP: %ld,%f\n",
std::chrono::duration_cast<std::chrono::milliseconds>(start_run_loop.time_since_epoch()).count(),
time_diff.count()
);
if(verbose_logging) {
printf(
"LOOP: %ld,%f\n",
std::chrono::duration_cast<std::chrono::milliseconds>(start_run_loop.time_since_epoch()).count(),
time_diff.count()
);
}
return retval;
}

Expand Down
3 changes: 2 additions & 1 deletion src/navigation/navigation.h
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,8 @@ class Navigation {
const cv::Mat& GetVisualizationImage();
std::vector<std::shared_ptr<motion_primitives::PathRolloutBase>> GetLastPathOptions();
std::shared_ptr<motion_primitives::PathRolloutBase> GetOption();

bool verbose_logging;

private:

// Test 1D TOC motion in a straight line.
Expand Down

0 comments on commit f5a08b8

Please sign in to comment.