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

[Admittance] multiple state/command interfaces #1196

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
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
24 changes: 15 additions & 9 deletions admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,6 +244,12 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
has_acceleration_state_interface_ = contains_interface_type(
admittance_->parameters_.state_interfaces, hardware_interface::HW_IF_ACCELERATION);

if (!has_position_state_interface_)
{
RCLCPP_ERROR(get_node()->get_logger(), "Position state interface is required.");
return CallbackReturn::FAILURE;
}

auto get_interface_list = [](const std::vector<std::string> & interface_types)
{
std::stringstream ss_command_interfaces;
Expand Down Expand Up @@ -470,7 +476,7 @@ void AdmittanceController::read_state_from_hardware(
bool nan_acceleration = false;

size_t pos_ind = 0;
size_t vel_ind = pos_ind + has_velocity_command_interface_;
size_t vel_ind = pos_ind + has_velocity_state_interface_;
size_t acc_ind = vel_ind + has_acceleration_state_interface_;
for (size_t joint_ind = 0; joint_ind < num_joints_; ++joint_ind)
{
Expand All @@ -480,13 +486,13 @@ void AdmittanceController::read_state_from_hardware(
state_interfaces_[pos_ind * num_joints_ + joint_ind].get_value();
nan_position |= std::isnan(state_current.positions[joint_ind]);
}
else if (has_velocity_state_interface_)
if (has_velocity_state_interface_)
{
state_current.velocities[joint_ind] =
state_interfaces_[vel_ind * num_joints_ + joint_ind].get_value();
nan_velocity |= std::isnan(state_current.velocities[joint_ind]);
}
else if (has_acceleration_state_interface_)
if (has_acceleration_state_interface_)
{
state_current.accelerations[joint_ind] =
state_interfaces_[acc_ind * num_joints_ + joint_ind].get_value();
Expand Down Expand Up @@ -523,24 +529,24 @@ void AdmittanceController::write_state_to_hardware(
{
// if any interface has nan values, assume state_commanded is the last command state
size_t pos_ind = 0;
size_t vel_ind = pos_ind + has_velocity_command_interface_;
size_t acc_ind = vel_ind + has_acceleration_state_interface_;
size_t vel_ind = (has_position_command_interface_) ? has_velocity_command_interface_ : pos_ind;
size_t acc_ind = vel_ind + has_acceleration_command_interface_;
for (size_t joint_ind = 0; joint_ind < num_joints_; ++joint_ind)
{
if (has_position_command_interface_)
{
command_interfaces_[pos_ind * num_joints_ + joint_ind].set_value(
state_commanded.positions[joint_ind]);
}
else if (has_velocity_command_interface_)
if (has_velocity_command_interface_)
{
command_interfaces_[vel_ind * num_joints_ + joint_ind].set_value(
state_commanded.positions[joint_ind]);
state_commanded.velocities[joint_ind]);
}
else if (has_acceleration_command_interface_)
if (has_acceleration_command_interface_)
{
command_interfaces_[acc_ind * num_joints_ + joint_ind].set_value(
state_commanded.positions[joint_ind]);
state_commanded.accelerations[joint_ind]);
}
}
last_commanded_ = state_commanded;
Expand Down
Loading