Skip to content

Commit

Permalink
add pre-commit
Browse files Browse the repository at this point in the history
  • Loading branch information
ArendJan committed May 15, 2024
1 parent c5edff2 commit a33c42a
Show file tree
Hide file tree
Showing 5 changed files with 40 additions and 17 deletions.
20 changes: 20 additions & 0 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
@@ -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

Check failure on line 4 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

4:4 [hyphens] too many spaces after hyphen

Check failure on line 4 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

4:1 [indentation] wrong indentation: expected at least 1
rev: v3.2.0
hooks:
- id: check-yaml

Check failure on line 7 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

7:8 [hyphens] too many spaces after hyphen

Check failure on line 7 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

7:5 [indentation] wrong indentation: expected at least 5
- id: check-added-large-files

Check failure on line 8 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

8:8 [hyphens] too many spaces after hyphen
- repo: https://github.com/psf/black

Check failure on line 9 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

9:4 [hyphens] too many spaces after hyphen
rev: 22.10.0
hooks:
- id: black

Check failure on line 12 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

12:8 [hyphens] too many spaces after hyphen

Check failure on line 12 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

12:5 [indentation] wrong indentation: expected at least 5
- repo: local
hooks:
- id: clang-format

Check failure on line 15 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

15:8 [hyphens] too many spaces after hyphen

Check failure on line 15 in .pre-commit-config.yaml

View workflow job for this annotation

GitHub Actions / yaml_style_check

15:3 [indentation] wrong indentation: expected at least 3
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
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@
#ifndef RRBOT_CONTROL__RRBOT_HW_INTERFACE_H
#define RRBOT_CONTROL__RRBOT_HW_INTERFACE_H

#include <ros_control_boilerplate/generic_hw_interface.h>
#include <boost/format.hpp>
#include <chrono>
#include <future>
#include <mutex>
#include <ros_control_boilerplate/generic_hw_interface.h>
#include <thread>

namespace rrbot_control {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@
*/

#include "ros/ros.h"
#include <chrono>
#include <iostream>
#include <mirte_msgs/ServoPosition.h>
#include <mirte_msgs/SetServoAngle.h>
#include <rrbot_control/rrbot_hw_interface.h>
#include <chrono>

namespace rrbot_control {

Expand Down Expand Up @@ -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<std::mutex> lock(this->service_clients_mutex);
client0 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoRot_servo_angle", true);
client1 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoShoulder_servo_angle", true);
client2 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoElbow_servo_angle", true);
client3 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoWrist_servo_angle", true);
client0 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoRot_servo_angle", true);
client1 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoShoulder_servo_angle", true);
client2 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoElbow_servo_angle", true);
client3 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/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) {
Expand Down
2 changes: 1 addition & 1 deletion mirte_telemetrix/scripts/ROS_telemetrix_aio_api.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
11 changes: 7 additions & 4 deletions mirte_telemetrix/scripts/modules/MPU9250.py
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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(
Expand Down

0 comments on commit a33c42a

Please sign in to comment.