Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Have set_hold_position() actually stop the robot #684

Closed
wants to merge 4 commits into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 23 additions & 0 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,6 +360,29 @@ controller_interface::return_type JointTrajectoryController::update(
RCLCPP_ERROR(get_node()->get_logger(), "Holding position due to state tolerance violation");
}
}
else
{
RCLCPP_DEBUG(get_node()->get_logger(), "Likely an Empty trajectory from set_hold_position(). Holding position...");
for (size_t index = 0; index < dof_; ++index)
{
if (has_position_command_interface_)
{
joint_command_interface_[0][index].get().set_value(
joint_command_interface_[0][index].get().get_value());
}

if (has_velocity_command_interface_)
{
joint_command_interface_[1][index].get().set_value(0.0);
}

// TODO(anyone): How to halt when using effort commands?
if (has_effort_command_interface_)
{
joint_command_interface_[3][index].get().set_value(0.0);
}
}
}
}

publish_state(time, state_desired_, state_current_, state_error_);
Expand Down