12 #include <franka/robot_state.h>
20 ROS_ERROR(
"JointImpedanceExampleController: Could not read parameter arm_id");
25 "JointImpedanceExampleController: No parameter radius, defaulting to: " <<
radius_);
27 if (std::fabs(
radius_) < 0.005) {
28 ROS_INFO_STREAM(
"JointImpedanceExampleController: Set radius to small, defaulting to: " << 0.1);
34 "JointImpedanceExampleController: No parameter vel_max, defaulting to: " <<
vel_max_);
38 "JointImpedanceExampleController: No parameter acceleration_time, defaulting to: "
45 "JointImpedanceExampleController: Invalid or no joint_names parameters provided, aborting "
52 "JointImpedanceExampleController: Invalid or no k_gain parameters provided, aborting "
59 "JointImpedanceExampleController: Invalid or no d_gain parameters provided, aborting "
64 double publish_rate(30.0);
65 if (!node_handle.
getParam(
"publish_rate", publish_rate)) {
66 ROS_INFO_STREAM(
"JointImpedanceExampleController: publish_rate not found. Defaulting to "
72 ROS_INFO_STREAM(
"JointImpedanceExampleController: coriolis_factor not found. Defaulting to "
77 if (model_interface ==
nullptr) {
79 "JointImpedanceExampleController: Error getting model interface from hardware");
83 model_handle_ = std::make_unique<franka_hw::FrankaModelHandle>(
84 model_interface->getHandle(
arm_id +
"_model"));
87 "JointImpedanceExampleController: Exception getting model handle from interface: "
93 if (cartesian_pose_interface ==
nullptr) {
95 "JointImpedanceExampleController: Error getting cartesian pose interface from hardware");
100 cartesian_pose_interface->getHandle(
arm_id +
"_robot"));
103 "JointImpedanceExampleController: Exception getting cartesian pose handle from interface: "
109 if (effort_joint_interface ==
nullptr) {
111 "JointImpedanceExampleController: Error getting effort joint interface from hardware");
114 for (
size_t i = 0; i < 7; ++i) {
119 "JointImpedanceExampleController: Exception getting joint handles: " << ex.
what());
150 pose_desired[13] += delta_y;
151 pose_desired[14] += delta_z;
155 std::array<double, 7> coriolis =
model_handle_->getCoriolis();
159 for (
size_t i = 0; i < 7; i++) {
163 std::array<double, 7> tau_d_calculated;
164 for (
size_t i = 0; i < 7; ++i) {
166 k_gains_[i] * (robot_state.q_d[i] - robot_state.q[i]) +
172 std::array<double, 7> tau_d_saturated =
saturateTorqueRate(tau_d_calculated, robot_state.tau_J_d);
174 for (
size_t i = 0; i < 7; ++i) {
179 std::array<double, 7> tau_j = robot_state.tau_J;
180 std::array<double, 7> tau_error;
181 double error_rms(0.0);
182 for (
size_t i = 0; i < 7; ++i) {
184 error_rms += std::sqrt(std::pow(tau_error[i], 2.0)) / 7.0;
187 for (
size_t i = 0; i < 7; ++i) {
195 for (
size_t i = 0; i < 7; ++i) {
201 const std::array<double, 7>& tau_d_calculated,
202 const std::array<double, 7>& tau_J_d) {
203 std::array<double, 7> tau_d_saturated{};
204 for (
size_t i = 0; i < 7; i++) {
205 double difference = tau_d_calculated[i] - tau_J_d[i];
208 return tau_d_saturated;