Skip to content

Commit

Permalink
Merge pull request #150 from rosflight/clang-format-tweaks
Browse files Browse the repository at this point in the history
Linter for clang-format
  • Loading branch information
bsutherland333 committed Oct 11, 2023
2 parents cc1c32a + 27ea6b3 commit add3d58
Show file tree
Hide file tree
Showing 25 changed files with 181 additions and 86 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ BraceWrapping:
SplitEmptyRecord: true
BreakBeforeBinaryOperators: NonAssignment
BreakBeforeTernaryOperators: true
BreakConstructorInitializers: BeforeColon
BreakConstructorInitializers: BeforeComma
BreakInheritanceList: BeforeColon
ColumnLimit: 100
CompactNamespaces: false
Expand Down
19 changes: 19 additions & 0 deletions .github/workflows/clang-format.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
name: Clang-Format

on:
push:
branches: [ main ]
pull_request:
branches: [ main ]

jobs:
build:
runs-on: ubuntu-latest

steps:
- uses: actions/checkout@v2
- uses: DoozyX/clang-format-lint-action@v0.14
with:
source: '.'
extensions: 'hpp,cpp'
clangFormatVersion: 14
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# ROSflight

[![ROS2 CI](https://github.com/rosflight/rosflight/actions/workflows/ros2-ci.yml/badge.svg)](https://github.com/rosflight/rosflight/actions/workflows/ros2-ci.yml)
[![ROS2 CI](https://github.com/rosflight/rosflight_ros_pkgs/actions/workflows/ros2-ci.yml/badge.svg)](https://github.com/rosflight/rosflight_ros_pkgs/actions/workflows/ros2-ci.yml) [![clang-format](https://github.com/rosflight/rosflight_ros_pkgs/actions/workflows/clang-format.yml/badge.svg)](https://github.com/rosflight/rosflight_ros_pkgs/actions/workflows/clang-format.yml)

This repository contains a ROS2 stack for interfacing with an autopilot running the ROSflight firmware.
For more information on the ROSflight autopilot firmware stack, visit http://rosflight.org.
Expand Down Expand Up @@ -167,4 +167,4 @@ command `ros2 launch rosflight_utils fixedwing_sim_io_joy.launch.py`.

Note that in order to actually arm and fly the UAV in the simulator, you still need to set the proper parameters on the
flight controller. To do so, launch both the rosflight_sil and rosflight_io nodes. Set all necessary parameters
with `ros2 launch rosflight_utils fixedwing_init_firmware.launch.py`. Wait until launch file completes.
with `ros2 launch rosflight_utils fixedwing_init_firmware.launch.py`. Wait until launch file completes.
2 changes: 1 addition & 1 deletion fix_code_style.sh
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ cd $SCRIPTPATH
# Find all files with ".hpp" or ".cpp" extensions in the current directory and subdirectories,
# excluding certain paths (.rosflight_io/include/mavlink/v1.0/, ./rosflight_firmware/firmware/, and ./.git)
find . -iname "*.hpp" -o -iname "*.cpp" | \
egrep -v "^(.rosflight_io/include/mavlink/v1.0/|./rosflight_firmware/firmware/|./.git)" | \
egrep -v "^(.rosflight_io/include/mavlink/v1.0/|./rosflight_sim/include/rosflight_sim/rosflight_firmware/|./.git)" | \

# Format the files according to the rules specified in .clang-format
xargs clang-format -i
21 changes: 13 additions & 8 deletions rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,12 +101,12 @@ class MavlinkComm
virtual bool is_open() = 0;
virtual void do_open() = 0;
virtual void do_close() = 0;
virtual void do_async_read(
const boost::asio::mutable_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) = 0;
virtual void do_async_write(
const boost::asio::const_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) = 0;
virtual void
do_async_read(const boost::asio::mutable_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) = 0;
virtual void
do_async_write(const boost::asio::const_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) = 0;

boost::asio::io_service io_service_; //!< boost io service provider

Expand All @@ -124,9 +124,14 @@ class MavlinkComm
size_t len;
size_t pos;

WriteBuffer() : len(0), pos(0) {}
WriteBuffer()
: len(0)
, pos(0)
{}

WriteBuffer(const uint8_t * buf, uint16_t len) : len(len), pos(0)
WriteBuffer(const uint8_t * buf, uint16_t len)
: len(len)
, pos(0)
{
assert(len <= MAVLINK_MAX_PACKET_LEN); //! \todo Do something less catastrophic here
memcpy(data, buf, len);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,17 +73,17 @@ class MavlinkSerial : public MavlinkComm
/**
* \brief Initiate an asynchronous read operation
*/
void do_async_read(
const boost::asio::mutable_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;
void
do_async_read(const boost::asio::mutable_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;

/**
* \brief Initialize an asynchronous write operation
* \param check_write_state If true, only start another write operation if a write sequence is not already running
*/
void do_async_write(
const boost::asio::const_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;
void
do_async_write(const boost::asio::const_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;

//===========================================================================
// member variables
Expand Down
12 changes: 6 additions & 6 deletions rosflight_io/include/rosflight_io/mavrosflight/mavlink_udp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,12 +72,12 @@ class MavlinkUDP : public MavlinkComm
bool is_open() override;
void do_open() override;
void do_close() override;
void do_async_read(
const boost::asio::mutable_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;
void do_async_write(
const boost::asio::const_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;
void
do_async_read(const boost::asio::mutable_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;
void
do_async_write(const boost::asio::const_buffers_1 & buffer,
boost::function<void(const boost::system::error_code &, size_t)> handler) override;

//===========================================================================
// member variables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,9 @@ class SerialException : public std::exception

explicit SerialException(const boost::system::system_error & err) { init(err.what()); }

SerialException(const SerialException & other) : what_(other.what_) {}
SerialException(const SerialException & other)
: what_(other.what_)
{}

~SerialException() noexcept override = default;

Expand Down
8 changes: 6 additions & 2 deletions rosflight_io/src/mag_cal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,12 @@
namespace rosflight_io
{
CalibrateMag::CalibrateMag()
: Node("calibrate_accel_temp"), reference_field_strength_(1.0), calibrating_(false),
first_time_(true), start_time_(0), measurement_throttle_(0)
: Node("calibrate_accel_temp")
, reference_field_strength_(1.0)
, calibrating_(false)
, first_time_(true)
, start_time_(0)
, measurement_throttle_(0)
{
A_ = Eigen::MatrixXd::Zero(3, 3);
b_ = Eigen::MatrixXd::Zero(3, 1);
Expand Down
6 changes: 5 additions & 1 deletion rosflight_io/src/mavrosflight/mavlink_comm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,11 @@ namespace mavrosflight
using boost::asio::serial_port_base;

MavlinkComm::MavlinkComm()
: io_service_(), read_buf_raw_(), msg_in_(), status_in_(), write_in_progress_(false)
: io_service_()
, read_buf_raw_()
, msg_in_()
, status_in_()
, write_in_progress_(false)
{}

MavlinkComm::~MavlinkComm() = default;
Expand Down
5 changes: 4 additions & 1 deletion rosflight_io/src/mavrosflight/mavlink_serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,10 @@ namespace mavrosflight
using boost::asio::serial_port_base;

MavlinkSerial::MavlinkSerial(std::string port, int baud_rate)
: MavlinkComm(), serial_port_(io_service_), port_(std::move(port)), baud_rate_(baud_rate)
: MavlinkComm()
, serial_port_(io_service_)
, port_(std::move(port))
, baud_rate_(baud_rate)
{}

MavlinkSerial::~MavlinkSerial() { MavlinkSerial::do_close(); }
Expand Down
8 changes: 6 additions & 2 deletions rosflight_io/src/mavrosflight/mavlink_udp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,12 @@ using boost::asio::serial_port_base;

MavlinkUDP::MavlinkUDP(std::string bind_host, uint16_t bind_port, std::string remote_host,
uint16_t remote_port)
: MavlinkComm(), bind_host_(std::move(bind_host)), bind_port_(bind_port),
remote_host_(std::move(remote_host)), remote_port_(remote_port), socket_(io_service_)
: MavlinkComm()
, bind_host_(std::move(bind_host))
, bind_port_(bind_port)
, remote_host_(std::move(remote_host))
, remote_port_(remote_port)
, socket_(io_service_)
{}

MavlinkUDP::~MavlinkUDP() { MavlinkUDP::do_close(); }
Expand Down
4 changes: 3 additions & 1 deletion rosflight_io/src/mavrosflight/mavrosflight.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,9 @@ namespace mavrosflight
using boost::asio::serial_port_base;

MavROSflight::MavROSflight(MavlinkComm & mavlink_comm, rclcpp::Node * const node)
: comm(mavlink_comm), param(&comm, node), time(&comm, node)
: comm(mavlink_comm)
, param(&comm, node)
, time(&comm, node)
{
comm.open();
}
Expand Down
14 changes: 11 additions & 3 deletions rosflight_io/src/mavrosflight/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,18 @@

namespace mavrosflight
{
Param::Param() : value_(0), new_value_(0), expected_raw_value_(0)
Param::Param()
: value_(0)
, new_value_(0)
, expected_raw_value_(0)
{
init("", -1, MAV_PARAM_TYPE_ENUM_END, 0.0f);
}

Param::Param(mavlink_param_value_t msg) : value_(0), new_value_(0), expected_raw_value_(0)
Param::Param(mavlink_param_value_t msg)
: value_(0)
, new_value_(0)
, expected_raw_value_(0)
{
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
memcpy(name, msg.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
Expand All @@ -53,7 +59,9 @@ Param::Param(mavlink_param_value_t msg) : value_(0), new_value_(0), expected_raw
}

Param::Param(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
: value_(0), new_value_(0), expected_raw_value_(0)
: value_(0)
, new_value_(0)
, expected_raw_value_(0)
{
init(std::move(name), index, type, raw_value);
}
Expand Down
13 changes: 10 additions & 3 deletions rosflight_io/src/mavrosflight/param_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,16 @@
namespace mavrosflight
{
ParamManager::ParamManager(MavlinkComm * const comm, rclcpp::Node * const node)
: node_(node), comm_(comm), unsaved_changes_(false), write_request_in_progress_(false),
first_param_received_(false), num_params_(0), received_count_(0), received_(nullptr),
got_all_params_(false), param_set_in_progress_(false)
: node_(node)
, comm_(comm)
, unsaved_changes_(false)
, write_request_in_progress_(false)
, first_param_received_(false)
, num_params_(0)
, received_count_(0)
, received_(nullptr)
, got_all_params_(false)
, param_set_in_progress_(false)
{
comm_->register_mavlink_listener(this);

Expand Down
9 changes: 6 additions & 3 deletions rosflight_io/src/mavrosflight/time_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,11 @@
namespace mavrosflight
{
TimeManager::TimeManager(MavlinkComm * const comm, rclcpp::Node * const node)
: comm_(comm), node_(node), offset_alpha_(0.95), offset_ns_(0), initialized_(false)
: comm_(comm)
, node_(node)
, offset_alpha_(0.95)
, offset_ns_(0)
, initialized_(false)
{
comm_->register_mavlink_listener(this);
time_sync_timer_ = node_->create_wall_timer(
Expand All @@ -64,8 +68,7 @@ void TimeManager::handle_mavlink_message(const mavlink_message_t & msg)

// if difference > 10ms, use it directly
if (!initialized_ || (offset_ns_ - offset_ns) > std::chrono::milliseconds(10)
|| (offset_ns_ - offset_ns) < std::chrono::milliseconds(-10))
{
|| (offset_ns_ - offset_ns) < std::chrono::milliseconds(-10)) {
RCLCPP_INFO(node_->get_logger(), "Detected time offset of %0.3f s.",
abs(std::chrono::duration<double>(offset_ns_ - offset_ns).count()));
RCLCPP_DEBUG(node_->get_logger(), "FCU time: %0.3f, System time: %0.3f", tsync.tc1 * 1e-9,
Expand Down
4 changes: 3 additions & 1 deletion rosflight_io/src/rosflight_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,9 @@

namespace rosflight_io
{
rosflightIO::rosflightIO() : Node("rosflight_io"), prev_status_()
rosflightIO::rosflightIO()
: Node("rosflight_io")
, prev_status_()
{
command_sub_ = this->create_subscription<rosflight_msgs::msg::Command>(
"command", 1, std::bind(&rosflightIO::commandCallback, this, std::placeholders::_1));
Expand Down
Loading

0 comments on commit add3d58

Please sign in to comment.