12 #include <franka/robot_state.h>
21 "ForceExampleController: Make sure your robot's endeffector is in contact "
22 "with a horizontal surface before starting the controller!");
24 ROS_ERROR(
"ForceExampleController: Could not read parameter arm_id");
29 "ForceExampleController: Invalid or no joint_names parameters provided, aborting "
35 if (model_interface ==
nullptr) {
36 ROS_ERROR_STREAM(
"ForceExampleController: Error getting model interface from hardware");
40 model_handle_ = std::make_unique<franka_hw::FrankaModelHandle>(
41 model_interface->getHandle(
arm_id +
"_model"));
44 "ForceExampleController: Exception getting model handle from interface: " << ex.
what());
49 if (state_interface ==
nullptr) {
50 ROS_ERROR_STREAM(
"ForceExampleController: Error getting state interface from hardware");
54 state_handle_ = std::make_unique<franka_hw::FrankaStateHandle>(
55 state_interface->getHandle(
arm_id +
"_robot"));
58 "ForceExampleController: Exception getting state handle from interface: " << ex.
what());
63 if (effort_joint_interface ==
nullptr) {
64 ROS_ERROR_STREAM(
"ForceExampleController: Error getting effort joint interface from hardware");
67 for (
size_t i = 0; i < 7; ++i) {
79 dynamic_reconfigure::Server<franka_example_controllers::desired_mass_paramConfig>>(
89 franka::RobotState robot_state =
state_handle_->getRobotState();
90 std::array<double, 7> gravity_array =
model_handle_->getGravity();
91 Eigen::Map<Eigen::Matrix<double, 7, 1>> tau_measured(robot_state.tau_J.data());
92 Eigen::Map<Eigen::Matrix<double, 7, 1>> gravity(gravity_array.data());
99 franka::RobotState robot_state =
state_handle_->getRobotState();
100 std::array<double, 42> jacobian_array =
102 std::array<double, 7> gravity_array =
model_handle_->getGravity();
103 Eigen::Map<Eigen::Matrix<double, 6, 7>> jacobian(jacobian_array.data());
104 Eigen::Map<Eigen::Matrix<double, 7, 1>> tau_measured(robot_state.tau_J.data());
105 Eigen::Map<Eigen::Matrix<double, 7, 1>> tau_J_d(
106 robot_state.tau_J_d.data());
107 Eigen::Map<Eigen::Matrix<double, 7, 1>> gravity(gravity_array.data());
109 Eigen::Matrix<double, 7, 1> tau_d, tau_cmd, tau_ext;
110 Eigen::Matrix<double, 6, 1> desired_force_torque;
111 desired_force_torque.setZero();
114 tau_d = jacobian.transpose() * desired_force_torque;
120 for (
size_t i = 0; i < 7; ++i) {
131 franka_example_controllers::desired_mass_paramConfig& config,
139 const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
140 const Eigen::Matrix<double, 7, 1>& tau_J_d) {
141 Eigen::Matrix<double, 7, 1> tau_d_saturated{};
142 for (
size_t i = 0; i < 7; i++) {
143 double difference = tau_d_calculated[i] - tau_J_d[i];
146 return tau_d_saturated;