@@ -292,14 +292,7 @@ controller_interface::return_type JointTrajectoryController::update(
292
292
}
293
293
if (has_effort_command_interface_)
294
294
{
295
- if (use_closed_loop_pid_adapter_)
296
- {
297
- assign_interface_from_point (joint_command_interface_[3 ], tmp_command_);
298
- }
299
- else
300
- {
301
- assign_interface_from_point (joint_command_interface_[3 ], state_desired_.effort );
302
- }
295
+ assign_interface_from_point (joint_command_interface_[3 ], tmp_command_);
303
296
}
304
297
305
298
// store the previous command. Used in open-loop control mode
@@ -1364,8 +1357,9 @@ bool JointTrajectoryController::validate_trajectory_point_field(
1364
1357
if (joint_names_size != vector_field.size ())
1365
1358
{
1366
1359
RCLCPP_ERROR (
1367
- get_node ()->get_logger (), " Mismatch between joint_names (%zu) and %s (%zu) at point #%zu." ,
1368
- joint_names_size, string_for_vector_field.c_str (), vector_field.size (), i);
1360
+ get_node ()->get_logger (),
1361
+ " Mismatch between joint_names size (%zu) and %s (%zu) at point #%zu." , joint_names_size,
1362
+ string_for_vector_field.c_str (), vector_field.size (), i);
1369
1363
return false ;
1370
1364
}
1371
1365
return true ;
@@ -1481,11 +1475,17 @@ bool JointTrajectoryController::validate_trajectory_msg(
1481
1475
!validate_trajectory_point_field (joint_count, points[i].positions , " positions" , i, false ) ||
1482
1476
!validate_trajectory_point_field (joint_count, points[i].velocities , " velocities" , i, true ) ||
1483
1477
!validate_trajectory_point_field (
1484
- joint_count, points[i].accelerations , " accelerations" , i, true ) ||
1485
- !validate_trajectory_point_field (joint_count, points[i].effort , " effort" , i, true ))
1478
+ joint_count, points[i].accelerations , " accelerations" , i, true ))
1486
1479
{
1487
1480
return false ;
1488
1481
}
1482
+ // reject effort entries
1483
+ if (!points[i].effort .empty ())
1484
+ {
1485
+ RCLCPP_ERROR (
1486
+ get_node ()->get_logger (), " Trajectories with effort fields are currently not supported." );
1487
+ return false ;
1488
+ }
1489
1489
}
1490
1490
return true ;
1491
1491
}
0 commit comments