diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 00000000..30945be8 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,20 @@ +# See https://pre-commit.com for more information +# See https://pre-commit.com/hooks.html for more hooks +repos: +- repo: https://github.com/pre-commit/pre-commit-hooks + rev: v3.2.0 + hooks: + - id: check-yaml + - id: check-added-large-files +- repo: https://github.com/psf/black + rev: 22.10.0 + hooks: + - id: black +- repo: local + hooks: + - id: clang-format + name: clang-format + entry: bash -c 'FILES=`find -type f -regex ".*\.\(cpp\|hpp\|h\|c\)$"`; clang-format-14 --Werror $FILES -style=llvm -i' + language: system + types: [c] + pass_filenames: false \ No newline at end of file diff --git a/mirte_control/ros_control_boilerplate/rrbot_control/include/rrbot_control/rrbot_hw_interface.h b/mirte_control/ros_control_boilerplate/rrbot_control/include/rrbot_control/rrbot_hw_interface.h index 54bd8c16..b85fd231 100644 --- a/mirte_control/ros_control_boilerplate/rrbot_control/include/rrbot_control/rrbot_hw_interface.h +++ b/mirte_control/ros_control_boilerplate/rrbot_control/include/rrbot_control/rrbot_hw_interface.h @@ -40,11 +40,11 @@ #ifndef RRBOT_CONTROL__RRBOT_HW_INTERFACE_H #define RRBOT_CONTROL__RRBOT_HW_INTERFACE_H -#include #include #include #include #include +#include #include namespace rrbot_control { diff --git a/mirte_control/ros_control_boilerplate/rrbot_control/src/rrbot_hw_interface.cpp b/mirte_control/ros_control_boilerplate/rrbot_control/src/rrbot_hw_interface.cpp index ddfa37f3..de13e5f8 100644 --- a/mirte_control/ros_control_boilerplate/rrbot_control/src/rrbot_hw_interface.cpp +++ b/mirte_control/ros_control_boilerplate/rrbot_control/src/rrbot_hw_interface.cpp @@ -38,11 +38,11 @@ */ #include "ros/ros.h" +#include #include #include #include #include -#include namespace rrbot_control { @@ -104,23 +104,23 @@ RRBotHWInterface::RRBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model) void RRBotHWInterface::connectServices() { ROS_INFO_NAMED("rrbot_hw_interface", "Connecting to the services..."); - + ros::service::waitForService("/mirte/set_servoRot_servo_angle", -1); ros::service::waitForService("/mirte/set_servoShoulder_servo_angle", -1); ros::service::waitForService("/mirte/set_servoElbow_servo_angle", -1); ros::service::waitForService("/mirte/set_servoWrist_servo_angle", -1); { // Only mutex when actually writing to class vars. const std::lock_guard lock(this->service_clients_mutex); - client0 = nh_.serviceClient( - "/mirte/set_servoRot_servo_angle", true); - client1 = nh_.serviceClient( - "/mirte/set_servoShoulder_servo_angle", true); - client2 = nh_.serviceClient( - "/mirte/set_servoElbow_servo_angle", true); - client3 = nh_.serviceClient( - "/mirte/set_servoWrist_servo_angle", true); + client0 = nh_.serviceClient( + "/mirte/set_servoRot_servo_angle", true); + client1 = nh_.serviceClient( + "/mirte/set_servoShoulder_servo_angle", true); + client2 = nh_.serviceClient( + "/mirte/set_servoElbow_servo_angle", true); + client3 = nh_.serviceClient( + "/mirte/set_servoWrist_servo_angle", true); } - ROS_INFO_NAMED("rrbot_hw_interface", "Connected to the services"); + ROS_INFO_NAMED("rrbot_hw_interface", "Connected to the services"); } void RRBotHWInterface::read(ros::Duration &elapsed_time) { diff --git a/mirte_telemetrix/scripts/ROS_telemetrix_aio_api.py b/mirte_telemetrix/scripts/ROS_telemetrix_aio_api.py index 2d1bc5ae..5379d3ca 100755 --- a/mirte_telemetrix/scripts/ROS_telemetrix_aio_api.py +++ b/mirte_telemetrix/scripts/ROS_telemetrix_aio_api.py @@ -296,7 +296,7 @@ async def receive_data(self, data): self.range.min_range = 0.02 self.range.max_range = 1.5 self.range.header = self.get_header() - self.range.range = data[2] / 100.0 # convert from cm to m + self.range.range = data[2] / 100.0 # convert from cm to m self.pub.publish(self.range) def publish_data(self, event=None): diff --git a/mirte_telemetrix/scripts/modules/MPU9250.py b/mirte_telemetrix/scripts/modules/MPU9250.py index 420f7f8a..e6ff29c1 100644 --- a/mirte_telemetrix/scripts/modules/MPU9250.py +++ b/mirte_telemetrix/scripts/modules/MPU9250.py @@ -62,9 +62,10 @@ def pub(self): y_index = 0 z_index = 2 lin_acc = Vector3( - x=self.acceleration[x_index] * 9.81, #positive forward, Imu is positioned differently - y=-self.acceleration[y_index] * 9.81, #positive left - z=-self.acceleration[z_index] * 9.81, # up is positive + x=self.acceleration[x_index] + * 9.81, # positive forward, Imu is positioned differently + y=-self.acceleration[y_index] * 9.81, # positive left + z=-self.acceleration[z_index] * 9.81, # up is positive ) # this is probably okay. Only real usefull value is z. @@ -74,7 +75,9 @@ def pub(self): z=self.gyroscope[z_index] * math.pi / 180.0, ) orie = Quaternion( - x=self.magnetometer[x_index], y=self.magnetometer[y_index], z=self.magnetometer[z_index] + x=self.magnetometer[x_index], + y=self.magnetometer[y_index], + z=self.magnetometer[z_index], ) # lin_acc.x = self.last_message = Imu(