doesn't pass colcon test's ament uncrustify. also need to work with pre-commit.
atticus@rospi-ssh-session [publish_ws]
~/workspace/publish_ws
12:45:11 $ colcon test-result --verbose
- uncrustify
<<< failure message
-- run_test.py: invoking following command in '/home/atticus/workspace/publish_ws/src/ros2_rpi_pwm_hardware_interface':
- /opt/ros/humble/bin/ament_uncrustify --xunit-file /home/atticus/workspace/publish_ws/build/rpi_pwm_hardware_interface/test_results/rpi_pwm_hardware_interface/uncrustify.xunit.xml
Code style divergence in file 'include/rpi_pwm_hardware_interface/angular_servo.hpp':
--- include/rpi_pwm_hardware_interface/angular_servo.hpp
+++ include/rpi_pwm_hardware_interface/angular_servo.hpp.uncrustify
@@ -3,5 +3,6 @@
-class Servo {
- public:
- Servo(int pi, int pin);
- int getPulseWidth();
- void setPulseWidth(int pulseWidth);
+class Servo
+{
+public:
+ Servo(int pi, int pin);
+ int getPulseWidth();
+ void setPulseWidth(int pulseWidth);
@@ -9,3 +10,4 @@
- int __pi; // TODO rename to indicate public, and pigpio pi
- protected:
- int __pin;
+ int __pi; // TODO rename to indicate public, and pigpio pi
+
+protected:
+ int __pin;
@@ -14,5 +16,8 @@
-class AngularServo : public Servo {
- public:
- AngularServo(int pi, int pin, float minAngle, float maxAngle, int minPulseWidthUs, int maxPulseWidthUs);
- void setAngle(float angle);
- int getAngle();
+class AngularServo : public Servo
+{
+public:
+ AngularServo(
+ int pi, int pin, float minAngle, float maxAngle, int minPulseWidthUs,
+ int maxPulseWidthUs);
+ void setAngle(float angle);
+ int getAngle();
@@ -20,6 +25,6 @@
- protected:
- float __angle;
- float __minAngle;
- float __maxAngle;
- int __minPulseWidthUs;
- int __maxPulseWidthUs;
+protected:
+ float __angle;
+ float __minAngle;
+ float __maxAngle;
+ int __minPulseWidthUs;
+ int __maxPulseWidthUs;
@@ -31 +35,0 @@
-
Code style divergence in file 'include/rpi_pwm_hardware_interface/rpi_pwm_hardware_interface.hpp':
--- include/rpi_pwm_hardware_interface/rpi_pwm_hardware_interface.hpp
+++ include/rpi_pwm_hardware_interface/rpi_pwm_hardware_interface.hpp.uncrustify
@@ -37,10 +37,10 @@
-struct ServoConfig
-{
- std::string name = "";
- int pin = 0;
- int pi = 0;
- float min_angle = 0.0;
- float max_angle = 0.0;
- int min_pulse_width_us = 0;
- int max_pulse_width_us = 0;
-};
+ struct ServoConfig
+ {
+ std::string name = "";
+ int pin = 0;
+ int pi = 0;
+ float min_angle = 0.0;
+ float max_angle = 0.0;
+ int min_pulse_width_us = 0;
+ int max_pulse_width_us = 0;
+ };
@@ -48,7 +48,7 @@
-struct ServoJoint
-{
- std::string name = "";
- std::unique_ptr<AngularServo> servo;
- double pos = 0;
- double cmd = 0;
-};
+ struct ServoJoint
+ {
+ std::string name = "";
+ std::unique_ptr<AngularServo> servo;
+ double pos = 0;
+ double cmd = 0;
+ };
Code style divergence in file 'src/angular_servo.cpp':
--- src/angular_servo.cpp
+++ src/angular_servo.cpp.uncrustify
@@ -10 +10 @@
-// TODO revisit private vs protected vars - maybe swap to private
+// TODO revisit private vs protected vars - maybe swap to private
@@ -12,14 +12,15 @@
-Servo::Servo(int pi, int pin) {
- __pi = pi;
- __pin = pin;
- int rc;
- rc = set_mode(__pi, __pin, PI_OUTPUT);
- if (rc < 0){
- throw "Invalid GPIO pin or mode Error!";
- }
-
- // initializing to zero with pigpio is no input
- rc = set_servo_pulsewidth(__pi, __pin, 0);
- if (rc < 0) {
- throw "Invalid user GPIO pin or pulsewidth Error!";
- }
+Servo::Servo(int pi, int pin)
+{
+ __pi = pi;
+ __pin = pin;
+ int rc;
+ rc = set_mode(__pi, __pin, PI_OUTPUT);
+ if (rc < 0) {
+ throw "Invalid GPIO pin or mode Error!";
+ }
+
+ // initializing to zero with pigpio is no input
+ rc = set_servo_pulsewidth(__pi, __pin, 0);
+ if (rc < 0) {
+ throw "Invalid user GPIO pin or pulsewidth Error!";
+ }
@@ -28,6 +29,7 @@
-int Servo::getPulseWidth() {
- int rc = get_servo_pulsewidth(__pi, __pin);
- if (rc < 0) {
- throw "Invalid user GPIO pin Error!";
- }
- return rc;
+int Servo::getPulseWidth()
+{
+ int rc = get_servo_pulsewidth(__pi, __pin);
+ if (rc < 0) {
+ throw "Invalid user GPIO pin Error!";
+ }
+ return rc;
@@ -36,5 +38,6 @@
-void Servo::setPulseWidth(int pulseWidth){
- int rc = set_servo_pulsewidth(__pi, __pin, pulseWidth);
- if (rc < 0) {
- throw "Invalid user GPIO pin or pulsewidth Error!";
- }
+void Servo::setPulseWidth(int pulseWidth)
+{
+ int rc = set_servo_pulsewidth(__pi, __pin, pulseWidth);
+ if (rc < 0) {
+ throw "Invalid user GPIO pin or pulsewidth Error!";
+ }
@@ -43,5 +46,9 @@
-AngularServo::AngularServo(int pi, int pin, float minAngle, float maxAngle, int minPulseWidthUs, int maxPulseWidthUs) : Servo(pi, pin) {
- __minAngle = minAngle;
- __maxAngle = maxAngle;
- __minPulseWidthUs = minPulseWidthUs;
- __maxPulseWidthUs = maxPulseWidthUs;
+AngularServo::AngularServo(
+ int pi, int pin, float minAngle, float maxAngle, int minPulseWidthUs,
+ int maxPulseWidthUs)
+: Servo(pi, pin)
+{
+ __minAngle = minAngle;
+ __maxAngle = maxAngle;
+ __minPulseWidthUs = minPulseWidthUs;
+ __maxPulseWidthUs = maxPulseWidthUs;
@@ -50,10 +57,12 @@
-void AngularServo::setAngle(float angle){
- __angle = angle;
- // make sure angle is within bounds
- if (__angle < __minAngle){
- __angle = __minAngle;
- }
- if (__angle > __maxAngle){
- __angle = __maxAngle;
- }
- int pulseWidth = __minPulseWidthUs + (__angle - __minAngle) * (__maxPulseWidthUs - __minPulseWidthUs) / (__maxAngle - __minAngle);
+void AngularServo::setAngle(float angle)
+{
+ __angle = angle;
+ // make sure angle is within bounds
+ if (__angle < __minAngle) {
+ __angle = __minAngle;
+ }
+ if (__angle > __maxAngle) {
+ __angle = __maxAngle;
+ }
+ int pulseWidth = __minPulseWidthUs + (__angle - __minAngle) *
+ (__maxPulseWidthUs - __minPulseWidthUs) / (__maxAngle - __minAngle);
@@ -61 +70 @@
- setPulseWidth(pulseWidth);
+ setPulseWidth(pulseWidth);
@@ -64,4 +73,6 @@
-int AngularServo::getAngle(){
- int pulseWidth = getPulseWidth();
- float angle = __minAngle + (pulseWidth - __minPulseWidthUs) * (__maxAngle - __minAngle) / (__maxPulseWidthUs - __minPulseWidthUs);
- return angle;
+int AngularServo::getAngle()
+{
+ int pulseWidth = getPulseWidth();
+ float angle = __minAngle + (pulseWidth - __minPulseWidthUs) * (__maxAngle - __minAngle) /
+ (__maxPulseWidthUs - __minPulseWidthUs);
+ return angle;
@@ -70,2 +81,17 @@
-bool isPigpiodRunning() {
- int result = system("pgrep pigpiod");
+bool isPigpiodRunning()
+{
+ int result = system("pgrep pigpiod");
+
+ if (result == 0) {
+ // pigpiod daemon is running
+ return true;
+ } else {
+ // pigpiod daemon is not running
+ return false;
+ }
+}
+
+void killPigpiod()
+{
+ if (isPigpiodRunning()) {
+ int result = system("sudo killall pigpiod -q");
@@ -74,2 +100,2 @@
- // pigpiod daemon is running
- return true;
+ // Successfully killed the pigpiod daemon
+ cout << "pigpiod daemon killed successfully" << endl;
@@ -77,2 +103,2 @@
- // pigpiod daemon is not running
- return false;
+ // An error occurred while trying to kill the pigpiod daemon
+ cerr << "Error killing pigpiod daemon. Return code: " << result << endl;
@@ -79,0 +106,3 @@
+ } else {
+ cout << "pigpiod daemon is not running" << endl;
+ }
@@ -82 +111,7 @@
-void killPigpiod() {
+void startPigpiod()
+{
+ if (!isPigpiodRunning()) {
+ cout << "pigpio daemon not running. attempting to start it." << endl;
+ system("sudo systemctl start pigpiod");
+ sleep(1);
+
@@ -84,9 +119,2 @@
- int result = system("sudo killall pigpiod -q");
-
- if (result == 0) {
- // Successfully killed the pigpiod daemon
- cout << "pigpiod daemon killed successfully" << endl;
- } else {
- // An error occurred while trying to kill the pigpiod daemon
- cerr << "Error killing pigpiod daemon. Return code: " << result << endl;
- }
+ // Successfully started the pigpiod daemon
+ cout << "pigpiod daemon started successfully" << endl;
@@ -94 +122,2 @@
- cout << "pigpiod daemon is not running" << endl;
+ // An error occurred while trying to start the pigpiod daemon
+ cerr << "Error starting pigpiod daemon." << endl;
@@ -95,0 +125,3 @@
+ } else {
+ cout << "pigpiod daemon is already running" << endl;
+ }
@@ -97,18 +128,0 @@
-
-void startPigpiod() {
- if (!isPigpiodRunning()) {
- cout << "pigpio daemon not running. attempting to start it." << endl;
- system("sudo systemctl start pigpiod");
- sleep(1);
-
- if (isPigpiodRunning()) {
- // Successfully started the pigpiod daemon
- cout << "pigpiod daemon started successfully" << endl;
- } else {
- // An error occurred while trying to start the pigpiod daemon
- cerr << "Error starting pigpiod daemon." << endl;
- }
- } else {
- cout << "pigpiod daemon is already running" << endl;
- }
-}
Code style divergence in file 'src/rpi_pwm_hardware_interface.cpp':
--- src/rpi_pwm_hardware_interface.cpp
+++ src/rpi_pwm_hardware_interface.cpp.uncrustify
@@ -30,2 +30 @@
- if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS)
- {
+ if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) {
@@ -51,2 +50,2 @@
- startPigpiod();
- }
+ startPigpiod();
+ }
@@ -55,2 +54,2 @@
- // pigpiod daemon is running
- return CallbackReturn::SUCCESS;
+ // pigpiod daemon is running
+ return CallbackReturn::SUCCESS;
@@ -58,2 +57,2 @@
- // pigpiod daemon is not running
- return CallbackReturn::ERROR;
+ // pigpiod daemon is not running
+ return CallbackReturn::ERROR;
@@ -74,3 +73,4 @@
- state_interfaces.emplace_back(hardware_interface::StateInterface(
- // TEST(anyone): insert correct interfaces
- rudder_joint_.name, hardware_interface::HW_IF_POSITION, &rudder_joint_.pos));
+ state_interfaces.emplace_back(
+ hardware_interface::StateInterface(
+ // TEST(anyone): insert correct interfaces
+ rudder_joint_.name, hardware_interface::HW_IF_POSITION, &rudder_joint_.pos));
@@ -84 +84,2 @@
- command_interfaces.emplace_back(hardware_interface::CommandInterface(
+ command_interfaces.emplace_back(
+ hardware_interface::CommandInterface(
@@ -98,3 +99,3 @@
- // TODO maybe make ros log error
- std::cerr << "Error initializing pigpio" << std::endl;
- return CallbackReturn::ERROR;
+ // TODO maybe make ros log error
+ std::cerr << "Error initializing pigpio" << std::endl;
+ return CallbackReturn::ERROR;
@@ -102 +103,5 @@
- rudder_joint_.servo = std::make_unique<AngularServo>(srv_cfg_.pi, srv_cfg_.pin, srv_cfg_.min_angle, srv_cfg_.max_angle, srv_cfg_.min_pulse_width_us, srv_cfg_.max_pulse_width_us);
+ rudder_joint_.servo = std::make_unique<AngularServo>(
+ srv_cfg_.pi, srv_cfg_.pin,
+ srv_cfg_.min_angle, srv_cfg_.max_angle,
+ srv_cfg_.min_pulse_width_us,
+ srv_cfg_.max_pulse_width_us);
Code style divergence in file 'test/test_rpi_pwm_hardware_interface.cpp':
--- test/test_rpi_pwm_hardware_interface.cpp
+++ test/test_rpi_pwm_hardware_interface.cpp.uncrustify
@@ -56 +56 @@
- ros2_control_test_assets::urdf_tail;
+ ros2_control_test_assets::urdf_tail;
5 files with code style divergence
No code style divergence in file 'include/rpi_pwm_hardware_interface/visibility_control.h'
-- run_test.py: return code 1
-- run_test.py: verify result file '/home/atticus/workspace/publish_ws/build/rpi_pwm_hardware_interface/test_results/rpi_pwm_hardware_interface/uncrustify.xunit.xml'
>>>
build/rpi_pwm_hardware_interface/test_results/rpi_pwm_hardware_interface/test_rpi_pwm_hardware_interface.gtest.xml: 1 test, 0 errors, 1 failure, 0 skipped
- rpi_pwm_hardware_interface.TestRPiPWMHardwareInterface load_rpi_pwm_hardware_interface_2dof
<<< failure message
/home/atticus/workspace/publish_ws/src/ros2_rpi_pwm_hardware_interface/test/test_rpi_pwm_hardware_interface.cpp:57
Expected: hardware_interface::ResourceManager rm(urdf) doesn't throw an exception.
Actual: it throws.
>>>
build/rpi_pwm_hardware_interface/test_results/rpi_pwm_hardware_interface/uncrustify.xunit.xml: 6 tests, 0 errors, 5 failures, 0 skipped
- rpi_pwm_hardware_interface.uncrustify include/rpi_pwm_hardware_interface/angular_servo.hpp
<<< failure message
Diff with 51 lines
>>>
- rpi_pwm_hardware_interface.uncrustify include/rpi_pwm_hardware_interface/rpi_pwm_hardware_interface.hpp
<<< failure message
Diff with 38 lines
>>>
- rpi_pwm_hardware_interface.uncrustify src/angular_servo.cpp
<<< failure message
Diff with 195 lines
>>>
- rpi_pwm_hardware_interface.uncrustify src/rpi_pwm_hardware_interface.cpp
<<< failure message
Diff with 47 lines
>>>
- rpi_pwm_hardware_interface.uncrustify test/test_rpi_pwm_hardware_interface.cpp
<<< failure message
Diff with 5 lines
>>>
Summary: 21 tests, 0 errors, 8 failures, 0 skipped