74 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
76 const rclcpp::Node::SharedPtr & )
78 joint_handle_ = joint_handle;
82 void starting(
const rclcpp::Time & ) {}
83 void stopping(
const rclcpp::Time & ) {}
86 double desired_position,
double ,
double ,
87 double ,
double max_allowed_effort)
90 joint_handle_->get().set_value(desired_position);
91 return max_allowed_effort;
95 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
117 template <
typename ParameterT>
119 const rclcpp::Node::SharedPtr & node,
const std::string & name,
120 const ParameterT & default_value)
122 if (!node->has_parameter(name))
124 return node->declare_parameter<ParameterT>(name, default_value);
128 return node->get_parameter(name).get_value<ParameterT>();
133 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
135 const rclcpp::Node::SharedPtr & node)
137 joint_handle_ = joint_handle;
139 const std::string prefix =
"gains." + joint_handle_->get().get_name();
140 const auto k_p = auto_declare<double>(node, prefix +
".p", 0.0);
141 const auto k_i = auto_declare<double>(node, prefix +
".i", 0.0);
142 const auto k_d = auto_declare<double>(node, prefix +
".d", 0.0);
143 const auto i_clamp = auto_declare<double>(node, prefix +
".i_clamp", 0.0);
145 pid_ = std::make_shared<control_toolbox::Pid>(k_p, k_i, k_d, i_clamp, -i_clamp);
149 void starting(
const rclcpp::Time & )
157 joint_handle_->get().set_value(0.0);
160 void stopping(
const rclcpp::Time & ) {}
162 double updateCommand(
163 double ,
double ,
double error_position,
164 double error_velocity,
double max_allowed_effort)
172 const auto period = std::chrono::steady_clock::now() - last_update_time_;
174 double command = pid_->computeCommand(error_position, error_velocity, period.count());
175 command = std::min<double>(
176 fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
177 joint_handle_->get().set_value(command);
178 last_update_time_ = std::chrono::steady_clock::now();
183 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
185 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
187 std::chrono::steady_clock::time_point last_update_time_;