@@ -221,6 +221,7 @@ void NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>::configure(bool calle
221
221
std::optional<double > scale_vel_from_dev;
222
222
std::optional<double > offset_pos_to_dev;
223
223
std::optional<double > offset_pos_from_dev;
224
+ std::optional<double > scale_eff_from_dev;
224
225
std::optional<int > switching_state;
225
226
std::optional<int > homing_timeout_seconds;
226
227
try
@@ -266,6 +267,13 @@ void NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>::configure(bool calle
266
267
{
267
268
}
268
269
try
270
+ {
271
+ scale_eff_from_dev = std::optional (this ->config_ [" scale_eff_from_dev" ].as <double >());
272
+ }
273
+ catch (...)
274
+ {
275
+ }
276
+ try
269
277
{
270
278
switching_state = std::optional (this ->config_ [" switching_state" ].as <int >());
271
279
}
@@ -288,16 +296,18 @@ void NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>::configure(bool calle
288
296
scale_vel_from_dev_ = scale_vel_from_dev.value_or (0.001 );
289
297
offset_pos_to_dev_ = offset_pos_to_dev.value_or (0.0 );
290
298
offset_pos_from_dev_ = offset_pos_from_dev.value_or (0.0 );
299
+ scale_eff_from_dev_ = scale_eff_from_dev.value_or (0.001 );
291
300
switching_state_ = (ros2_canopen::State402::InternalState)switching_state.value_or (
292
301
(int )ros2_canopen::State402::InternalState::Operation_Enable);
293
302
homing_timeout_seconds_ = homing_timeout_seconds.value_or (10 );
294
303
RCLCPP_INFO (
295
304
this ->node_ ->get_logger (),
296
305
" scale_pos_to_dev_ %f\n scale_pos_from_dev_ %f\n scale_vel_to_dev_ %f\n scale_vel_from_dev_ "
306
+ " %f\n scale_eff_from_dev_ "
297
307
" %f\n offset_pos_to_dev_ %f\n offset_pos_from_dev_ "
298
308
" %f\n homing_timeout_seconds_ %i\n " ,
299
309
scale_pos_to_dev_, scale_pos_from_dev_, scale_vel_to_dev_, scale_vel_from_dev_,
300
- offset_pos_to_dev_, offset_pos_from_dev_, homing_timeout_seconds_);
310
+ scale_eff_from_dev_, offset_pos_to_dev_, offset_pos_from_dev_, homing_timeout_seconds_);
301
311
}
302
312
303
313
template <>
@@ -310,6 +320,7 @@ void NodeCanopen402Driver<rclcpp::Node>::configure(bool called_from_base)
310
320
std::optional<double > scale_vel_from_dev;
311
321
std::optional<double > offset_pos_to_dev;
312
322
std::optional<double > offset_pos_from_dev;
323
+ std::optional<double > scale_eff_from_dev;
313
324
std::optional<int > switching_state;
314
325
std::optional<int > homing_timeout_seconds;
315
326
try
@@ -355,6 +366,13 @@ void NodeCanopen402Driver<rclcpp::Node>::configure(bool called_from_base)
355
366
{
356
367
}
357
368
try
369
+ {
370
+ scale_eff_from_dev = std::optional (this ->config_ [" scale_eff_from_dev" ].as <double >());
371
+ }
372
+ catch (...)
373
+ {
374
+ }
375
+ try
358
376
{
359
377
switching_state = std::optional (this ->config_ [" switching_state" ].as <int >());
360
378
}
@@ -377,16 +395,18 @@ void NodeCanopen402Driver<rclcpp::Node>::configure(bool called_from_base)
377
395
scale_vel_from_dev_ = scale_vel_from_dev.value_or (0.001 );
378
396
offset_pos_to_dev_ = offset_pos_to_dev.value_or (0.0 );
379
397
offset_pos_from_dev_ = offset_pos_from_dev.value_or (0.0 );
398
+ scale_eff_from_dev_ = scale_eff_from_dev.value_or (0.001 );
380
399
switching_state_ = (ros2_canopen::State402::InternalState)switching_state.value_or (
381
400
(int )ros2_canopen::State402::InternalState::Operation_Enable);
382
401
homing_timeout_seconds_ = homing_timeout_seconds.value_or (10 );
383
402
RCLCPP_INFO (
384
403
this ->node_ ->get_logger (),
385
404
" scale_pos_to_dev_ %f\n scale_pos_from_dev_ %f\n scale_vel_to_dev_ %f\n scale_vel_from_dev_ "
405
+ " %f\n scale_eff_from_dev_ "
386
406
" %f\n offset_pos_to_dev_ %f\n offset_pos_from_dev_ "
387
407
" %f\n homing_timeout_seconds_ %i\n " ,
388
408
scale_pos_to_dev_, scale_pos_from_dev_, scale_vel_to_dev_, scale_vel_from_dev_,
389
- offset_pos_to_dev_, offset_pos_from_dev_, homing_timeout_seconds_);
409
+ scale_eff_from_dev_, offset_pos_to_dev_, offset_pos_from_dev_, homing_timeout_seconds_);
390
410
}
391
411
392
412
template <class NODETYPE >
@@ -420,7 +440,7 @@ void NodeCanopen402Driver<NODETYPE>::publish()
420
440
js_msg.name .push_back (this ->node_ ->get_name ());
421
441
js_msg.position .push_back (motor_->get_position () * scale_pos_from_dev_ + offset_pos_from_dev_);
422
442
js_msg.velocity .push_back (motor_->get_speed () * scale_vel_from_dev_);
423
- js_msg.effort .push_back (0.0 );
443
+ js_msg.effort .push_back (motor_-> get_effort () * scale_eff_from_dev_ );
424
444
publish_joint_state->publish (js_msg);
425
445
}
426
446
0 commit comments