cartesian_impedance_example_controller.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
4 
5 #include <cmath>
6 #include <memory>
7 
9 #include <franka/robot_state.h>
11 #include <ros/ros.h>
12 
14 
16 
18  ros::NodeHandle& node_handle) {
19  std::vector<double> cartesian_stiffness_vector;
20  std::vector<double> cartesian_damping_vector;
21 
22  sub_equilibrium_pose_ = node_handle.subscribe(
24  ros::TransportHints().reliable().tcpNoDelay());
25 
26  std::string arm_id;
27  if (!node_handle.getParam("arm_id", arm_id)) {
28  ROS_ERROR_STREAM("CartesianImpedanceExampleController: Could not read parameter arm_id");
29  return false;
30  }
31  std::vector<std::string> joint_names;
32  if (!node_handle.getParam("joint_names", joint_names) || joint_names.size() != 7) {
33  ROS_ERROR(
34  "CartesianImpedanceExampleController: Invalid or no joint_names parameters provided, "
35  "aborting controller init!");
36  return false;
37  }
38 
39  auto* model_interface = robot_hw->get<franka_hw::FrankaModelInterface>();
40  if (model_interface == nullptr) {
42  "CartesianImpedanceExampleController: Error getting model interface from hardware");
43  return false;
44  }
45  try {
46  model_handle_ = std::make_unique<franka_hw::FrankaModelHandle>(
47  model_interface->getHandle(arm_id + "_model"));
50  "CartesianImpedanceExampleController: Exception getting model handle from interface: "
51  << ex.what());
52  return false;
53  }
54 
55  auto* state_interface = robot_hw->get<franka_hw::FrankaStateInterface>();
56  if (state_interface == nullptr) {
58  "CartesianImpedanceExampleController: Error getting state interface from hardware");
59  return false;
60  }
61  try {
62  state_handle_ = std::make_unique<franka_hw::FrankaStateHandle>(
63  state_interface->getHandle(arm_id + "_robot"));
66  "CartesianImpedanceExampleController: Exception getting state handle from interface: "
67  << ex.what());
68  return false;
69  }
70 
71  auto* effort_joint_interface = robot_hw->get<hardware_interface::EffortJointInterface>();
72  if (effort_joint_interface == nullptr) {
74  "CartesianImpedanceExampleController: Error getting effort joint interface from hardware");
75  return false;
76  }
77  for (size_t i = 0; i < 7; ++i) {
78  try {
79  joint_handles_.push_back(effort_joint_interface->getHandle(joint_names[i]));
82  "CartesianImpedanceExampleController: Exception getting joint handles: " << ex.what());
83  return false;
84  }
85  }
86 
88  ros::NodeHandle("dynamic_reconfigure_compliance_param_node");
89 
90  dynamic_server_compliance_param_ = std::make_unique<
91  dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>>(
92 
96 
97  position_d_.setZero();
98  orientation_d_.coeffs() << 0.0, 0.0, 0.0, 1.0;
99  position_d_target_.setZero();
100  orientation_d_target_.coeffs() << 0.0, 0.0, 0.0, 1.0;
101 
102  cartesian_stiffness_.setZero();
103  cartesian_damping_.setZero();
104 
105  return true;
106 }
107 
109  // compute initial velocity with jacobian and set x_attractor and q_d_nullspace
110  // to initial configuration
111  franka::RobotState initial_state = state_handle_->getRobotState();
112  // get jacobian
113  std::array<double, 42> jacobian_array =
114  model_handle_->getZeroJacobian(franka::Frame::kEndEffector);
115  // convert to eigen
116  Eigen::Map<Eigen::Matrix<double, 7, 1>> q_initial(initial_state.q.data());
117  Eigen::Affine3d initial_transform(Eigen::Matrix4d::Map(initial_state.O_T_EE.data()));
118 
119  // set equilibrium point to current state
120  position_d_ = initial_transform.translation();
121  orientation_d_ = Eigen::Quaterniond(initial_transform.linear());
122  position_d_target_ = initial_transform.translation();
123  orientation_d_target_ = Eigen::Quaterniond(initial_transform.linear());
124 
125  // set nullspace equilibrium configuration to initial q
126  q_d_nullspace_ = q_initial;
127 }
128 
130  const ros::Duration& /*period*/) {
131  // get state variables
132  franka::RobotState robot_state = state_handle_->getRobotState();
133  std::array<double, 7> coriolis_array = model_handle_->getCoriolis();
134  std::array<double, 42> jacobian_array =
135  model_handle_->getZeroJacobian(franka::Frame::kEndEffector);
136 
137  // convert to Eigen
138  Eigen::Map<Eigen::Matrix<double, 7, 1>> coriolis(coriolis_array.data());
139  Eigen::Map<Eigen::Matrix<double, 6, 7>> jacobian(jacobian_array.data());
140  Eigen::Map<Eigen::Matrix<double, 7, 1>> q(robot_state.q.data());
141  Eigen::Map<Eigen::Matrix<double, 7, 1>> dq(robot_state.dq.data());
142  Eigen::Map<Eigen::Matrix<double, 7, 1>> tau_J_d( // NOLINT (readability-identifier-naming)
143  robot_state.tau_J_d.data());
144  Eigen::Affine3d transform(Eigen::Matrix4d::Map(robot_state.O_T_EE.data()));
145  Eigen::Vector3d position(transform.translation());
146  Eigen::Quaterniond orientation(transform.linear());
147 
148  // compute error to desired pose
149  // position error
150  Eigen::Matrix<double, 6, 1> error;
151  error.head(3) << position - position_d_;
152 
153  // orientation error
154  if (orientation_d_.coeffs().dot(orientation.coeffs()) < 0.0) {
155  orientation.coeffs() << -orientation.coeffs();
156  }
157  // "difference" quaternion
158  Eigen::Quaterniond error_quaternion(orientation.inverse() * orientation_d_);
159  error.tail(3) << error_quaternion.x(), error_quaternion.y(), error_quaternion.z();
160  // Transform to base frame
161  error.tail(3) << -transform.linear() * error.tail(3);
162 
163  // compute control
164  // allocate variables
165  Eigen::VectorXd tau_task(7), tau_nullspace(7), tau_d(7);
166 
167  // pseudoinverse for nullspace handling
168  // kinematic pseuoinverse
169  Eigen::MatrixXd jacobian_transpose_pinv;
170  pseudoInverse(jacobian.transpose(), jacobian_transpose_pinv);
171 
172  // Cartesian PD control with damping ratio = 1
173  tau_task << jacobian.transpose() *
174  (-cartesian_stiffness_ * error - cartesian_damping_ * (jacobian * dq));
175  // nullspace PD control with damping ratio = 1
176  tau_nullspace << (Eigen::MatrixXd::Identity(7, 7) -
177  jacobian.transpose() * jacobian_transpose_pinv) *
179  (2.0 * sqrt(nullspace_stiffness_)) * dq);
180  // Desired torque
181  tau_d << tau_task + tau_nullspace + coriolis;
182  // Saturate torque rate to avoid discontinuities
183  tau_d << saturateTorqueRate(tau_d, tau_J_d);
184  for (size_t i = 0; i < 7; ++i) {
185  joint_handles_[i].setCommand(tau_d(i));
186  }
187 
188  // update parameters changed online either through dynamic reconfigure or through the interactive
189  // target by filtering
193  filter_params_ * cartesian_damping_target_ + (1.0 - filter_params_) * cartesian_damping_;
195  filter_params_ * nullspace_stiffness_target_ + (1.0 - filter_params_) * nullspace_stiffness_;
196  position_d_ = filter_params_ * position_d_target_ + (1.0 - filter_params_) * position_d_;
197  orientation_d_ = orientation_d_.slerp(filter_params_, orientation_d_target_);
198 }
199 
201  const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
202  const Eigen::Matrix<double, 7, 1>& tau_J_d) { // NOLINT (readability-identifier-naming)
203  Eigen::Matrix<double, 7, 1> tau_d_saturated{};
204  for (size_t i = 0; i < 7; i++) {
205  double difference = tau_d_calculated[i] - tau_J_d[i];
206  tau_d_saturated[i] =
207  tau_J_d[i] + std::max(std::min(difference, delta_tau_max_), -delta_tau_max_);
208  }
209  return tau_d_saturated;
210 }
211 
213  franka_example_controllers::compliance_paramConfig& config,
214  uint32_t /*level*/) {
215  cartesian_stiffness_target_.setIdentity();
216  cartesian_stiffness_target_.topLeftCorner(3, 3)
217  << config.translational_stiffness * Eigen::Matrix3d::Identity();
218  cartesian_stiffness_target_.bottomRightCorner(3, 3)
219  << config.rotational_stiffness * Eigen::Matrix3d::Identity();
220  cartesian_damping_target_.setIdentity();
221  // Damping ratio = 1
222  cartesian_damping_target_.topLeftCorner(3, 3)
223  << 2.0 * sqrt(config.translational_stiffness) * Eigen::Matrix3d::Identity();
224  cartesian_damping_target_.bottomRightCorner(3, 3)
225  << 2.0 * sqrt(config.rotational_stiffness) * Eigen::Matrix3d::Identity();
226  nullspace_stiffness_target_ = config.nullspace_stiffness;
227 }
228 
230  const geometry_msgs::PoseStampedConstPtr& msg) {
231  position_d_target_ << msg->pose.position.x, msg->pose.position.y, msg->pose.position.z;
232  Eigen::Quaterniond last_orientation_d_target(orientation_d_target_);
233  orientation_d_target_.coeffs() << msg->pose.orientation.x, msg->pose.orientation.y,
234  msg->pose.orientation.z, msg->pose.orientation.w;
235  if (last_orientation_d_target.coeffs().dot(orientation_d_target_.coeffs()) < 0.0) {
236  orientation_d_target_.coeffs() << -orientation_d_target_.coeffs();
237  }
238 }
239 
240 } // namespace franka_example_controllers
241 
void pseudoInverse(const Eigen::MatrixXd &M_, Eigen::MatrixXd &M_pinv_, bool damped=true)
q
std::string arm_id
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::compliance_paramConfig > > dynamic_server_compliance_param_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void update(const ros::Time &, const ros::Duration &period) override
std::array< std::string, 7 > joint_names
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
std::array< double, 7 > q
def error(args, kwargs)
Eigen::Matrix< double, 7, 1 > saturateTorqueRate(const Eigen::Matrix< double, 7, 1 > &tau_d_calculated, const Eigen::Matrix< double, 7, 1 > &tau_J_d)
std::array< double, 7 > dq
std::array< double, 16 > O_T_EE
void complianceParamCallback(franka_example_controllers::compliance_paramConfig &config, uint32_t level)
std::array< double, 7 > tau_J_d
bool getParam(const std::string &key, std::string &s) const
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:17