Skip to content

Commit

Permalink
Extend durations for saluki debugging purposes
Browse files Browse the repository at this point in the history
  • Loading branch information
mehmetkillioglu committed Feb 2, 2024
1 parent 353d616 commit 9871148
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
2 changes: 2 additions & 0 deletions .github/workflows/tii-depthai-ctrl.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ jobs:
if [[ "${{ github.event_name }}" == "push" && "${{ github.ref }}" == "refs/heads/$default_branch" ]]; then
matrix_list=("amd64" "arm64" "riscv64")
elif [[ "${{ github.event_name }}" == "push" && "${{ github.ref }}" == "refs/heads/dbg_extend_stream_handling_durations" ]]; then
matrix_list=("riscv64") # TODO(mehmetkillioglu): DEBUG ONLY, MAKE SURE TO REMOVE LATER
elif [[ "${{ github.event_name }}" == "pull_request" && "${{ github.base_ref }}" == "$default_branch" ]]; then
matrix_list=("amd64" "arm64" "riscv64")
elif [[ "${{ github.event_name }}" == "workflow_dispatch" ]]; then
Expand Down
8 changes: 4 additions & 4 deletions src/depthai_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void DepthAICamera::Initialize()
std::bind(&DepthAICamera::AutoFocusTimer, this));

_handle_camera_status_timer = this->create_wall_timer(
std::chrono::milliseconds(10000),
std::chrono::milliseconds(45000),
std::bind(&DepthAICamera::HandleStreamStatus, this), _callback_group_timer); // 10 sec

// Video Stream parameters
Expand Down Expand Up @@ -197,7 +197,7 @@ void DepthAICamera::HandleStreamStatus()
{
std::lock_guard<std::mutex> lock(_callback_mutex);
device_running = _thread_running && _firstFrameReceived &&
(_lastFrameTime.seconds() + 3.0) > _steady_clock->now().seconds();
(_lastFrameTime.seconds() + 30.0) > _steady_clock->now().seconds();
}
if (!device_running) {
RCLCPP_WARN(
Expand Down Expand Up @@ -225,7 +225,7 @@ void DepthAICamera::HandleStreamStatus()
}
if (rclcpp::ok()) {
_handle_camera_status_timer = this->create_wall_timer(
std::chrono::milliseconds(10000),
std::chrono::milliseconds(45000),
std::bind(&DepthAICamera::HandleStreamStatus, this), _callback_group_timer); // 10 sec
}

Expand Down Expand Up @@ -374,7 +374,7 @@ void DepthAICamera::changeParametersCallback(

if (rclcpp::ok()) {
_handle_camera_status_timer = this->create_wall_timer(
std::chrono::milliseconds(10000),
std::chrono::milliseconds(45000),
std::bind(&DepthAICamera::HandleStreamStatus, this), _callback_group_timer); // 10 sec
}
}
Expand Down

0 comments on commit 9871148

Please sign in to comment.