Skip to content

Commit

Permalink
Fixed implementation so that effort_controllers/GripperActionControll…
Browse files Browse the repository at this point in the history
…er works. (#756) (#868)

(cherry picked from commit 6352a70)

Co-authored-by: chama1176 <[email protected]>
  • Loading branch information
mergify[bot] and chama1176 authored Nov 27, 2023
1 parent b4b465d commit c8f1b44
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class GripperActionController : public controller_interface::ControllerInterface
bool verbose_ = false; ///< Hard coded verbose flag to help in debugging
std::string name_; ///< Controller name.
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
joint_position_command_interface_;
joint_command_interface_;
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
joint_position_state_interface_;
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -226,20 +226,21 @@ template <const char * HardwareInterface>
controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_activate(
const rclcpp_lifecycle::State &)
{
auto position_command_interface_it = std::find_if(
auto command_interface_it = std::find_if(
command_interfaces_.begin(), command_interfaces_.end(),
[](const hardware_interface::LoanedCommandInterface & command_interface)
{ return command_interface.get_interface_name() == hardware_interface::HW_IF_POSITION; });
if (position_command_interface_it == command_interfaces_.end())
{ return command_interface.get_interface_name() == HardwareInterface; });
if (command_interface_it == command_interfaces_.end())
{
RCLCPP_ERROR(get_node()->get_logger(), "Expected 1 position command interface");
RCLCPP_ERROR_STREAM(
get_node()->get_logger(), "Expected 1 " << HardwareInterface << " command interface");
return controller_interface::CallbackReturn::ERROR;
}
if (position_command_interface_it->get_prefix_name() != params_.joint)
if (command_interface_it->get_prefix_name() != params_.joint)
{
RCLCPP_ERROR_STREAM(
get_node()->get_logger(), "Position command interface is different than joint name `"
<< position_command_interface_it->get_prefix_name() << "` != `"
get_node()->get_logger(), "Command interface is different than joint name `"
<< command_interface_it->get_prefix_name() << "` != `"
<< params_.joint << "`");
return controller_interface::CallbackReturn::ERROR;
}
Expand Down Expand Up @@ -278,12 +279,12 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
return controller_interface::CallbackReturn::ERROR;
}

joint_position_command_interface_ = *position_command_interface_it;
joint_command_interface_ = *command_interface_it;
joint_position_state_interface_ = *position_state_interface_it;
joint_velocity_state_interface_ = *velocity_state_interface_it;

// Hardware interface adapter
hw_iface_adapter_.init(joint_position_command_interface_, get_node());
hw_iface_adapter_.init(joint_command_interface_, get_node());

// Command - non RT version
command_struct_.position_ = joint_position_state_interface_->get().get_value();
Expand Down Expand Up @@ -311,7 +312,7 @@ template <const char * HardwareInterface>
controller_interface::CallbackReturn GripperActionController<HardwareInterface>::on_deactivate(
const rclcpp_lifecycle::State &)
{
joint_position_command_interface_ = std::nullopt;
joint_command_interface_ = std::nullopt;
joint_position_state_interface_ = std::nullopt;
joint_velocity_state_interface_ = std::nullopt;
release_interfaces();
Expand All @@ -324,7 +325,7 @@ GripperActionController<HardwareInterface>::command_interface_configuration() co
{
return {
controller_interface::interface_configuration_type::INDIVIDUAL,
{params_.joint + "/" + hardware_interface::HW_IF_POSITION}};
{params_.joint + "/" + HardwareInterface}};
}

template <const char * HardwareInterface>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ class HardwareInterfaceAdapter<hardware_interface::HW_IF_EFFORT>
{
joint_handle_ = joint_handle;
// Init PID gains from ROS parameter server
const std::string prefix = "gains." + joint_handle_->get().get_name();
const std::string prefix = "gains." + joint_handle_->get().get_prefix_name();
const auto k_p = auto_declare<double>(node, prefix + ".p", 0.0);
const auto k_i = auto_declare<double>(node, prefix + ".i", 0.0);
const auto k_d = auto_declare<double>(node, prefix + ".d", 0.0);
Expand Down

0 comments on commit c8f1b44

Please sign in to comment.