Skip to content

Commit 158dd34

Browse files
committed
joint_trajectory_controller should not go into FINALIZED state when fails to configure, remain in UNCONFIGURED
1 parent 9b4793e commit 158dd34

File tree

1 file changed

+13
-13
lines changed

1 file changed

+13
-13
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -316,7 +316,7 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
316316
joint_names_ = node_->get_parameter("joints").as_string_array();
317317

318318
if (!reset()) {
319-
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
319+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
320320
}
321321

322322
if (joint_names_.empty()) {
@@ -330,7 +330,7 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
330330

331331
if (command_interface_types_.empty()) {
332332
RCLCPP_ERROR(logger, "'command_interfaces' parameter is empty.");
333-
return CallbackReturn::ERROR;
333+
return CallbackReturn::FAILURE;
334334
}
335335

336336
// Check if only allowed interface types are used and initialize storage to avoid memory
@@ -341,7 +341,7 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
341341
allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
342342
if (it == allowed_interface_types_.end()) {
343343
RCLCPP_ERROR(logger, "Command interface type '" + interface + "' not allowed!");
344-
return CallbackReturn::ERROR;
344+
return CallbackReturn::FAILURE;
345345
}
346346
}
347347

@@ -359,10 +359,10 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
359359
use_closed_loop_pid_adapter = true;
360360
// TODO(anyone): remove the next two lines when implemented
361361
RCLCPP_ERROR(logger, "using 'effort' command interface alone is not yet implemented yet.");
362-
return CallbackReturn::ERROR;
362+
return CallbackReturn::FAILURE;
363363
} else {
364364
RCLCPP_ERROR(logger, "'effort' command interface has to be used alone.");
365-
return CallbackReturn::ERROR;
365+
return CallbackReturn::FAILURE;
366366
}
367367
}
368368

@@ -382,20 +382,20 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
382382
use_closed_loop_pid_adapter = true;
383383
// TODO(anyone): remove this when implemented
384384
RCLCPP_ERROR(logger, "using 'velocity' command interface alone is not yet implemented yet.");
385-
return CallbackReturn::ERROR;
385+
return CallbackReturn::FAILURE;
386386
// if velocity interface can be used without position if multiple defined
387387
} else if (!has_position_command_interface_) {
388388
RCLCPP_ERROR(
389389
logger, "'velocity' command interface can be used either alone or 'position' "
390390
"interface has to be present.");
391-
return CallbackReturn::ERROR;
391+
return CallbackReturn::FAILURE;
392392
}
393393
// invalid: acceleration is defined and no velocity
394394
} else if (has_acceleration_command_interface_) {
395395
RCLCPP_ERROR(
396396
logger, "'acceleration' command interface can only be used if 'velocity' and "
397397
"'position' interfaces are present");
398-
return CallbackReturn::ERROR;
398+
return CallbackReturn::FAILURE;
399399
}
400400

401401
// Read always state interfaces from the parameter because they can be used
@@ -405,12 +405,12 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
405405

406406
if (state_interface_types_.empty()) {
407407
RCLCPP_ERROR(logger, "'state_interfaces' parameter is empty.");
408-
return CallbackReturn::ERROR;
408+
return CallbackReturn::FAILURE;
409409
}
410410

411411
if (contains_interface_type(state_interface_types_, hardware_interface::HW_IF_EFFORT)) {
412412
RCLCPP_ERROR(logger, "State interface type 'effort' not allowed!");
413-
return CallbackReturn::ERROR;
413+
return CallbackReturn::FAILURE;
414414
}
415415

416416
// Check if only allowed interface types are used and initialize storage to avoid memory
@@ -422,7 +422,7 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
422422
allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
423423
if (it == allowed_interface_types_.end()) {
424424
RCLCPP_ERROR(logger, "State interface type '" + interface + "' not allowed!");
425-
return CallbackReturn::ERROR;
425+
return CallbackReturn::FAILURE;
426426
}
427427
}
428428

@@ -438,13 +438,13 @@ JointTrajectoryController::on_configure(const rclcpp_lifecycle::State &)
438438
RCLCPP_ERROR(
439439
logger, "'velocity' state interface cannot be used if 'position' interface "
440440
"is missing.");
441-
return CallbackReturn::ERROR;
441+
return CallbackReturn::FAILURE;
442442
}
443443
} else if (has_acceleration_state_interface_) {
444444
RCLCPP_ERROR(
445445
logger, "'acceleration' state interface cannot be used if 'position' and 'velocity' "
446446
"interfaces are not present.");
447-
return CallbackReturn::ERROR;
447+
return CallbackReturn::FAILURE;
448448
}
449449

450450
auto get_interface_list = [](const std::vector<std::string> & interface_types) {

0 commit comments

Comments
 (0)