9 #include <franka/robot_state.h>
19 std::vector<double> cartesian_stiffness_vector;
20 std::vector<double> cartesian_damping_vector;
28 ROS_ERROR_STREAM(
"CartesianImpedanceExampleController: Could not read parameter arm_id");
34 "CartesianImpedanceExampleController: Invalid or no joint_names parameters provided, "
35 "aborting controller init!");
40 if (model_interface ==
nullptr) {
42 "CartesianImpedanceExampleController: Error getting model interface from hardware");
46 model_handle_ = std::make_unique<franka_hw::FrankaModelHandle>(
47 model_interface->getHandle(
arm_id +
"_model"));
50 "CartesianImpedanceExampleController: Exception getting model handle from interface: "
56 if (state_interface ==
nullptr) {
58 "CartesianImpedanceExampleController: Error getting state interface from hardware");
62 state_handle_ = std::make_unique<franka_hw::FrankaStateHandle>(
63 state_interface->getHandle(
arm_id +
"_robot"));
66 "CartesianImpedanceExampleController: Exception getting state handle from interface: "
72 if (effort_joint_interface ==
nullptr) {
74 "CartesianImpedanceExampleController: Error getting effort joint interface from hardware");
77 for (
size_t i = 0; i < 7; ++i) {
82 "CartesianImpedanceExampleController: Exception getting joint handles: " << ex.
what());
91 dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>>(
111 franka::RobotState initial_state =
state_handle_->getRobotState();
113 std::array<double, 42> jacobian_array =
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()));
121 orientation_d_ = Eigen::Quaterniond(initial_transform.rotation());
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 =
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(
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.rotation());
150 Eigen::Matrix<double, 6, 1>
error;
155 orientation.coeffs() << -orientation.coeffs();
158 Eigen::Quaterniond error_quaternion(orientation.inverse() *
orientation_d_);
159 error.tail(3) << error_quaternion.x(), error_quaternion.y(), error_quaternion.z();
161 error.tail(3) << -transform.rotation() *
error.tail(3);
165 Eigen::VectorXd tau_task(7), tau_nullspace(7), tau_d(7);
169 Eigen::MatrixXd jacobian_transpose_pinv;
170 pseudoInverse(jacobian.transpose(), jacobian_transpose_pinv);
173 tau_task << jacobian.transpose() *
176 tau_nullspace << (Eigen::MatrixXd::Identity(7, 7) -
177 jacobian.transpose() * jacobian_transpose_pinv) *
181 tau_d << tau_task + tau_nullspace + coriolis;
184 for (
size_t i = 0; i < 7; ++i) {
196 std::lock_guard<std::mutex> position_d_target_mutex_lock(
203 const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
204 const Eigen::Matrix<double, 7, 1>& tau_J_d) {
205 Eigen::Matrix<double, 7, 1> tau_d_saturated{};
206 for (
size_t i = 0; i < 7; i++) {
207 double difference = tau_d_calculated[i] - tau_J_d[i];
211 return tau_d_saturated;
215 franka_example_controllers::compliance_paramConfig& config,
219 << config.translational_stiffness * Eigen::Matrix3d::Identity();
221 << config.rotational_stiffness * Eigen::Matrix3d::Identity();
225 << 2.0 * sqrt(config.translational_stiffness) * Eigen::Matrix3d::Identity();
227 << 2.0 * sqrt(config.rotational_stiffness) * Eigen::Matrix3d::Identity();
232 const geometry_msgs::PoseStampedConstPtr& msg) {
233 std::lock_guard<std::mutex> position_d_target_mutex_lock(
235 position_d_target_ << msg->pose.position.x, msg->pose.position.y, msg->pose.position.z;
238 msg->pose.orientation.z, msg->pose.orientation.w;