Skip to content

Commit

Permalink
Add workflow for static checks (#31)
Browse files Browse the repository at this point in the history
* Add workflows for cpplint and cppcheck.

- Add GitHub workflows for static checks.
- Style changes for conformance with Google style enforced by cpplint.
- Apply exceptions / filters documented in CPPLINT.cfg.
- Changes mostly concern line length, indentation within namespaces, and terminating whitespace.

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>

* Add status badges for cpplink and cppcheck. Fix badge for build.

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
  • Loading branch information
srmainwaring authored Dec 14, 2022
1 parent 5b30c4a commit 8686cc1
Show file tree
Hide file tree
Showing 13 changed files with 600 additions and 401 deletions.
21 changes: 21 additions & 0 deletions .github/workflows/ccpcheck.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
# GitHub Action to run cppcheck
#
name: cppcheck

on: [push, pull_request]

jobs:
cpplint:
runs-on: ubuntu-20.04
name: cppcheck
steps:
- name: Checkout
uses: actions/checkout@v3
- name: Install cppcheck
run: |
sudo apt-get update
sudo apt-get install cppcheck
- name: Run cppcheck
run: |
cppcheck --std=c++17 ./include/*.hh
cppcheck --std=c++17 ./src/*.cc
28 changes: 28 additions & 0 deletions .github/workflows/ccplint.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# GitHub Action to run cpplint
#
# The cpplint configuration file is:
#
# ./CPPLINT.cfg
#
name: ccplint

on: [push, pull_request]

jobs:
cpplint:
runs-on: ubuntu-20.04
name: cpplint
steps:
- name: Checkout
uses: actions/checkout@v3
- name: Setup
uses: actions/setup-python@v4
with:
python-version: '3.10'
- name: Install cpplint
run: |
pip install cpplint
- name: Run cpplint
run: |
cpplint ./include/*.hh
cpplint ./src/*.cc
56 changes: 56 additions & 0 deletions CPPLINT.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# filters
#
# 1. [-whitespace/braces]
# { should almost always be at the end of the previous line
#
# Allow:
# bool SocketAPM::pollout(uint32_t timeout_ms)
# {
#
# Instead of:
# bool SocketAPM::pollout(uint32_t timeout_ms) {
#
# 2. [-runtime/references]
# Is this a non-const reference? If so, make const or use a pointer
#
# Allow:
# void last_recv_address(const char *&ip_addr, uint16_t &port);
#
# Instead of:
# void last_recv_address(const char *&ip_addr, uint16_t *port);
#
# 3. [-whitespace/indent]
# private: should be indented +1 space
#
# 4. [-whitespace/blank_line]
# Do not leave a blank line after "private:"
#
# 3 and 4 are to allow Gazebo Sim class formatting where each
# function / method must have an access specifier.
#
#
# 5. [-whitespace/newline]
# An else should appear on the same line as the preceding }
#
# Allow:
# }
# else if (time > this->dataPtr->lastUpdateTime)
# {
#
# Instead of:
# } else if (time > this->dataPtr->lastUpdateTime) {
#
# 6. [-build/include_subdir]
# Include the directory when naming header files
#
# This prevent an error when including the plugin headers as:
# #include "GimbalSmall2dPlugin.hh"
#
# 7. [-build/c++11], [+build/c++14]
#
# This is to allow headers not approved for C++11 such as <chrono> etc.
#
set noparent
filter=-whitespace/braces,-runtime/references,-whitespace/indent,-whitespace/blank_line,-whitespace/newline,-build/include_subdir,-build/c++11,+build/c++14
linelength=80
root=include
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
# ArduPilot Gazebo Plugin

[![ubuntu-build](https://github.com/srmainwaring/ardupilot_gazebo-1/actions/workflows/ubuntu-build.yml/badge.svg)](https://github.com/srmainwaring/ardupilot_gazebo-1/actions/workflows/ubuntu-build.yml)
[![ubuntu-build](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ubuntu-build.yml/badge.svg)](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ubuntu-build.yml)
[![ccplint](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccplint.yml/badge.svg)](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccplint.yml)
[![cppcheck](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccpcheck.yml/badge.svg)](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccpcheck.yml)

This is the official ArduPilot plugin for [Gazebo Sim](https://gazebosim.org/home).
It replaces the previous
Expand Down
70 changes: 36 additions & 34 deletions include/ArduCopterIRLockPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef _GAZEBO_ARDUCOPTERIRLOCK_PLUGIN_HH_
#define _GAZEBO_ARDUCOPTERIRLOCK_PLUGIN_HH_
#ifndef ARDUCOPTERIRLOCKPLUGIN_HH_
#define ARDUCOPTERIRLOCKPLUGIN_HH_

#include <string>
#include <memory>
Expand All @@ -26,41 +26,43 @@

namespace gazebo
{
// Forward declare private class.
class ArduCopterIRLockPluginPrivate;
// Forward declare private class.
class ArduCopterIRLockPluginPrivate;

/// \brief A camera sensor plugin for fiducial detection
class GAZEBO_VISIBLE ArduCopterIRLockPlugin : public SensorPlugin
{
/// \brief Constructor
public: ArduCopterIRLockPlugin();
/// \brief A camera sensor plugin for fiducial detection
class GAZEBO_VISIBLE ArduCopterIRLockPlugin : public SensorPlugin
{
/// \brief Constructor
public: ArduCopterIRLockPlugin();

/// \brief Destructor
public: virtual ~ArduCopterIRLockPlugin();

// Documentation Inherited.
public: void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);

/// \brief Destructor
public: virtual ~ArduCopterIRLockPlugin();
/// \brief Callback when a new camera frame is available
/// \param[in] _image image data
/// \param[in] _width image width
/// \param[in] _height image height
/// \param[in] _depth image depth
/// \param[in] _format image format
public: virtual void OnNewFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format);

// Documentation Inherited.
public: void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
/// \brief Publish the result
/// \param[in] _name Name of fiducial
/// \param[in] _x x position in image
/// \param[in] _y y position in image
public: virtual void Publish(const std::string &_fiducial, unsigned int _x,
unsigned int _y);

/// \brief Callback when a new camera frame is available
/// \param[in] _image image data
/// \param[in] _width image width
/// \param[in] _height image height
/// \param[in] _depth image depth
/// \param[in] _format image format
public: virtual void OnNewFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format);
/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<ArduCopterIRLockPluginPrivate> dataPtr;
};

/// \brief Publish the result
/// \param[in] _name Name of fiducial
/// \param[in] _x x position in image
/// \param[in] _y y position in image
public: virtual void Publish(const std::string &_fiducial, unsigned int _x,
unsigned int _y);
} // namespace gazebo

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<ArduCopterIRLockPluginPrivate> dataPtr;
};
}
#endif
#endif // ARDUCOPTERIRLOCKPLUGIN_HH_
Loading

0 comments on commit 8686cc1

Please sign in to comment.