Skip to content

Commit

Permalink
Merge pull request #8 from husarion/healthcheck_fix
Browse files Browse the repository at this point in the history
Healthcheck fix
  • Loading branch information
JanBrzyk authored Dec 19, 2023
2 parents 0f643bd + 91130bd commit 0b4c278
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 14 deletions.
15 changes: 5 additions & 10 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -43,18 +43,13 @@ COPY --from=pkg-builder /ros2_ws /ros2_ws
RUN echo $(cat /ros2_ws/src/sllidar_ros2/package.xml | grep '<version>' | sed -r 's/.*<version>([0-9]+.[0-9]+.[0-9]+)<\/version>/\1/g') > /version.txt

# Run healthcheck in background
RUN if [ -f "/ros_entrypoint.sh" ]; then \
sed -i '/test -f "\/ros2_ws\/install\/setup.bash" && source "\/ros2_ws\/install\/setup.bash"/a \
ros2 run healthcheck_pkg healthcheck_node &' \
/ros_entrypoint.sh; \
else \
sed -i '/test -f "\/ros2_ws\/install\/setup.bash" && source "\/ros2_ws\/install\/setup.bash"/a \
ros2 run healthcheck_pkg healthcheck_node &' \
/vulcanexus_entrypoint.sh; \
fi
RUN entrypoint_file=$(if [ -f "/ros_entrypoint.sh" ]; then echo "/ros_entrypoint.sh"; else echo "/vulcanexus_entrypoint.sh"; fi) && \
sed -i '/test -f "\/ros2_ws\/install\/setup.bash" && source "\/ros2_ws\/install\/setup.bash"/a \
ros2 run healthcheck_pkg healthcheck_node &' \
$entrypoint_file

COPY ./healthcheck.sh /
HEALTHCHECK --interval=5s --timeout=2s --start-period=5s --retries=4 \
HEALTHCHECK --interval=2s --timeout=1s --start-period=20s --retries=1 \
CMD ["/healthcheck.sh"]

# Ensure LIDAR stops spinning on container shutdown
Expand Down
8 changes: 4 additions & 4 deletions healthcheck.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@

using namespace std::chrono_literals;

#define LOOP_PERIOD 2s
#define MSG_VALID_TIME 5s
#define LOOP_PERIOD 500ms
#define MSG_VALID_TIME 2s

std::chrono::steady_clock::time_point last_msg_time;

Expand All @@ -22,7 +22,7 @@ void healthy_check() {
std::chrono::steady_clock::time_point current_time =
std::chrono::steady_clock::now();
std::chrono::duration<double> elapsed_time = current_time - last_msg_time;
bool is_msg_valid = elapsed_time.count() < MSG_VALID_TIME.count();
bool is_msg_valid = elapsed_time < MSG_VALID_TIME;

if (is_msg_valid) {
write_health_status("healthy");
Expand All @@ -33,7 +33,7 @@ void healthy_check() {

int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("healthcheck_node");
auto node = rclcpp::Node::make_shared("healthcheck_rplidar");
auto sub = node->create_subscription<sensor_msgs::msg::LaserScan>(
"scan", rclcpp::SensorDataQoS().keep_last(1), msg_callback);

Expand Down

0 comments on commit 0b4c278

Please sign in to comment.