37
37
#include < sys/ioctl.h>
38
38
#include < bits/stdc++.h>
39
39
40
- enum CanId : uint8_t {
40
+ enum CanId : uint8_t
41
+ {
41
42
IMU_LINEAR_CAN_ID = 0x09 ,
42
43
IMU_ANGULAR_CAN_ID,
43
44
IMU_ORIENTATION_CAN_ID,
@@ -65,11 +66,12 @@ enum CanId : uint8_t{
65
66
IMU_CALIBRATION_SEND_CAN_ID = 0x38 ,
66
67
};
67
68
68
- class CanAllNode : public rclcpp ::Node {
69
+ class CanAllNode : public rclcpp ::Node
70
+ {
69
71
public:
70
72
CanAllNode ()
71
- : Node(" can_all_node" )
72
- {
73
+ : Node(" can_all_node" )
74
+ {
73
75
std::vector<int64_t > calibration_params (22 , 0 );
74
76
declare_parameter (" calibration_params" , calibration_params);
75
77
std::string can_interface = " can0" ;
@@ -92,12 +94,12 @@ class CanAllNode: public rclcpp::Node {
92
94
capacitive_touch_raw_pub_ = this ->create_publisher <std_msgs::msg::Int16>(" capacitive/touch_raw" , 50 );
93
95
tof_touch_raw_pub_ = this ->create_publisher <std_msgs::msg::Int16>(" tof/touch_raw" , 50 );
94
96
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 );});
98
100
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));
101
103
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]
102
104
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]
103
105
can_socket_ = openCanSocket ();
@@ -108,7 +110,8 @@ class CanAllNode: public rclcpp::Node {
108
110
}
109
111
110
112
private:
111
- int openCanSocket () {
113
+ int openCanSocket ()
114
+ {
112
115
std::string can_interface = this ->get_parameter (" can_interface" ).as_string ();
113
116
int s = socket (PF_CAN, SOCK_RAW, CAN_RAW);
114
117
if (s < 0 ) {
@@ -126,10 +129,11 @@ class CanAllNode: public rclcpp::Node {
126
129
close (s);
127
130
return -1 ;
128
131
}
129
- return s;
132
+ return s;
130
133
}
131
134
132
- void writeImuCalibration () {
135
+ void writeImuCalibration ()
136
+ {
133
137
std::vector<int64_t > calibration_params = get_parameter (" calibration_params" ).as_integer_array ();
134
138
struct can_frame frame;
135
139
std::memset (&frame, 0 , sizeof (struct can_frame ));
@@ -165,9 +169,10 @@ class CanAllNode: public rclcpp::Node {
165
169
nbytes = write (can_socket_, &frame, sizeof (struct can_frame ));
166
170
}
167
171
168
- void timerPubCallback () {
172
+ void timerPubCallback ()
173
+ {
169
174
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 ));
171
176
if (nbytes > 0 ) {
172
177
if (frame.can_id >= CanId::TEMPERATURE_1_CAN_ID && frame.can_id <= CanId::TEMPERATURE_5_CAN_ID) {
173
178
publishTemperatureData (frame);
@@ -179,18 +184,20 @@ class CanAllNode: public rclcpp::Node {
179
184
readImuCalibration (frame);
180
185
} else if (frame.can_id == CanId::TACT_CAN_ID) {
181
186
publishTactData (frame);
182
- } else if (frame.can_id == CanId::TOUCH_CAN_ID){
187
+ } else if (frame.can_id == CanId::TOUCH_CAN_ID) {
183
188
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) {
185
190
publishImuData (frame);
186
- } else if (frame.can_id == CanId::SERVO_POS_CAN_ID){
191
+ } else if (frame.can_id == CanId::SERVO_POS_CAN_ID) {
187
192
publishServoPosData (frame);
188
193
}
189
194
}
190
195
}
191
196
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
+ {
194
201
struct can_frame frame;
195
202
std::memset (&frame, 0 , sizeof (struct can_frame ));
196
203
frame.can_id = CanId::IMU_CALIBRATION_SEND_CAN_ID;
@@ -208,7 +215,8 @@ class CanAllNode: public rclcpp::Node {
208
215
}
209
216
}
210
217
211
- void readImuCalibration (const struct can_frame &frame) {
218
+ void readImuCalibration (const struct can_frame & frame)
219
+ {
212
220
static std::vector<int32_t > calibration_data (22 );
213
221
static bool imu_calibration_data_1 = false ;
214
222
static bool imu_calibration_data_2 = false ;
@@ -246,7 +254,8 @@ class CanAllNode: public rclcpp::Node {
246
254
}
247
255
248
256
249
- void publishImuData (const struct can_frame &frame) {
257
+ void publishImuData (const struct can_frame & frame)
258
+ {
250
259
static bool linear_data = false ;
251
260
static bool angular_data = false ;
252
261
if (frame.can_id == CanId::IMU_LINEAR_CAN_ID) {
@@ -302,7 +311,8 @@ class CanAllNode: public rclcpp::Node {
302
311
}
303
312
}
304
313
305
- void publishWifiData (const struct can_frame &frame) {
314
+ void publishWifiData (const struct can_frame & frame)
315
+ {
306
316
static std::array<uint8_t , 6 > mac_address{};
307
317
static std::string ssid;
308
318
static int8_t channel = 0 ;
@@ -328,8 +338,7 @@ class CanAllNode: public rclcpp::Node {
328
338
channel_data = true ;
329
339
rssi = frame.data [7 ];
330
340
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) {
333
342
for (int i = 0 ; i < frame.can_dlc ; ++i) {
334
343
if (frame.data [i] != ' \0 ' ) {
335
344
ssid += static_cast <char >(frame.data [i]);
@@ -368,7 +377,8 @@ class CanAllNode: public rclcpp::Node {
368
377
}
369
378
}
370
379
371
- void publishBmeData (const struct can_frame &frame) {
380
+ void publishBmeData (const struct can_frame & frame)
381
+ {
372
382
if (frame.can_id == CanId::BME_CAN_ID) {
373
383
if (frame.can_dlc >= 8 ) {
374
384
int16_t temperature_raw = ((uint16_t )(frame.data [1 ] << 8 ) | ((uint16_t )frame.data [0 ]));
@@ -388,7 +398,8 @@ class CanAllNode: public rclcpp::Node {
388
398
}
389
399
}
390
400
391
- void publishTouchData (const struct can_frame &frame) {
401
+ void publishTouchData (const struct can_frame & frame)
402
+ {
392
403
if (frame.can_id == CanId::TOUCH_CAN_ID && frame.can_dlc >= 4 ) {
393
404
int16_t capacitive_touch = frame.data [3 ];
394
405
std_msgs::msg::Int16 capacitive_touch_msg;
@@ -404,7 +415,7 @@ class CanAllNode: public rclcpp::Node {
404
415
tof_touch_raw_pub_->publish (tof_raw_msg);
405
416
int16_t tof_touch = 0 ;
406
417
int16_t touch = frame.data [3 ];
407
- if (touch == 0 ){
418
+ if (touch == 0 ) {
408
419
if (tof_touch_raw >= 16 && tof_touch_raw <= 25 ) {
409
420
touch = 1 ;
410
421
} else {
@@ -415,38 +426,40 @@ class CanAllNode: public rclcpp::Node {
415
426
tof_touch = 1 ;
416
427
} else {
417
428
tof_touch = 0 ;
418
- }
429
+ }
419
430
std_msgs::msg::Int16 tof_touch_msg;
420
431
tof_touch_msg.data = tof_touch;
421
- tof_touch_pub_->publish (tof_touch_msg);
432
+ tof_touch_pub_->publish (tof_touch_msg);
422
433
std_msgs::msg::Int16 touch_msg;
423
434
touch_msg.data = touch;
424
435
touch_pub_->publish (touch_msg);
425
436
}
426
437
}
427
438
428
- void publishTactData (const struct can_frame &frame) {
439
+ void publishTactData (const struct can_frame & frame)
440
+ {
429
441
if (frame.can_id == CanId::TACT_CAN_ID && frame.can_dlc >= 1 ) {
430
442
std_msgs::msg::Int8 tact_msg;
431
443
uint8_t tact_data = 0 ;
432
- if (frame.data [0 ] == 1 ){
444
+ if (frame.data [0 ] == 1 ) {
433
445
tact_data = 8 ;
434
446
}
435
- if (frame.data [0 ] == 2 ){
447
+ if (frame.data [0 ] == 2 ) {
436
448
tact_data = 4 ;
437
449
}
438
- if (frame.data [0 ] == 4 ){
450
+ if (frame.data [0 ] == 4 ) {
439
451
tact_data = 1 ;
440
452
}
441
- if (frame.data [0 ] == 8 ){
453
+ if (frame.data [0 ] == 8 ) {
442
454
tact_data = 2 ;
443
455
}
444
456
tact_msg.data = tact_data;
445
457
tact_pub_->publish (tact_msg);
446
458
}
447
459
}
448
460
449
- void publishServoPosData (const struct can_frame &frame) {
461
+ void publishServoPosData (const struct can_frame & frame)
462
+ {
450
463
if (frame.can_id == CanId::SERVO_POS_CAN_ID && frame.can_dlc >= 2 ) {
451
464
int16_t servo_pos_raw = (((uint16_t )frame.data [1 ]) << 8 ) | ((uint16_t )frame.data [0 ]);
452
465
// The servo target angle (servo_target_deg) is determined by multiplying 2048
@@ -458,7 +471,8 @@ class CanAllNode: public rclcpp::Node {
458
471
}
459
472
}
460
473
461
- void publishTemperatureData (const struct can_frame &frame) {
474
+ void publishTemperatureData (const struct can_frame & frame)
475
+ {
462
476
int16_t temperature_raw = (((uint16_t )frame.data [1 ]) << 8 ) | ((uint16_t )frame.data [0 ]);
463
477
float temperature = temperature_raw * 0.0625 ;
464
478
sensor_msgs::msg::Temperature msg;
@@ -485,7 +499,8 @@ class CanAllNode: public rclcpp::Node {
485
499
}
486
500
}
487
501
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
+ {
489
504
uint8_t vibrator1 = 0 ;
490
505
uint8_t vibrator3 = 0 ;
491
506
uint8_t vibrator4 = 0 ;
@@ -508,7 +523,8 @@ class CanAllNode: public rclcpp::Node {
508
523
}
509
524
}
510
525
511
- void subscribeServoTargetData (const std_msgs::msg::Int16& msg) {
526
+ void subscribeServoTargetData (const std_msgs::msg::Int16 & msg)
527
+ {
512
528
int16_t servo_target_per = -1 * msg.data ;
513
529
// The servo target angle (servo_target_deg) is determined by multiplying 2048
514
530
// by the servo angle (ranging from -179 to +179,0 ~ 4096)
@@ -527,7 +543,8 @@ class CanAllNode: public rclcpp::Node {
527
543
}
528
544
}
529
545
530
- void subServoFree (const std_msgs::msg::Bool::SharedPtr msg) {
546
+ void subServoFree (const std_msgs::msg::Bool::SharedPtr msg)
547
+ {
531
548
uint8_t servo_free = msg->data ? 0x00 : 0x01 ;
532
549
struct can_frame frame;
533
550
std::memset (&frame, 0 , sizeof (struct can_frame ));
@@ -551,7 +568,7 @@ class CanAllNode: public rclcpp::Node {
551
568
rclcpp::Publisher<sensor_msgs::msg::Temperature>::SharedPtr BME_temperature_pub_;
552
569
rclcpp::Publisher<sensor_msgs::msg::FluidPressure>::SharedPtr BME_pressure_pub_;
553
570
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_;
555
572
rclcpp::Publisher<std_msgs::msg::Int8>::SharedPtr tact_pub_;
556
573
rclcpp::Publisher<std_msgs::msg::Int16>::SharedPtr capacitive_touch_pub_;
557
574
rclcpp::Publisher<std_msgs::msg::Int16>::SharedPtr capacitive_touch_raw_pub_;
@@ -570,9 +587,10 @@ class CanAllNode: public rclcpp::Node {
570
587
std::vector<double > imu_gyro_bias_;
571
588
};
572
589
573
- int main (int argc, char *argv[]) {
590
+ int main (int argc, char * argv[])
591
+ {
574
592
rclcpp::init (argc, argv);
575
593
rclcpp::spin (std::make_shared<CanAllNode>());
576
594
rclcpp::shutdown ();
577
595
return 0 ;
578
- }
596
+ }
0 commit comments