refactor(eagleye_rt): convert all nodes to class-based rclcpp::Node#366
refactor(eagleye_rt): convert all nodes to class-based rclcpp::Node#366rsasaki0109 wants to merge 1 commit intodevelop-ros2from
Conversation
…attern Replace global static variables and free callback functions with encapsulated class-based rclcpp::Node pattern across all 21 nodes. Also fix CMakeLists.txt ROS_DISTRO comparison (quoted env var). - Each node is now a class inheriting rclcpp::Node - Subscribers, publishers, and timers are private member variables - Callbacks are private member functions - GenericTimer replaced with create_wall_timer() - Nodes with argc/argv routing (heading, rtk_heading, heading_interpolate, yaw_rate_offset) pass args through constructor
There was a problem hiding this comment.
Other comments (16)
- eagleye_rt/src/slip_angle_node.cpp (63-77) The `sub_velocity_status_` subscription is declared but never initialized in the constructor, while `velocity_status_` is used in the `imuCallback` method. This could lead to undefined behavior when `use_can_less_mode_` is true.
-
eagleye_rt/src/smoothing_node.cpp (31-33)
Missing include for YAML::Node which is used throughout the code.
#include "eagleye_coordinate/eagleye_coordinate.hpp" #include "eagleye_navigation/eagleye_navigation.hpp" #include "rclcpp/rclcpp.hpp" #include "yaml-cpp/yaml.hpp" -
eagleye_rt/src/smoothing_node.cpp (31-33)
Missing include for tf2_ros which is used for TransformListener and Buffer.
#include "eagleye_coordinate/eagleye_coordinate.hpp" #include "eagleye_navigation/eagleye_navigation.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/transform_listener.h" #include "tf2_ros/buffer.h" -
eagleye_rt/src/position_interpolate_node.cpp (65-66)
The error message in the catch block refers to 'heading_interpolate Node' but this is the position_interpolate node. This should be updated for clarity.
std::cerr << "\033[1;31mposition_interpolate Node YAML Error: " << e.msg << "\033[0m" << std::endl; -
eagleye_rt/src/velocity_scale_factor_node.cpp (283-284)
The csv_file is created but not checked for successful opening before returning. This could lead to silent failures if the file cannot be opened.
std::ofstream csv_file(velocity_scale_factor_save_str_); if (!csv_file) { RCLCPP_ERROR(this->get_logger(), "Failed to open file for writing: %s", velocity_scale_factor_save_str_.c_str()); } return; -
eagleye_rt/src/velocity_scale_factor_node.cpp (273-275)
The file is closed unconditionally, even if it wasn't successfully opened. This should be moved inside the else block.
} ifs.close(); } -
eagleye_rt/src/yaw_rate_offset_node.cpp (134-134)
The error message when an invalid first argument is provided is misleading. It currently says 'No arguments' when it should indicate that the argument is invalid.
RCLCPP_ERROR(this->get_logger(), "Invalid argument. Expected '1st' or '2nd'"); - eagleye_rt/src/yaw_rate_offset_node.cpp (171-171) The `use_can_less_mode_` variable is initialized to false but never set to true anywhere in the code, making the condition check in imuCallback ineffective.
- eagleye_rt/src/enable_additional_rolling_node.cpp (125-125) The `velocity_` member variable is declared but never assigned a value. It's used in the `enable_additional_rolling_estimate()` function call, but there's no subscription or callback to populate it. This could lead to undefined behavior.
- eagleye_rt/src/enable_additional_rolling_node.cpp (126-126) The `velocity_status_` member variable is declared but never assigned a value. It's used in the `use_can_less_mode_` check in the `imuCallback()` function, but there's no subscription or callback to populate it.
- eagleye_rt/src/rtk_dead_reckoning_node.cpp (59-59) The YAML::LoadFile call might throw exceptions other than YAML::Exception (such as std::runtime_error if the file doesn't exist). Consider using a more general catch block or adding specific handling for file-related errors.
- eagleye_rt/src/yaw_rate_offset_stop_node.cpp (63-64) There's an inconsistency between the parameter name and the log message. The parameter is named `estimated_interval` but the log message refers to it as `estimated_minimum_interval`. Consider updating the log message to match the parameter name for clarity.
-
eagleye_rt/src/angular_velocity_offset_stop_node.cpp (59-59)
The log message for the estimated_interval parameter is inconsistent with the variable name. It's printing 'estimated_minimum_interval' but the parameter is named 'estimated_interval'.
std::cout << "estimated_interval " << angular_velocity_offset_stop_parameter_.estimated_interval << std::endl; -
eagleye_rt/src/velocity_estimator_node.cpp (84-84)
Consider using a consistent style for all callback methods. The `ggaCallback` is implemented as a one-liner while other callbacks use a multi-line format with braces on separate lines.
void ggaCallback(const nmea_msgs::msg::Gpgga::ConstSharedPtr msg) { gga_msg_ = *msg; } - eagleye_rt/src/height_node.cpp (130-130) The member variable `use_can_less_mode_` is initialized to `false` in the class declaration, but then unconditionally overwritten in the constructor with the value from the config file. This initialization is redundant and could be confusing.
-
eagleye_rt/src/correction_imu.cpp (103-103)
The condition is missing a check for `enabled_status` in the second part. It should be `acc_x_scale_factor_.status.enabled_status == true` for consistency.
if (acc_x_offset_.status.enabled_status == true && acc_x_scale_factor_.status.enabled_status == true)
1 file skipped due to size limits:
- eagleye_rt/src/monitor_node.cpp
💡 To request another review, post a new comment with "/windsurf-review".
| rclcpp::spin(node); | ||
|
|
||
| std::string str; | ||
| node->declare_parameter(str, "output_dir"); |
There was a problem hiding this comment.
The parameter declaration for 'output_dir' is incorrect. The variable 'str' is being passed as the parameter name instead of a string literal.
| node->declare_parameter(str, "output_dir"); | |
| std::string str; | |
| node->declare_parameter("output_dir", ""); | |
| node->get_parameter("output_dir", str); |
| } catch (tf2::TransformException& ex) { | ||
| return; | ||
| } |
There was a problem hiding this comment.
The exception handler in onTimer() silently returns without logging the error. Consider preserving the error logging from the previous implementation to help with debugging transform issues.
| } catch (tf2::TransformException& ex) { | |
| return; | |
| } | |
| } catch (tf2::TransformException& ex) { | |
| RCLCPP_ERROR(this->get_logger(), "%s", ex.what()); | |
| return; | |
| } |
| std::string subscribe_topic_name_1 = "/subscribe_topic_name/invalid_1"; | ||
| std::string subscribe_topic_name_2 = "/subscribe_topic_name/invalid_2"; | ||
|
|
||
| if (argc > 2) { |
There was a problem hiding this comment.
The condition argc > 2 checks if there are at least 3 arguments (including the program name), but the code only accesses argv[1]. This could lead to undefined behavior if exactly 2 arguments are provided (program name + one argument). Consider changing to argc >= 2 to check if at least one argument is available after the program name.
Summary
rclcpp::Nodepattern across all 21 nodes ineagleye_rtrclcpp::Nodewith private member variables for state, subscribers, and publishersGenericTimerreplaced withcreate_wall_timer()argc/argv(heading, rtk_heading, heading_interpolate, yaw_rate_offset) pass args through the constructor$ENV{ROS_DISTRO}inif()comparisonTest plan
colcon build --packages-select eagleye_rt✅