From 4404564f1fd48816c091c5bce06aef2819e36ec3 Mon Sep 17 00:00:00 2001 From: SamerKhshiboun Date: Wed, 1 Feb 2023 23:33:56 +0200 Subject: [PATCH] add static_analysis.yaml to project and fix some code to pass cppcheck run --- .github/workflows/static_analysis.yaml | 60 +++++++++++++++++++ .../include/base_realsense_node.h | 4 +- realsense2_camera/include/dynamic_params.h | 2 + realsense2_camera/src/base_realsense_node.cpp | 19 ++++-- realsense2_camera/src/dynamic_params.cpp | 3 +- 5 files changed, 79 insertions(+), 9 deletions(-) create mode 100644 .github/workflows/static_analysis.yaml diff --git a/.github/workflows/static_analysis.yaml b/.github/workflows/static_analysis.yaml new file mode 100644 index 0000000000..7672fd6956 --- /dev/null +++ b/.github/workflows/static_analysis.yaml @@ -0,0 +1,60 @@ +name: static_analysis + +on: + push: + branches: ['**'] + pull_request: + branches: ['**'] + +jobs: + cppcheck: + name: cppcheck + runs-on: ubuntu-22.04 + steps: + - uses: actions/checkout@v3 + + - name: Install + shell: bash + run: | + sudo apt-get update; + sudo apt-get install -qq cppcheck; + + - name: Cppcheck Run + shell: bash + #Selected run options: + # ./xxx : Folders to scan + # --quiet : Don't show current checked configuration in log + # --std=c++11 : Use C++11 standard (default but worth mentioning) + # --xml : Output in XML format + # -j4 : Run parallel jobs for a faster scan. current HW is 2 core (https://docs.github.com/en/actions/using-github-hosted-runners/about-github-hosted-runners) using 4 to future proof + # --enable : Additional check to run. options are [all, warning, style, performance, protability, information, unusedFunction, missingInclude] + # -I : Include directories + # -i : Ignore directories. Ignore third-party libs that we don't want to check + # --suppress : Don't issue errors about files matching the expression (when -i for folders is not enough) + # --force : Check all configurations, takes a very long time (~2 hours) and did not find additional errors. Removed. + # --max-configs=6 : Using less configuration permutations (default is 12) to reduce run time. Detects less errors. Removed. + # -Dxxx : preprocessor configuration to use. Relevant flags taken from build on Ubuntu. + run: > + cppcheck ./realsense2_camera/src ./realsense2_camera/include ./realsense2_camera/tools + --quiet --std=c++11 --xml -j4 --enable=warning + -I./realsense2_camera/include -I./realsense2_camera/tools + &> cppcheck_run.log + + - name: Cppcheck Result + shell: bash + run: | + ERROR_COUNT=$(grep cppcheck_run.log -e "severity=\"error\"" -c) || ERROR_COUNT=0 + EXPECTED_ERROR_COUNT=0 + if [ $ERROR_COUNT -eq $EXPECTED_ERROR_COUNT ] + then + echo "cppcheck_run succeeded, found" $ERROR_COUNT "errors, as expected" + exit 0 + elif [ $ERROR_COUNT -lt $EXPECTED_ERROR_COUNT ] + then + echo "cppcheck_run ---> SUCCEEDED <--- but found" $ERROR_COUNT "errors when expecting" $EXPECTED_ERROR_COUNT + echo "Please update EXPECTED_ERROR_COUNT var in .github/workflows/static_analysis.yaml to the new lower value" + else + echo "cppcheck_run ---> FAILED <--- with" $ERROR_COUNT "errors; expecting" $EXPECTED_ERROR_COUNT + fi + cat cppcheck_run.log + exit 1 diff --git a/realsense2_camera/include/base_realsense_node.h b/realsense2_camera/include/base_realsense_node.h index 4a88f9496e..26a03532b0 100755 --- a/realsense2_camera/include/base_realsense_node.h +++ b/realsense2_camera/include/base_realsense_node.h @@ -77,7 +77,6 @@ namespace realsense2_camera class SyncedImuPublisher { public: - SyncedImuPublisher() {_is_enabled=false;}; SyncedImuPublisher(rclcpp::Publisher::SharedPtr imu_publisher, std::size_t waiting_list_size=1000); ~SyncedImuPublisher(); @@ -146,7 +145,7 @@ namespace realsense2_camera std::list _parameters_names; void publishExtrinsicsTopic(const stream_index_pair& sip, const rs2_extrinsics& ex); - virtual void calcAndPublishStaticTransform(const rs2::stream_profile& profile, const rs2::stream_profile& base_profile); + void calcAndPublishStaticTransform(const rs2::stream_profile& profile, const rs2::stream_profile& base_profile); void getDeviceInfo(const realsense2_camera_msgs::srv::DeviceInfo::Request::SharedPtr req, realsense2_camera_msgs::srv::DeviceInfo::Response::SharedPtr res); tf2::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const; @@ -247,6 +246,7 @@ namespace realsense2_camera std::mutex _publish_tf_mutex; std::mutex _update_sensor_mutex; std::mutex _profile_changes_mutex; + std::mutex _publish_dynamic_tf_mutex; std::shared_ptr _static_tf_broadcaster; std::shared_ptr _dynamic_tf_broadcaster; diff --git a/realsense2_camera/include/dynamic_params.h b/realsense2_camera/include/dynamic_params.h index 208415df7c..0950d2a644 100644 --- a/realsense2_camera/include/dynamic_params.h +++ b/realsense2_camera/include/dynamic_params.h @@ -50,5 +50,7 @@ namespace realsense2_camera std::shared_ptr _update_functions_t; std::deque > _update_functions_v; std::list self_set_parameters; + std::mutex _mu; + }; } diff --git a/realsense2_camera/src/base_realsense_node.cpp b/realsense2_camera/src/base_realsense_node.cpp index 671e794dfe..a97ef85b8d 100755 --- a/realsense2_camera/src/base_realsense_node.cpp +++ b/realsense2_camera/src/base_realsense_node.cpp @@ -22,7 +22,7 @@ using namespace realsense2_camera; SyncedImuPublisher::SyncedImuPublisher(rclcpp::Publisher::SharedPtr imu_publisher, std::size_t waiting_list_size): _publisher(imu_publisher), _pause_mode(false), - _waiting_list_size(waiting_list_size) + _waiting_list_size(waiting_list_size), _is_enabled(false) {} SyncedImuPublisher::~SyncedImuPublisher() @@ -87,10 +87,21 @@ BaseRealSenseNode::BaseRealSenseNode(rclcpp::Node& node, _parameters(parameters), _dev(dev), _json_file_path(""), + _depth_scale_meters(0), + _clipping_distance(0), + _linear_accel_cov(0), + _angular_velocity_cov(0), + _hold_back_imu_for_frames(false), + _publish_tf(false), _tf_publish_rate(TF_PUBLISH_RATE), + _diagnostics_period(0), _use_intra_process(use_intra_process), _is_initialized_time_base(false), + _camera_time_base(0), _sync_frames(SYNC_FRAMES), + _pointcloud(false), + _publish_odom_tf(false), + _imu_sync_method(imu_sync_method::NONE), _is_profile_changed(false), _is_align_depth_changed(false) { @@ -918,7 +929,7 @@ void BaseRealSenseNode::SetBaseStream() } std::vector::const_iterator base_stream(base_stream_priority.begin()); - while( (available_profiles.find(*base_stream) == available_profiles.end()) && (base_stream != base_stream_priority.end())) + while((base_stream != base_stream_priority.end()) && (available_profiles.find(*base_stream) == available_profiles.end())) { base_stream++; } @@ -973,9 +984,7 @@ void BaseRealSenseNode::startDynamicTf() void BaseRealSenseNode::publishDynamicTransforms() { // Publish transforms for the cameras - - std::mutex mu; - std::unique_lock lock(mu); + std::unique_lock lock(_publish_dynamic_tf_mutex); while (rclcpp::ok() && _is_running && _tf_publish_rate > 0) { _cv_tf.wait_for(lock, std::chrono::milliseconds((int)(1000.0/_tf_publish_rate)), [&]{return (!(_is_running && _tf_publish_rate > 0));}); diff --git a/realsense2_camera/src/dynamic_params.cpp b/realsense2_camera/src/dynamic_params.cpp index 7622f54aad..3873ccea5c 100644 --- a/realsense2_camera/src/dynamic_params.cpp +++ b/realsense2_camera/src/dynamic_params.cpp @@ -59,8 +59,7 @@ namespace realsense2_camera { int time_interval(1000); std::function func = [this, time_interval](){ - std::mutex mu; - std::unique_lock lock(mu); + std::unique_lock lock(_mu); while(_is_running) { _update_functions_cv.wait_for(lock, std::chrono::milliseconds(time_interval), [&]{return !_is_running || !_update_functions_v.empty();}); while (!_update_functions_v.empty())