@@ -73,8 +73,6 @@ void Driver::processMessage(const can_msgs::msg::Frame::SharedPtr received_msg)
73
73
// If there's no data then this is a request message, jump out.
74
74
if (received_msg->dlc == 0 ) return ;
75
75
76
- RCLCPP_INFO (rclcpp::get_logger (" rclcpp" ), " processMessage: received message!" );
77
-
78
76
Field* field = nullptr ;
79
77
uint32_t received_api = getApi (*received_msg);
80
78
if ((received_api & CAN_MSGID_API_M & CAN_API_MC_CFG) == CAN_API_MC_CFG)
@@ -263,7 +261,6 @@ void Driver::verifyParams()
263
261
}
264
262
else
265
263
{
266
- // interface_->queue(Message(LM_API_STATUS_POWER | device_number_));
267
264
sendId (LM_API_STATUS_POWER | device_number_);
268
265
}
269
266
break ;
@@ -276,7 +273,6 @@ void Driver::verifyParams()
276
273
}
277
274
else
278
275
{
279
- // interface_->queue(Message(LM_API_POS_REF | device_number_));
280
276
sendId (LM_API_POS_REF | device_number_);
281
277
}
282
278
break ;
@@ -289,7 +285,6 @@ void Driver::verifyParams()
289
285
}
290
286
else
291
287
{
292
- // interface_->queue(Message(LM_API_SPD_REF | device_number_));
293
288
sendId (LM_API_SPD_REF | device_number_);
294
289
}
295
290
break ;
@@ -302,9 +297,6 @@ void Driver::verifyParams()
302
297
}
303
298
else
304
299
{
305
- RCLCPP_WARN (rclcpp::get_logger (" rclcpp" ), " Puma Motor Controller on %s (%i): encoder count not set. Set to %i." ,
306
- device_name_.c_str (), device_number_, encoderCounts ());
307
- // interface_->queue(Message(LM_API_CFG_ENC_LINES | device_number_));
308
300
sendId (LM_API_CFG_ENC_LINES | device_number_);
309
301
}
310
302
break ;
@@ -317,9 +309,6 @@ void Driver::verifyParams()
317
309
}
318
310
else
319
311
{
320
- RCLCPP_WARN (rclcpp::get_logger (" rclcpp" ), " Puma Motor Controller on %s (%i): not in ClosedLoop mode, in mode: %i" ,
321
- device_name_.c_str (), device_number_, lastMode ());
322
- // interface_->queue(Message(LM_API_STATUS_CMODE | device_number_));
323
312
sendId (LM_API_STATUS_CMODE | device_number_);
324
313
}
325
314
break ;
@@ -354,15 +343,12 @@ void Driver::verifyParams()
354
343
switch (control_mode_)
355
344
{
356
345
case clearpath_motor_msgs::msg::PumaStatus::MODE_CURRENT:
357
- // interface_->queue(Message(LM_API_ICTRL_PC | device_number_));
358
346
sendId (LM_API_ICTRL_PC | device_number_);
359
347
break ;
360
348
case clearpath_motor_msgs::msg::PumaStatus::MODE_POSITION:
361
- // interface_->queue(Message(LM_API_POS_PC | device_number_));
362
349
sendId (LM_API_POS_PC | device_number_);
363
350
break ;
364
351
case clearpath_motor_msgs::msg::PumaStatus::MODE_SPEED:
365
- // interface_->queue(Message(LM_API_SPD_PC | device_number_));
366
352
sendId (LM_API_SPD_PC | device_number_);
367
353
break ;
368
354
}
@@ -382,15 +368,12 @@ void Driver::verifyParams()
382
368
switch (control_mode_)
383
369
{
384
370
case clearpath_motor_msgs::msg::PumaStatus::MODE_CURRENT:
385
- // interface_->queue(Message(LM_API_ICTRL_IC | device_number_));
386
371
sendId (LM_API_ICTRL_IC | device_number_);
387
372
break ;
388
373
case clearpath_motor_msgs::msg::PumaStatus::MODE_POSITION:
389
- // interface_->queue(Message(LM_API_POS_IC | device_number_));
390
374
sendId (LM_API_POS_IC | device_number_);
391
375
break ;
392
376
case clearpath_motor_msgs::msg::PumaStatus::MODE_SPEED:
393
- // interface_->queue(Message(LM_API_SPD_IC | device_number_));
394
377
sendId (LM_API_SPD_IC | device_number_);
395
378
break ;
396
379
}
@@ -410,15 +393,12 @@ void Driver::verifyParams()
410
393
switch (control_mode_)
411
394
{
412
395
case clearpath_motor_msgs::msg::PumaStatus::MODE_CURRENT:
413
- // interface_->queue(Message(LM_API_ICTRL_DC | device_number_));
414
396
sendId (LM_API_ICTRL_DC | device_number_);
415
397
break ;
416
398
case clearpath_motor_msgs::msg::PumaStatus::MODE_POSITION:
417
- // interface_->queue(Message(LM_API_POS_DC | device_number_));
418
399
sendId (LM_API_POS_DC | device_number_);
419
400
break ;
420
401
case clearpath_motor_msgs::msg::PumaStatus::MODE_SPEED:
421
- // interface_->queue(Message(LM_API_SPD_DC | device_number_));
422
402
sendId (LM_API_SPD_DC | device_number_);
423
403
break ;
424
404
}
@@ -451,26 +431,21 @@ void Driver::configureParams()
451
431
sendUint16 ((LM_API_CFG_ENC_LINES | device_number_), encoder_cpr_);
452
432
break ;
453
433
case ConfigurationState::ClosedLoop: // Need to enter a close loop mode to record encoder data.
454
- // interface_->queue(Message(LM_API_SPD_EN | device_number_));
455
434
sendId (LM_API_SPD_EN | device_number_);
456
435
break ;
457
436
case ConfigurationState::ControlMode:
458
437
switch (control_mode_)
459
438
{
460
439
case clearpath_motor_msgs::msg::PumaStatus::MODE_VOLTAGE:
461
- // interface_->queue(Message(LM_API_VOLT_EN | device_number_));
462
440
sendId (LM_API_VOLT_EN | device_number_);
463
441
break ;
464
442
case clearpath_motor_msgs::msg::PumaStatus::MODE_CURRENT:
465
- // interface_->queue(Message(LM_API_ICTRL_EN | device_number_));
466
443
sendId (LM_API_ICTRL_EN | device_number_);
467
444
break ;
468
445
case clearpath_motor_msgs::msg::PumaStatus::MODE_POSITION:
469
- // interface_->queue(Message(LM_API_POS_EN | device_number_));
470
446
sendId (LM_API_POS_EN | device_number_);
471
447
break ;
472
448
case clearpath_motor_msgs::msg::PumaStatus::MODE_SPEED:
473
- // interface_->queue(Message(LM_API_SPD_EN | device_number_));
474
449
sendId (LM_API_SPD_EN | device_number_);
475
450
break ;
476
451
}
@@ -599,17 +574,11 @@ void Driver::clearMsgCache()
599
574
600
575
void Driver::requestStatusMessages ()
601
576
{
602
- // interface_->queue(Message(LM_API_STATUS_POWER | device_number_));
603
577
sendId (LM_API_STATUS_POWER | device_number_);
604
578
}
605
579
606
580
void Driver::requestFeedbackMessages ()
607
581
{
608
- // interface_->queue(Message(LM_API_STATUS_VOLTOUT | device_number_));
609
- // interface_->queue(Message(LM_API_STATUS_CURRENT | device_number_));
610
- // interface_->queue(Message(LM_API_STATUS_POS | device_number_));
611
- // interface_->queue(Message(LM_API_STATUS_SPD | device_number_));
612
- // interface_->queue(Message(LM_API_SPD_SET | device_number_));
613
582
sendId (LM_API_STATUS_VOLTOUT | device_number_);
614
583
sendId (LM_API_STATUS_CURRENT | device_number_);
615
584
sendId (LM_API_STATUS_POS | device_number_);
@@ -618,31 +587,26 @@ void Driver::requestFeedbackMessages()
618
587
}
619
588
void Driver::requestFeedbackDutyCycle ()
620
589
{
621
- // interface_->queue(Message(LM_API_STATUS_VOLTOUT | device_number_));
622
590
sendId (LM_API_STATUS_VOLTOUT | device_number_);
623
591
}
624
592
625
593
void Driver::requestFeedbackCurrent ()
626
594
{
627
- // interface_->queue(Message(LM_API_STATUS_CURRENT | device_number_));
628
595
sendId (LM_API_STATUS_CURRENT | device_number_);
629
596
}
630
597
631
598
void Driver::requestFeedbackPosition ()
632
599
{
633
- // interface_->queue(Message(LM_API_STATUS_POS | device_number_));
634
600
sendId (LM_API_STATUS_POS | device_number_);
635
601
}
636
602
637
603
void Driver::requestFeedbackSpeed ()
638
604
{
639
- // interface_->queue(Message(LM_API_STATUS_SPD | device_number_));
640
605
sendId (LM_API_STATUS_SPD | device_number_);
641
606
}
642
607
643
608
void Driver::requestFeedbackPowerState ()
644
609
{
645
- // interface_->queue(Message(LM_API_STATUS_POWER | device_number_));
646
610
sendId (LM_API_STATUS_POWER | device_number_);
647
611
}
648
612
@@ -651,19 +615,15 @@ void Driver::requestFeedbackSetpoint()
651
615
switch (control_mode_)
652
616
{
653
617
case clearpath_motor_msgs::msg::PumaStatus::MODE_CURRENT:
654
- // interface_->queue(Message(LM_API_ICTRL_SET | device_number_));
655
618
sendId (LM_API_ICTRL_SET | device_number_);
656
619
break ;
657
620
case clearpath_motor_msgs::msg::PumaStatus::MODE_POSITION:
658
- // interface_->queue(Message(LM_API_POS_SET | device_number_));
659
621
sendId (LM_API_POS_SET | device_number_);
660
622
break ;
661
623
case clearpath_motor_msgs::msg::PumaStatus::MODE_SPEED:
662
- // interface_->queue(Message(LM_API_SPD_SET | device_number_));
663
624
sendId (LM_API_SPD_SET | device_number_);
664
625
break ;
665
626
case clearpath_motor_msgs::msg::PumaStatus::MODE_VOLTAGE:
666
- // interface_->queue(Message(LM_API_VOLT_SET | device_number_));
667
627
sendId (LM_API_VOLT_SET | device_number_);
668
628
break ;
669
629
};
0 commit comments