From 145989f7e3b55b2d92e971398ee1ba47c978e4bd Mon Sep 17 00:00:00 2001 From: Brandon Sutherland Date: Tue, 3 Oct 2023 13:31:16 -0600 Subject: [PATCH 1/5] Changed clang-format to put class initializations on separate lines --- .clang-format | 2 +- fix_code_style.sh | 2 +- .../mavrosflight/mavlink_comm.hpp | 11 +++-- .../mavrosflight/serial_exception.hpp | 4 +- rosflight_io/src/mag_cal.cpp | 8 +++- .../src/mavrosflight/mavlink_comm.cpp | 6 ++- .../src/mavrosflight/mavlink_serial.cpp | 5 +- rosflight_io/src/mavrosflight/mavlink_udp.cpp | 8 +++- .../src/mavrosflight/mavrosflight.cpp | 4 +- rosflight_io/src/mavrosflight/param.cpp | 14 ++++-- .../src/mavrosflight/param_manager.cpp | 13 +++-- .../src/mavrosflight/time_manager.cpp | 9 ++-- rosflight_io/src/rosflight_io.cpp | 4 +- .../include/rosflight_sim/sil_board.hpp | 2 +- .../include/rosflight_sim/udp_board.hpp | 11 +++-- .../src/fixedwing_forces_and_moments.cpp | 47 ++++++++++++------- .../src/multirotor_forces_and_moments.cpp | 5 +- rosflight_sim/src/rosflight_sil.cpp | 5 +- rosflight_sim/src/sil_board.cpp | 4 +- rosflight_sim/src/udp_board.cpp | 11 +++-- rosflight_utils/src/viz.cpp | 3 +- 21 files changed, 127 insertions(+), 51 deletions(-) diff --git a/.clang-format b/.clang-format index 768dee39..536a1802 100644 --- a/.clang-format +++ b/.clang-format @@ -33,7 +33,7 @@ BraceWrapping: SplitEmptyRecord: true BreakBeforeBinaryOperators: NonAssignment BreakBeforeTernaryOperators: true -BreakConstructorInitializers: BeforeColon +BreakConstructorInitializers: BeforeComma BreakInheritanceList: BeforeColon ColumnLimit: 100 CompactNamespaces: false diff --git a/fix_code_style.sh b/fix_code_style.sh index 9cd52775..ac100a9c 100755 --- a/fix_code_style.sh +++ b/fix_code_style.sh @@ -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 diff --git a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp index f5b4725a..a3b8dc75 100644 --- a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp +++ b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp @@ -124,9 +124,14 @@ class MavlinkComm size_t len; size_t pos; - WriteBuffer() : len(0), pos(0) {} - - WriteBuffer(const uint8_t * buf, uint16_t len) : len(len), pos(0) + WriteBuffer() + : len(0) + , 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); diff --git a/rosflight_io/include/rosflight_io/mavrosflight/serial_exception.hpp b/rosflight_io/include/rosflight_io/mavrosflight/serial_exception.hpp index 3659a68e..bbda5bc1 100644 --- a/rosflight_io/include/rosflight_io/mavrosflight/serial_exception.hpp +++ b/rosflight_io/include/rosflight_io/mavrosflight/serial_exception.hpp @@ -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; diff --git a/rosflight_io/src/mag_cal.cpp b/rosflight_io/src/mag_cal.cpp index 439352f3..efbc6ab0 100644 --- a/rosflight_io/src/mag_cal.cpp +++ b/rosflight_io/src/mag_cal.cpp @@ -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); diff --git a/rosflight_io/src/mavrosflight/mavlink_comm.cpp b/rosflight_io/src/mavrosflight/mavlink_comm.cpp index 80cf2ea8..84de507b 100644 --- a/rosflight_io/src/mavrosflight/mavlink_comm.cpp +++ b/rosflight_io/src/mavrosflight/mavlink_comm.cpp @@ -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; diff --git a/rosflight_io/src/mavrosflight/mavlink_serial.cpp b/rosflight_io/src/mavrosflight/mavlink_serial.cpp index 7b25f349..9142f9d7 100644 --- a/rosflight_io/src/mavrosflight/mavlink_serial.cpp +++ b/rosflight_io/src/mavrosflight/mavlink_serial.cpp @@ -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(); } diff --git a/rosflight_io/src/mavrosflight/mavlink_udp.cpp b/rosflight_io/src/mavrosflight/mavlink_udp.cpp index ed98b12d..babeb7eb 100644 --- a/rosflight_io/src/mavrosflight/mavlink_udp.cpp +++ b/rosflight_io/src/mavrosflight/mavlink_udp.cpp @@ -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(); } diff --git a/rosflight_io/src/mavrosflight/mavrosflight.cpp b/rosflight_io/src/mavrosflight/mavrosflight.cpp index 409c459d..33f2072e 100644 --- a/rosflight_io/src/mavrosflight/mavrosflight.cpp +++ b/rosflight_io/src/mavrosflight/mavrosflight.cpp @@ -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(); } diff --git a/rosflight_io/src/mavrosflight/param.cpp b/rosflight_io/src/mavrosflight/param.cpp index 1936cd2e..592bfd66 100644 --- a/rosflight_io/src/mavrosflight/param.cpp +++ b/rosflight_io/src/mavrosflight/param.cpp @@ -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); @@ -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); } diff --git a/rosflight_io/src/mavrosflight/param_manager.cpp b/rosflight_io/src/mavrosflight/param_manager.cpp index 0dd632ad..600d6c92 100644 --- a/rosflight_io/src/mavrosflight/param_manager.cpp +++ b/rosflight_io/src/mavrosflight/param_manager.cpp @@ -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); diff --git a/rosflight_io/src/mavrosflight/time_manager.cpp b/rosflight_io/src/mavrosflight/time_manager.cpp index 21b02864..09a04461 100644 --- a/rosflight_io/src/mavrosflight/time_manager.cpp +++ b/rosflight_io/src/mavrosflight/time_manager.cpp @@ -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( @@ -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(offset_ns_ - offset_ns).count())); RCLCPP_DEBUG(node_->get_logger(), "FCU time: %0.3f, System time: %0.3f", tsync.tc1 * 1e-9, diff --git a/rosflight_io/src/rosflight_io.cpp b/rosflight_io/src/rosflight_io.cpp index d2e9821d..d14d0ad6 100644 --- a/rosflight_io/src/rosflight_io.cpp +++ b/rosflight_io/src/rosflight_io.cpp @@ -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( "command", 1, std::bind(&rosflightIO::commandCallback, this, std::placeholders::_1)); diff --git a/rosflight_sim/include/rosflight_sim/sil_board.hpp b/rosflight_sim/include/rosflight_sim/sil_board.hpp index 28e563ac..e33914ad 100644 --- a/rosflight_sim/include/rosflight_sim/sil_board.hpp +++ b/rosflight_sim/include/rosflight_sim/sil_board.hpp @@ -48,8 +48,8 @@ #include #include -#include #include +#include namespace rosflight_sim { diff --git a/rosflight_sim/include/rosflight_sim/udp_board.hpp b/rosflight_sim/include/rosflight_sim/udp_board.hpp index b347935c..64718643 100644 --- a/rosflight_sim/include/rosflight_sim/udp_board.hpp +++ b/rosflight_sim/include/rosflight_sim/udp_board.hpp @@ -71,9 +71,14 @@ class UDPBoard : public rosflight_firmware::Board size_t len; size_t pos; - Buffer() : len(0), pos(0) {} - - Buffer(const uint8_t * src, size_t length) : len(length), pos(0) + Buffer() + : len(0) + , pos(0) + {} + + Buffer(const uint8_t * src, size_t length) + : len(length) + , pos(0) { assert(length <= MAVLINK_MAX_PACKET_LEN); //! \todo Do something less catastrophic here memcpy(data, src, length); diff --git a/rosflight_sim/src/fixedwing_forces_and_moments.cpp b/rosflight_sim/src/fixedwing_forces_and_moments.cpp index 35249646..4cf06f09 100644 --- a/rosflight_sim/src/fixedwing_forces_and_moments.cpp +++ b/rosflight_sim/src/fixedwing_forces_and_moments.cpp @@ -37,8 +37,17 @@ namespace rosflight_sim { Fixedwing::Fixedwing(rclcpp::Node::SharedPtr node) - : node_(std::move(node)), rho_(0), wing_(), prop_(), CL_(), CD_(), Cm_(), CY_(), Cell_(), Cn_(), - delta_() + : node_(std::move(node)) + , rho_(0) + , wing_() + , prop_() + , CL_() + , CD_() + , Cm_() + , CY_() + , Cell_() + , Cn_() + , delta_() { declare_fixedwing_params(); update_params_from_ROS(); @@ -175,7 +184,7 @@ void Fixedwing::update_params_from_ROS() RCLCPP_ERROR(node_->get_logger(), "Param 'prop_C' not defined"); } - if(!node_->get_parameter("servo_tau", servo_tau_)){ + if (!node_->get_parameter("servo_tau", servo_tau_)) { RCLCPP_ERROR(node_->get_logger(), "Param 'servo_tau' not defined"); } @@ -354,7 +363,8 @@ void Fixedwing::update_params_from_ROS() } } -Eigen::Matrix Fixedwing::update_forces_and_torques(CurrentState x, const int act_cmds[]) +Eigen::Matrix Fixedwing::update_forces_and_torques(CurrentState x, + const int act_cmds[]) { delta_.a = (act_cmds[0] - 1500.0) / 500.0; delta_.e = -(act_cmds[1] - 1500.0) / 500.0; @@ -365,8 +375,10 @@ Eigen::Matrix Fixedwing::update_forces_and_torques(CurrentState x, float Ts = .003; // refresh rate TODO find a way to programmatically set this. - delta_curr.a = 1/(2*servo_tau_/Ts + 1) * (delta_prev_command_.a + delta_.a + (2*servo_tau_/Ts - 1)*delta_prev_.a); - delta_curr.e = 1/(2*servo_tau_/Ts + 1) * (delta_prev_command_.e + delta_.e + (2*servo_tau_/Ts - 1)*delta_prev_.e); + delta_curr.a = 1 / (2 * servo_tau_ / Ts + 1) + * (delta_prev_command_.a + delta_.a + (2 * servo_tau_ / Ts - 1) * delta_prev_.a); + delta_curr.e = 1 / (2 * servo_tau_ / Ts + 1) + * (delta_prev_command_.e + delta_.e + (2 * servo_tau_ / Ts - 1) * delta_prev_.e); delta_prev_ = delta_curr; @@ -418,25 +430,28 @@ Eigen::Matrix Fixedwing::update_forces_and_torques(CurrentState x, double CZ_q_a = -CD_.q * sa - CL_.q * ca; double CZ_deltaE_a = -CD_.delta_e * sa - CL_.delta_e * ca; - forces(0) = 0.5 * (rho_) * Va * Va * wing_.S - * (CX_a + (CX_q_a * wing_.c * q) / (2.0 * Va) + CX_deltaE_a * delta_curr.e) + forces(0) = 0.5 * (rho_) *Va * Va * wing_.S + * (CX_a + (CX_q_a * wing_.c * q) / (2.0 * Va) + CX_deltaE_a * delta_curr.e) + 0.5 * rho_ * prop_.S * prop_.C * (pow((prop_.k_motor * delta_.t), 2.0) - Va * Va); - forces(1) = 0.5 * (rho_) * Va * Va * wing_.S + forces(1) = 0.5 * (rho_) *Va * Va * wing_.S * (CY_.O + CY_.beta * beta + ((CY_.p * wing_.b * p) / (2.0 * Va)) - + ((CY_.r * wing_.b * r) / (2.0 * Va)) + CY_.delta_a * delta_curr.a + CY_.delta_r * delta_.r); - forces(2) = 0.5 * (rho_) * Va * Va * wing_.S + + ((CY_.r * wing_.b * r) / (2.0 * Va)) + CY_.delta_a * delta_curr.a + + CY_.delta_r * delta_.r); + forces(2) = 0.5 * (rho_) *Va * Va * wing_.S * (CZ_a + (CZ_q_a * wing_.c * q) / (2.0 * Va) + CZ_deltaE_a * delta_curr.e); - forces(3) = 0.5 * (rho_) * Va * Va * wing_.S * wing_.b + forces(3) = 0.5 * (rho_) *Va * Va * wing_.S * wing_.b * (Cell_.O + Cell_.beta * beta + (Cell_.p * wing_.b * p) / (2.0 * Va) + (Cell_.r * wing_.b * r) / (2.0 * Va) + Cell_.delta_a * delta_curr.a + Cell_.delta_r * delta_.r) - prop_.k_T_P * pow((prop_.k_Omega * delta_.t), 2.0); - forces(4) = 0.5 * (rho_) * Va * Va * wing_.S * wing_.c - * (Cm_.O + Cm_.alpha * alpha + (Cm_.q * wing_.c * q) / (2.0 * Va) + Cm_.delta_e * delta_curr.e); - forces(5) = 0.5 * (rho_) * Va * Va * wing_.S * wing_.b + forces(4) = 0.5 * (rho_) *Va * Va * wing_.S * wing_.c + * (Cm_.O + Cm_.alpha * alpha + (Cm_.q * wing_.c * q) / (2.0 * Va) + + Cm_.delta_e * delta_curr.e); + forces(5) = 0.5 * (rho_) *Va * Va * wing_.S * wing_.b * (Cn_.O + Cn_.beta * beta + (Cn_.p * wing_.b * p) / (2.0 * Va) - + (Cn_.r * wing_.b * r) / (2.0 * Va) + Cn_.delta_a * delta_curr.a + Cn_.delta_r * delta_.r); + + (Cn_.r * wing_.b * r) / (2.0 * Va) + Cn_.delta_a * delta_curr.a + + Cn_.delta_r * delta_.r); } else { forces(0) = 0.5 * rho_ * prop_.S * prop_.C * ((prop_.k_motor * delta_.t * prop_.k_motor * delta_.t)); diff --git a/rosflight_sim/src/multirotor_forces_and_moments.cpp b/rosflight_sim/src/multirotor_forces_and_moments.cpp index 3805673c..25dcf358 100644 --- a/rosflight_sim/src/multirotor_forces_and_moments.cpp +++ b/rosflight_sim/src/multirotor_forces_and_moments.cpp @@ -37,7 +37,10 @@ namespace rosflight_sim { Multirotor::Multirotor(rclcpp::Node::SharedPtr node) - : node_(std::move(node)), num_rotors_(0), linear_mu_(0), angular_mu_(0) + : node_(std::move(node)) + , num_rotors_(0) + , linear_mu_(0) + , angular_mu_(0) { declare_multirotor_params(); diff --git a/rosflight_sim/src/rosflight_sil.cpp b/rosflight_sim/src/rosflight_sil.cpp index acec4cf1..dfff38a5 100644 --- a/rosflight_sim/src/rosflight_sil.cpp +++ b/rosflight_sim/src/rosflight_sil.cpp @@ -43,7 +43,10 @@ namespace rosflight_sim { ROSflightSIL::ROSflightSIL() - : gazebo::ModelPlugin(), comm_(board_), firmware_(board_, comm_), mav_dynamics_() + : gazebo::ModelPlugin() + , comm_(board_) + , firmware_(board_, comm_) + , mav_dynamics_() {} ROSflightSIL::~ROSflightSIL() { GZ_COMPAT_DISCONNECT_WORLD_UPDATE_BEGIN(updateConnection_); } diff --git a/rosflight_sim/src/sil_board.cpp b/rosflight_sim/src/sil_board.cpp index 92800893..59f28cda 100644 --- a/rosflight_sim/src/sil_board.cpp +++ b/rosflight_sim/src/sil_board.cpp @@ -40,8 +40,8 @@ namespace rosflight_sim { SILBoard::SILBoard() - : UDPBoard(), - random_generator_(std::chrono::system_clock::now().time_since_epoch().count()) + : UDPBoard() + , random_generator_(std::chrono::system_clock::now().time_since_epoch().count()) {} void SILBoard::init_board() { boot_time_ = GZ_COMPAT_GET_SIM_TIME(world_); } diff --git a/rosflight_sim/src/udp_board.cpp b/rosflight_sim/src/udp_board.cpp index 8adf92c9..6a7fa55b 100644 --- a/rosflight_sim/src/udp_board.cpp +++ b/rosflight_sim/src/udp_board.cpp @@ -34,8 +34,8 @@ * \author Daniel Koch */ -#include #include "rosflight_sim/udp_board.hpp" +#include using boost::asio::ip::udp; @@ -43,8 +43,13 @@ namespace rosflight_sim { UDPBoard::UDPBoard(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port) - : bind_host_(std::move(bind_host)), bind_port_(bind_port), remote_host_(std::move(remote_host)), - remote_port_(remote_port), io_service_(), socket_(io_service_), write_in_progress_(false) + : bind_host_(std::move(bind_host)) + , bind_port_(bind_port) + , remote_host_(std::move(remote_host)) + , remote_port_(remote_port) + , io_service_() + , socket_(io_service_) + , write_in_progress_(false) {} UDPBoard::~UDPBoard() diff --git a/rosflight_utils/src/viz.cpp b/rosflight_utils/src/viz.cpp index ac4fe11f..0ad19945 100644 --- a/rosflight_utils/src/viz.cpp +++ b/rosflight_utils/src/viz.cpp @@ -36,7 +36,8 @@ namespace rosflight_utils { -Viz::Viz() : Node("viz_node") +Viz::Viz() + : Node("viz_node") { // retrieve params From f213cc12bbc8fdcccdbd6e8e6c8da2d20cd6cbb9 Mon Sep 17 00:00:00 2001 From: Brandon Sutherland Date: Tue, 3 Oct 2023 13:37:08 -0600 Subject: [PATCH 2/5] Gave up on trying to fix some edge-case clang-format behavior --- .../mavrosflight/mavlink_comm.hpp | 12 +++---- .../mavrosflight/mavlink_serial.hpp | 12 +++---- .../rosflight_io/mavrosflight/mavlink_udp.hpp | 12 +++---- .../include/rosflight_sim/sil_board.hpp | 32 +++++++++---------- 4 files changed, 34 insertions(+), 34 deletions(-) diff --git a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp index a3b8dc75..89a8fec7 100644 --- a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp +++ b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_comm.hpp @@ -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 handler) = 0; - virtual void do_async_write( - const boost::asio::const_buffers_1 & buffer, - boost::function handler) = 0; + virtual void + do_async_read(const boost::asio::mutable_buffers_1 & buffer, + boost::function handler) = 0; + virtual void + do_async_write(const boost::asio::const_buffers_1 & buffer, + boost::function handler) = 0; boost::asio::io_service io_service_; //!< boost io service provider diff --git a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_serial.hpp b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_serial.hpp index 450c9408..8dc42da5 100644 --- a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_serial.hpp +++ b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_serial.hpp @@ -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 handler) override; + void + do_async_read(const boost::asio::mutable_buffers_1 & buffer, + boost::function 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 handler) override; + void + do_async_write(const boost::asio::const_buffers_1 & buffer, + boost::function handler) override; //=========================================================================== // member variables diff --git a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_udp.hpp b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_udp.hpp index 35d38326..1c1876c0 100644 --- a/rosflight_io/include/rosflight_io/mavrosflight/mavlink_udp.hpp +++ b/rosflight_io/include/rosflight_io/mavrosflight/mavlink_udp.hpp @@ -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 handler) override; - void do_async_write( - const boost::asio::const_buffers_1 & buffer, - boost::function handler) override; + void + do_async_read(const boost::asio::mutable_buffers_1 & buffer, + boost::function handler) override; + void + do_async_write(const boost::asio::const_buffers_1 & buffer, + boost::function handler) override; //=========================================================================== // member variables diff --git a/rosflight_sim/include/rosflight_sim/sil_board.hpp b/rosflight_sim/include/rosflight_sim/sil_board.hpp index e33914ad..4fe4c437 100644 --- a/rosflight_sim/include/rosflight_sim/sil_board.hpp +++ b/rosflight_sim/include/rosflight_sim/sil_board.hpp @@ -164,7 +164,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void board_reset(bool bootloader) override {}; + void board_reset(bool bootloader) override{}; // clock /** @@ -182,7 +182,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void clock_delay(uint32_t milliseconds) override {}; + void clock_delay(uint32_t milliseconds) override{}; // serial /** @@ -247,7 +247,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void mag_update() override {}; + void mag_update() override{}; /** * @brief Function used to check if a barometer is present. Currently returns true. @@ -266,7 +266,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void baro_update() override {}; + void baro_update() override{}; /** * @brief Checks if a pitot tube sensor is present. Returns true if sim is a fixedwing sim. @@ -285,7 +285,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void diff_pressure_update() override {}; + void diff_pressure_update() override{}; /** * @brief Function used to see if a sonar altitude sensor is present. Currently returns true. @@ -305,7 +305,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void sonar_update() override {}; + void sonar_update() override{}; // PWM // TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific) @@ -344,7 +344,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void rc_init(rc_type_t rc_type) override {}; + void rc_init(rc_type_t rc_type) override{}; /** * @brief Function used to check if RC connection is present. Currently returns false if anything * is ever published on RC. @@ -357,7 +357,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void memory_init() override {}; + void memory_init() override{}; /** * @brief Reads data from memory file. * @@ -379,34 +379,34 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void led0_on() override {}; + void led0_on() override{}; /** * @brief Function required to be overridden, but not used by sim. */ - void led0_off() override {}; + void led0_off() override{}; /** * @brief Function required to be overridden, but not used by sim. */ - void led0_toggle() override {}; + void led0_toggle() override{}; /** * @brief Function required to be overridden, but not used by sim. */ - void led1_on() override {}; + void led1_on() override{}; /** * @brief Function required to be overridden, but not used by sim. */ - void led1_off() override {}; + void led1_off() override{}; /** * @brief Function required to be overridden, but not used by sim. */ - void led1_toggle() override {}; + void led1_toggle() override{}; // Backup Memory /** * @brief Function required to be overridden, but not used by sim. */ - void backup_memory_init() override {}; + void backup_memory_init() override{}; /** * @brief Reads data from backup memory object. * @@ -440,7 +440,7 @@ class SILBoard : public UDPBoard /** * @brief Function required to be overridden, but not used by sim. */ - void gnss_update() override {}; + void gnss_update() override{}; /** * @brief Generates GNSS data based on Gazebo truth and noise/bias parameters. From 6fe78bfc5b94caba2b718fe34a0361ebb009c3b0 Mon Sep 17 00:00:00 2001 From: Brandon Sutherland Date: Tue, 3 Oct 2023 13:42:57 -0600 Subject: [PATCH 3/5] Added clang-format linter check --- .github/workflows/clang-format.yml | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) create mode 100644 .github/workflows/clang-format.yml diff --git a/.github/workflows/clang-format.yml b/.github/workflows/clang-format.yml new file mode 100644 index 00000000..03a1192d --- /dev/null +++ b/.github/workflows/clang-format.yml @@ -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.16 + with: + source: '.' + extensions: 'hpp,cpp' + clangFormatVersion: 16 From cb2a29d2c4f24fd7720654064bd0b1068c4ea66e Mon Sep 17 00:00:00 2001 From: Brandon Sutherland Date: Tue, 3 Oct 2023 13:49:12 -0600 Subject: [PATCH 4/5] Attempting to fix clang-format linter failing to run --- .github/workflows/clang-format.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/clang-format.yml b/.github/workflows/clang-format.yml index 03a1192d..ccf0ca42 100644 --- a/.github/workflows/clang-format.yml +++ b/.github/workflows/clang-format.yml @@ -12,8 +12,8 @@ jobs: steps: - uses: actions/checkout@v2 - - uses: DoozyX/clang-format-lint-action@v0.16 + - uses: DoozyX/clang-format-lint-action@v0.14 with: source: '.' extensions: 'hpp,cpp' - clangFormatVersion: 16 + clangFormatVersion: 14 From 27ea6b39a53ca695098e0a266d42f64ca3ab2874 Mon Sep 17 00:00:00 2001 From: Brandon Sutherland Date: Tue, 3 Oct 2023 13:53:04 -0600 Subject: [PATCH 5/5] Added linter status badge --- .github/workflows/clang-format.yml | 2 +- README.md | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/clang-format.yml b/.github/workflows/clang-format.yml index ccf0ca42..a40bd495 100644 --- a/.github/workflows/clang-format.yml +++ b/.github/workflows/clang-format.yml @@ -1,4 +1,4 @@ -name: clang-format +name: Clang-Format on: push: diff --git a/README.md b/README.md index 500f9099..2549629a 100644 --- a/README.md +++ b/README.md @@ -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. @@ -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. \ No newline at end of file +with `ros2 launch rosflight_utils fixedwing_init_firmware.launch.py`. Wait until launch file completes.