Skip to content

Commit

Permalink
Merge pull request #18 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 1bf96ac + 7b628c2 commit c029bcc
Show file tree
Hide file tree
Showing 6 changed files with 29 additions and 49 deletions.
15 changes: 5 additions & 10 deletions Dockerfile.hardware
Original file line number Diff line number Diff line change
Expand Up @@ -117,16 +117,11 @@ COPY ftdi-eeprom-conf.py /usr/bin/
COPY print-serial-number.py /usr/bin/

# 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=30s --retries=1 \
CMD ["/healthcheck.sh"]
15 changes: 5 additions & 10 deletions Dockerfile.manipulation.hardware
Original file line number Diff line number Diff line change
Expand Up @@ -56,16 +56,11 @@ RUN apt-get update && apt-get install -y \
rm -rf /var/lib/apt/lists/*

# 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=30s --retries=1 \
CMD ["/healthcheck.sh"]
15 changes: 5 additions & 10 deletions Dockerfile.manipulation.simulation
Original file line number Diff line number Diff line change
Expand Up @@ -59,16 +59,11 @@ RUN apt-get update --fix-missing && apt-get install -y \
rm -rf /var/lib/apt/lists/*

# 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=30s --retries=1 \
CMD ["/healthcheck.sh"]
15 changes: 5 additions & 10 deletions Dockerfile.simulation
Original file line number Diff line number Diff line change
Expand Up @@ -63,16 +63,11 @@ RUN MYDISTRO=${PREFIX:-ros}; MYDISTRO=${MYDISTRO//-/} && \
rm -rf /var/lib/apt/lists/*

# 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=30s --retries=1 \
CMD ["/healthcheck.sh"]
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_rosbot_xl");
auto sub = node->create_subscription<nav_msgs::msg::Odometry>(
"odometry/filtered", rclcpp::SensorDataQoS().keep_last(1), msg_callback);

Expand Down
10 changes: 5 additions & 5 deletions healthcheck_manipulation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,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_odom_msg_time;
std::chrono::steady_clock::time_point last_joint_msg_time;
Expand Down Expand Up @@ -53,8 +53,8 @@ void healthy_check() {
current_time - last_odom_msg_time;
std::chrono::duration<double> joint_elapsed_time =
current_time - last_joint_msg_time;
bool is_odom_valid = odom_elapsed_time.count() < MSG_VALID_TIME.count();
bool are_joints_valid = joint_elapsed_time.count() < MSG_VALID_TIME.count();
bool is_odom_valid = odom_elapsed_time < MSG_VALID_TIME;
bool are_joints_valid = joint_elapsed_time < MSG_VALID_TIME;

if (is_odom_valid && are_joints_valid) {
write_health_status("healthy");
Expand All @@ -65,7 +65,7 @@ void healthy_check() {

int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("healthcheck_manipulation");
auto node = rclcpp::Node::make_shared("healthcheck_rosbot_xl");
auto odom_sub = node->create_subscription<nav_msgs::msg::Odometry>(
"odometry/filtered", rclcpp::SensorDataQoS().keep_last(1), odom_callback);
auto joint_sub =
Expand Down

0 comments on commit c029bcc

Please sign in to comment.