18 #ifndef GRIPPER_CONTROLLERS__HARDWARE_INTERFACE_ADAPTER_HPP_
19 #define GRIPPER_CONTROLLERS__HARDWARE_INTERFACE_ADAPTER_HPP_
26 #include "control_toolbox/pid.hpp"
27 #include "hardware_interface/types/hardware_interface_type_values.hpp"
28 #include "rclcpp/time.hpp"
29 #include "rclcpp_lifecycle/lifecycle_node.hpp"
39 template <const
char * HardwareInterface>
45 std::reference_wrapper<hardware_interface::LoanedCommandInterface>> ,
46 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & )
51 void starting(
const rclcpp::Time & ) {}
52 void stopping(
const rclcpp::Time & ) {}
55 double ,
double ,
double ,
71 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle,
72 const rclcpp_lifecycle::LifecycleNode::SharedPtr & )
74 joint_handle_ = joint_handle;
78 void starting(
const rclcpp::Time & ) {}
79 void stopping(
const rclcpp::Time & ) {}
82 double desired_position,
double ,
double ,
83 double ,
double max_allowed_effort)
86 joint_handle_->get().set_value(desired_position);
87 return max_allowed_effort;
91 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle_;
112 template <
typename ParameterT>
114 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node,
const std::string & name,
115 const ParameterT & default_value)
117 if (!node->has_parameter(name))
119 return node->declare_parameter<ParameterT>(name, default_value);
123 return node->get_parameter(name).get_value<ParameterT>();
128 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle,
129 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node)
131 joint_handle_ = joint_handle;
133 const std::string prefix =
"gains." + joint_handle_->get().get_prefix_name();
134 const auto k_p = auto_declare<double>(node, prefix +
".p", 0.0);
135 const auto k_i = auto_declare<double>(node, prefix +
".i", 0.0);
136 const auto k_d = auto_declare<double>(node, prefix +
".d", 0.0);
137 const auto i_clamp = auto_declare<double>(node, prefix +
".i_clamp", 0.0);
139 pid_ = std::make_shared<control_toolbox::Pid>(k_p, k_i, k_d, i_clamp, -i_clamp);
143 void starting(
const rclcpp::Time & )
151 joint_handle_->get().set_value(0.0);
154 void stopping(
const rclcpp::Time & ) {}
156 double updateCommand(
157 double ,
double ,
double error_position,
158 double error_velocity,
double max_allowed_effort)
166 const auto period = std::chrono::steady_clock::now() - last_update_time_;
169 pid_->computeCommand(error_position, error_velocity,
static_cast<uint64_t
>(period.count()));
170 command = std::min<double>(
171 fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
172 joint_handle_->get().set_value(command);
173 last_update_time_ = std::chrono::steady_clock::now();
178 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
180 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_handle_;
181 std::chrono::steady_clock::time_point last_update_time_;
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
Definition: hardware_interface_adapter.hpp:41
Definition: actuator.hpp:34