Skip to content

Commit c8ec2f0

Browse files
committed
fix lint error
Signed-off-by: Daisuke Sato <[email protected]>
1 parent 3bb9d7c commit c8ec2f0

File tree

12 files changed

+351
-305
lines changed

12 files changed

+351
-305
lines changed

cabot_base/launch/cabot3.launch.py

+8-8
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,7 @@ def generate_launch_description():
129129
odrive_can_pkg_dir,
130130
PythonExpression(['"json"']),
131131
odrive_firmware_version,
132-
PythonExpression(['"flat_endpoints_',odrive_model,'.json"'])
132+
PythonExpression(['"flat_endpoints_', odrive_model, '.json"'])
133133
])
134134

135135
# deprecated parameters
@@ -521,7 +521,7 @@ def generate_launch_description():
521521
output='screen',
522522
parameters=[
523523
{
524-
'is_clockwise' : True,
524+
'is_clockwise': True,
525525
}
526526
],
527527
remappings=[
@@ -544,9 +544,9 @@ def generate_launch_description():
544544
output='screen',
545545
parameters=[
546546
{
547-
'node_id' : 0,
548-
'interface' : 'can1',
549-
'axis_idle_on_shutdown' : True,
547+
'node_id': 0,
548+
'interface': 'can1',
549+
'axis_idle_on_shutdown': True,
550550
'json_file_path': flat_endpoints_json_path,
551551
}
552552
],
@@ -565,9 +565,9 @@ def generate_launch_description():
565565
output='screen',
566566
parameters=[
567567
{
568-
'node_id' : 1,
569-
'interface' : 'can1',
570-
'axis_idle_on_shutdown' : True,
568+
'node_id': 1,
569+
'interface': 'can1',
570+
'axis_idle_on_shutdown': True,
571571
'json_file_path': flat_endpoints_json_path,
572572
}
573573
],

cabot_can/src/can_all_node.cpp

+60-42
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,8 @@
3737
#include <sys/ioctl.h>
3838
#include <bits/stdc++.h>
3939

40-
enum CanId : uint8_t{
40+
enum CanId : uint8_t
41+
{
4142
IMU_LINEAR_CAN_ID = 0x09,
4243
IMU_ANGULAR_CAN_ID,
4344
IMU_ORIENTATION_CAN_ID,
@@ -65,11 +66,12 @@ enum CanId : uint8_t{
6566
IMU_CALIBRATION_SEND_CAN_ID = 0x38,
6667
};
6768

68-
class CanAllNode: public rclcpp::Node {
69+
class CanAllNode : public rclcpp::Node
70+
{
6971
public:
7072
CanAllNode()
71-
: Node("can_all_node")
72-
{
73+
: Node("can_all_node")
74+
{
7375
std::vector<int64_t> calibration_params(22, 0);
7476
declare_parameter("calibration_params", calibration_params);
7577
std::string can_interface = "can0";
@@ -92,12 +94,12 @@ class CanAllNode: public rclcpp::Node {
9294
capacitive_touch_raw_pub_ = this->create_publisher<std_msgs::msg::Int16>("capacitive/touch_raw", 50);
9395
tof_touch_raw_pub_ = this->create_publisher<std_msgs::msg::Int16>("tof/touch_raw", 50);
9496
servo_pos_pub_ = this->create_publisher<std_msgs::msg::Int16>("servo_pos", 50);
95-
vibrator_1_sub_ = this->create_subscription<std_msgs::msg::UInt8>("vibrator1", 10,[this](const std_msgs::msg::UInt8::SharedPtr msg) {this->subscribeVibratorData(msg, 1);});
96-
vibrator_3_sub_ = this->create_subscription<std_msgs::msg::UInt8>("vibrator3", 10,[this](const std_msgs::msg::UInt8::SharedPtr msg) {this->subscribeVibratorData(msg, 3);});
97-
vibrator_4_sub_ = this->create_subscription<std_msgs::msg::UInt8>("vibrator4", 10,[this](const std_msgs::msg::UInt8::SharedPtr msg) {this->subscribeVibratorData(msg, 4);});
97+
vibrator_1_sub_ = this->create_subscription<std_msgs::msg::UInt8>("vibrator1", 10, [this](const std_msgs::msg::UInt8::SharedPtr msg) {this->subscribeVibratorData(msg, 1);});
98+
vibrator_3_sub_ = this->create_subscription<std_msgs::msg::UInt8>("vibrator3", 10, [this](const std_msgs::msg::UInt8::SharedPtr msg) {this->subscribeVibratorData(msg, 3);});
99+
vibrator_4_sub_ = this->create_subscription<std_msgs::msg::UInt8>("vibrator4", 10, [this](const std_msgs::msg::UInt8::SharedPtr msg) {this->subscribeVibratorData(msg, 4);});
98100
servo_target_sub_ = this->create_subscription<std_msgs::msg::Int16>("servo_target", 10, std::bind(&CanAllNode::subscribeServoTargetData, this, std::placeholders::_1));
99-
servo_free_sub_ = this->create_subscription<std_msgs::msg::Bool>("servo_free",10,std::bind(&CanAllNode::subServoFree, this, std::placeholders::_1));
100-
imu_calibration_srv_ = this->create_service<std_srvs::srv::Trigger>("run_imu_calibration",std::bind(&CanAllNode::readImuServiceCalibration, this, std::placeholders::_1, std::placeholders::_2));
101+
servo_free_sub_ = this->create_subscription<std_msgs::msg::Bool>("servo_free", 10, std::bind(&CanAllNode::subServoFree, this, std::placeholders::_1));
102+
imu_calibration_srv_ = this->create_service<std_srvs::srv::Trigger>("run_imu_calibration", std::bind(&CanAllNode::readImuServiceCalibration, this, std::placeholders::_1, std::placeholders::_2));
101103
imu_accel_bias_ = this->declare_parameter("imu_accel_bias", std::vector<double>(3, 0.0)); // parameters for adjusting linear acceleration. default value = [0,0, 0.0, 0.0]
102104
imu_gyro_bias_ = this->declare_parameter("imu_gyro_bias", std::vector<double>(3, 0.0)); // parameters for adjusting angular velocity. default value = [0,0, 0.0, 0.0]
103105
can_socket_ = openCanSocket();
@@ -108,7 +110,8 @@ class CanAllNode: public rclcpp::Node {
108110
}
109111

110112
private:
111-
int openCanSocket() {
113+
int openCanSocket()
114+
{
112115
std::string can_interface = this->get_parameter("can_interface").as_string();
113116
int s = socket(PF_CAN, SOCK_RAW, CAN_RAW);
114117
if (s < 0) {
@@ -126,10 +129,11 @@ class CanAllNode: public rclcpp::Node {
126129
close(s);
127130
return -1;
128131
}
129-
return s;
132+
return s;
130133
}
131134

132-
void writeImuCalibration() {
135+
void writeImuCalibration()
136+
{
133137
std::vector<int64_t> calibration_params = get_parameter("calibration_params").as_integer_array();
134138
struct can_frame frame;
135139
std::memset(&frame, 0, sizeof(struct can_frame));
@@ -165,9 +169,10 @@ class CanAllNode: public rclcpp::Node {
165169
nbytes = write(can_socket_, &frame, sizeof(struct can_frame));
166170
}
167171

168-
void timerPubCallback() {
172+
void timerPubCallback()
173+
{
169174
struct can_frame frame;
170-
int nbytes = read(can_socket_ , &frame, sizeof(struct can_frame));
175+
int nbytes = read(can_socket_, &frame, sizeof(struct can_frame));
171176
if (nbytes > 0) {
172177
if (frame.can_id >= CanId::TEMPERATURE_1_CAN_ID && frame.can_id <= CanId::TEMPERATURE_5_CAN_ID) {
173178
publishTemperatureData(frame);
@@ -179,18 +184,20 @@ class CanAllNode: public rclcpp::Node {
179184
readImuCalibration(frame);
180185
} else if (frame.can_id == CanId::TACT_CAN_ID) {
181186
publishTactData(frame);
182-
} else if (frame.can_id == CanId::TOUCH_CAN_ID){
187+
} else if (frame.can_id == CanId::TOUCH_CAN_ID) {
183188
publishTouchData(frame);
184-
} else if (frame.can_id >= CanId::IMU_LINEAR_CAN_ID && frame.can_id <= CanId::IMU_ORIENTATION_CAN_ID){
189+
} else if (frame.can_id >= CanId::IMU_LINEAR_CAN_ID && frame.can_id <= CanId::IMU_ORIENTATION_CAN_ID) {
185190
publishImuData(frame);
186-
} else if (frame.can_id == CanId::SERVO_POS_CAN_ID){
191+
} else if (frame.can_id == CanId::SERVO_POS_CAN_ID) {
187192
publishServoPosData(frame);
188193
}
189194
}
190195
}
191196

192-
void readImuServiceCalibration(const std::shared_ptr<std_srvs::srv::Trigger::Request> /*request*/,
193-
std::shared_ptr<std_srvs::srv::Trigger::Response> response) {
197+
void readImuServiceCalibration(
198+
const std::shared_ptr<std_srvs::srv::Trigger::Request>/*request*/,
199+
std::shared_ptr<std_srvs::srv::Trigger::Response> response)
200+
{
194201
struct can_frame frame;
195202
std::memset(&frame, 0, sizeof(struct can_frame));
196203
frame.can_id = CanId::IMU_CALIBRATION_SEND_CAN_ID;
@@ -208,7 +215,8 @@ class CanAllNode: public rclcpp::Node {
208215
}
209216
}
210217

211-
void readImuCalibration(const struct can_frame &frame) {
218+
void readImuCalibration(const struct can_frame & frame)
219+
{
212220
static std::vector<int32_t> calibration_data(22);
213221
static bool imu_calibration_data_1 = false;
214222
static bool imu_calibration_data_2 = false;
@@ -246,7 +254,8 @@ class CanAllNode: public rclcpp::Node {
246254
}
247255

248256

249-
void publishImuData(const struct can_frame &frame) {
257+
void publishImuData(const struct can_frame & frame)
258+
{
250259
static bool linear_data = false;
251260
static bool angular_data = false;
252261
if (frame.can_id == CanId::IMU_LINEAR_CAN_ID) {
@@ -302,7 +311,8 @@ class CanAllNode: public rclcpp::Node {
302311
}
303312
}
304313

305-
void publishWifiData(const struct can_frame &frame) {
314+
void publishWifiData(const struct can_frame & frame)
315+
{
306316
static std::array<uint8_t, 6> mac_address{};
307317
static std::string ssid;
308318
static int8_t channel = 0;
@@ -328,8 +338,7 @@ class CanAllNode: public rclcpp::Node {
328338
channel_data = true;
329339
rssi = frame.data[7];
330340
rssi_data = true;
331-
}
332-
else if (frame.can_id >= CanId::WIFI_CAN_ID_START && frame.can_id <= CanId::WIFI_SSID_CAN_ID_END) {
341+
} else if (frame.can_id >= CanId::WIFI_CAN_ID_START && frame.can_id <= CanId::WIFI_SSID_CAN_ID_END) {
333342
for (int i = 0; i < frame.can_dlc; ++i) {
334343
if (frame.data[i] != '\0') {
335344
ssid += static_cast<char>(frame.data[i]);
@@ -368,7 +377,8 @@ class CanAllNode: public rclcpp::Node {
368377
}
369378
}
370379

371-
void publishBmeData(const struct can_frame &frame) {
380+
void publishBmeData(const struct can_frame & frame)
381+
{
372382
if (frame.can_id == CanId::BME_CAN_ID) {
373383
if (frame.can_dlc >= 8) {
374384
int16_t temperature_raw = ((uint16_t)(frame.data[1] << 8) | ((uint16_t)frame.data[0]));
@@ -388,7 +398,8 @@ class CanAllNode: public rclcpp::Node {
388398
}
389399
}
390400

391-
void publishTouchData(const struct can_frame &frame) {
401+
void publishTouchData(const struct can_frame & frame)
402+
{
392403
if (frame.can_id == CanId::TOUCH_CAN_ID && frame.can_dlc >= 4) {
393404
int16_t capacitive_touch = frame.data[3];
394405
std_msgs::msg::Int16 capacitive_touch_msg;
@@ -404,7 +415,7 @@ class CanAllNode: public rclcpp::Node {
404415
tof_touch_raw_pub_->publish(tof_raw_msg);
405416
int16_t tof_touch = 0;
406417
int16_t touch = frame.data[3];
407-
if (touch == 0){
418+
if (touch == 0) {
408419
if (tof_touch_raw >= 16 && tof_touch_raw <= 25) {
409420
touch = 1;
410421
} else {
@@ -415,38 +426,40 @@ class CanAllNode: public rclcpp::Node {
415426
tof_touch = 1;
416427
} else {
417428
tof_touch = 0;
418-
}
429+
}
419430
std_msgs::msg::Int16 tof_touch_msg;
420431
tof_touch_msg.data = tof_touch;
421-
tof_touch_pub_->publish(tof_touch_msg);
432+
tof_touch_pub_->publish(tof_touch_msg);
422433
std_msgs::msg::Int16 touch_msg;
423434
touch_msg.data = touch;
424435
touch_pub_->publish(touch_msg);
425436
}
426437
}
427438

428-
void publishTactData(const struct can_frame &frame) {
439+
void publishTactData(const struct can_frame & frame)
440+
{
429441
if (frame.can_id == CanId::TACT_CAN_ID && frame.can_dlc >= 1) {
430442
std_msgs::msg::Int8 tact_msg;
431443
uint8_t tact_data = 0;
432-
if (frame.data[0] == 1){
444+
if (frame.data[0] == 1) {
433445
tact_data = 8;
434446
}
435-
if (frame.data[0] == 2){
447+
if (frame.data[0] == 2) {
436448
tact_data = 4;
437449
}
438-
if (frame.data[0] == 4){
450+
if (frame.data[0] == 4) {
439451
tact_data = 1;
440452
}
441-
if (frame.data[0] == 8){
453+
if (frame.data[0] == 8) {
442454
tact_data = 2;
443455
}
444456
tact_msg.data = tact_data;
445457
tact_pub_->publish(tact_msg);
446458
}
447459
}
448460

449-
void publishServoPosData(const struct can_frame &frame) {
461+
void publishServoPosData(const struct can_frame & frame)
462+
{
450463
if (frame.can_id == CanId::SERVO_POS_CAN_ID && frame.can_dlc >= 2) {
451464
int16_t servo_pos_raw = (((uint16_t)frame.data[1]) << 8) | ((uint16_t)frame.data[0]);
452465
//The servo target angle (servo_target_deg) is determined by multiplying 2048
@@ -458,7 +471,8 @@ class CanAllNode: public rclcpp::Node {
458471
}
459472
}
460473

461-
void publishTemperatureData(const struct can_frame &frame) {
474+
void publishTemperatureData(const struct can_frame & frame)
475+
{
462476
int16_t temperature_raw = (((uint16_t)frame.data[1]) << 8) | ((uint16_t)frame.data[0]);
463477
float temperature = temperature_raw * 0.0625;
464478
sensor_msgs::msg::Temperature msg;
@@ -485,7 +499,8 @@ class CanAllNode: public rclcpp::Node {
485499
}
486500
}
487501

488-
void subscribeVibratorData(const std_msgs::msg::UInt8::SharedPtr msg, int vibrator_id) {
502+
void subscribeVibratorData(const std_msgs::msg::UInt8::SharedPtr msg, int vibrator_id)
503+
{
489504
uint8_t vibrator1 = 0;
490505
uint8_t vibrator3 = 0;
491506
uint8_t vibrator4 = 0;
@@ -508,7 +523,8 @@ class CanAllNode: public rclcpp::Node {
508523
}
509524
}
510525

511-
void subscribeServoTargetData(const std_msgs::msg::Int16& msg) {
526+
void subscribeServoTargetData(const std_msgs::msg::Int16 & msg)
527+
{
512528
int16_t servo_target_per = -1 * msg.data;
513529
//The servo target angle (servo_target_deg) is determined by multiplying 2048
514530
//by the servo angle (ranging from -179 to +179,0 ~ 4096)
@@ -527,7 +543,8 @@ class CanAllNode: public rclcpp::Node {
527543
}
528544
}
529545

530-
void subServoFree(const std_msgs::msg::Bool::SharedPtr msg) {
546+
void subServoFree(const std_msgs::msg::Bool::SharedPtr msg)
547+
{
531548
uint8_t servo_free = msg->data ? 0x00 : 0x01;
532549
struct can_frame frame;
533550
std::memset(&frame, 0, sizeof(struct can_frame));
@@ -551,7 +568,7 @@ class CanAllNode: public rclcpp::Node {
551568
rclcpp::Publisher<sensor_msgs::msg::Temperature>::SharedPtr BME_temperature_pub_;
552569
rclcpp::Publisher<sensor_msgs::msg::FluidPressure>::SharedPtr BME_pressure_pub_;
553570
rclcpp::Publisher<sensor_msgs::msg::FluidPressure>::SharedPtr pressure_pub_;
554-
rclcpp::Publisher< std_msgs::msg::Int32MultiArray>::SharedPtr calibration_pub_;
571+
rclcpp::Publisher<std_msgs::msg::Int32MultiArray>::SharedPtr calibration_pub_;
555572
rclcpp::Publisher<std_msgs::msg::Int8>::SharedPtr tact_pub_;
556573
rclcpp::Publisher<std_msgs::msg::Int16>::SharedPtr capacitive_touch_pub_;
557574
rclcpp::Publisher<std_msgs::msg::Int16>::SharedPtr capacitive_touch_raw_pub_;
@@ -570,9 +587,10 @@ class CanAllNode: public rclcpp::Node {
570587
std::vector<double> imu_gyro_bias_;
571588
};
572589

573-
int main(int argc, char *argv[]) {
590+
int main(int argc, char * argv[])
591+
{
574592
rclcpp::init(argc, argv);
575593
rclcpp::spin(std::make_shared<CanAllNode>());
576594
rclcpp::shutdown();
577595
return 0;
578-
}
596+
}

motor_controller/odriver_can/CMakeLists.txt

+14-4
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,20 @@ endforeach()
2020
install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch/)
2121

2222
if(BUILD_TESTING)
23-
find_package(ament_lint_auto REQUIRED)
24-
set(ament_cmake_copyright_FOUND TRUE)
25-
set(ament_cmake_cpplint_FOUND TRUE)
26-
ament_lint_auto_find_test_dependencies()
23+
find_package(ament_cmake_copyright REQUIRED)
24+
find_package(ament_cmake_cpplint REQUIRED)
25+
find_package(ament_cmake_flake8 REQUIRED)
26+
find_package(ament_cmake_lint_cmake REQUIRED)
27+
find_package(ament_cmake_uncrustify REQUIRED)
28+
find_package(ament_cmake_xmllint REQUIRED)
29+
30+
set(MAX_LINE_LENGTH 200)
31+
ament_copyright()
32+
ament_cpplint(MAX_LINE_LENGTH ${MAX_LINE_LENGTH})
33+
ament_flake8(MAX_LINE_LENGTH ${MAX_LINE_LENGTH})
34+
ament_lint_cmake()
35+
ament_uncrustify(MAX_LINE_LENGTH ${MAX_LINE_LENGTH})
36+
ament_xmllint()
2737
endif()
2838

2939
ament_package()

motor_controller/odriver_can/launch/odriver_can.launch.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,9 @@
2424

2525
from launch import LaunchDescription
2626
from launch_ros.actions import Node
27-
from launch.substitutions import LaunchConfiguration
2827
from launch.actions import SetEnvironmentVariable
2928

29+
3030
def generate_launch_description():
3131
return LaunchDescription([
3232
SetEnvironmentVariable('ROS_LOG_DIR', launch_config.log_dir),

0 commit comments

Comments
 (0)