Skip to content

Commit

Permalink
add static_analysis.yaml to project and fix some code to pass cppchec…
Browse files Browse the repository at this point in the history
…k run
  • Loading branch information
SamerKhshiboun committed Feb 1, 2023
1 parent 1173504 commit 4404564
Show file tree
Hide file tree
Showing 5 changed files with 79 additions and 9 deletions.
60 changes: 60 additions & 0 deletions .github/workflows/static_analysis.yaml
Original file line number Diff line number Diff line change
@@ -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
4 changes: 2 additions & 2 deletions realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,6 @@ namespace realsense2_camera
class SyncedImuPublisher
{
public:
SyncedImuPublisher() {_is_enabled=false;};
SyncedImuPublisher(rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr imu_publisher,
std::size_t waiting_list_size=1000);
~SyncedImuPublisher();
Expand Down Expand Up @@ -146,7 +145,7 @@ namespace realsense2_camera
std::list<std::string> _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;
Expand Down Expand Up @@ -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<tf2_ros::StaticTransformBroadcaster> _static_tf_broadcaster;
std::shared_ptr<tf2_ros::TransformBroadcaster> _dynamic_tf_broadcaster;
Expand Down
2 changes: 2 additions & 0 deletions realsense2_camera/include/dynamic_params.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,5 +50,7 @@ namespace realsense2_camera
std::shared_ptr<std::thread> _update_functions_t;
std::deque<std::function<void()> > _update_functions_v;
std::list<std::string> self_set_parameters;
std::mutex _mu;

};
}
19 changes: 14 additions & 5 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ using namespace realsense2_camera;
SyncedImuPublisher::SyncedImuPublisher(rclcpp::Publisher<sensor_msgs::msg::Imu>::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()
Expand Down Expand Up @@ -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)
{
Expand Down Expand Up @@ -918,7 +929,7 @@ void BaseRealSenseNode::SetBaseStream()
}

std::vector<stream_index_pair>::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++;
}
Expand Down Expand Up @@ -973,9 +984,7 @@ void BaseRealSenseNode::startDynamicTf()
void BaseRealSenseNode::publishDynamicTransforms()
{
// Publish transforms for the cameras

std::mutex mu;
std::unique_lock<std::mutex> lock(mu);
std::unique_lock<std::mutex> 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));});
Expand Down
3 changes: 1 addition & 2 deletions realsense2_camera/src/dynamic_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,7 @@ namespace realsense2_camera
{
int time_interval(1000);
std::function<void()> func = [this, time_interval](){
std::mutex mu;
std::unique_lock<std::mutex> lock(mu);
std::unique_lock<std::mutex> 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())
Expand Down

0 comments on commit 4404564

Please sign in to comment.