A simple PI force controller that renders in the Z axis the gravitational force corresponding to a target mass of 1 kg.
A simple PI force controller that renders in the Z axis the gravitational force corresponding to a target mass of 1 kg.
#include <array>
#include <iostream>
#include <Eigen/Core>
int main(int argc, char** argv) {
if (argc != 2) {
std::cerr << "Usage: " << argv[0] << " <robot-hostname>" << std::endl;
return -1;
}
double desired_mass{0.0};
constexpr double target_mass{1.0};
constexpr double k_p{1.0};
constexpr double k_i{2.0};
constexpr double filter_gain{0.001};
try {
setDefaultBehavior(robot);
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}},
{{100.0, 100.0, 100.0, 100.0, 100.0, 100.0}});
Eigen::VectorXd initial_tau_ext(7), tau_error_integral(7);
std::array<double, 7> gravity_array = model.
gravity(initial_state);
Eigen::Map<Eigen::Matrix<double, 7, 1>> initial_tau_measured(initial_state.
tau_J.data());
Eigen::Map<Eigen::Matrix<double, 7, 1>> initial_gravity(gravity_array.data());
initial_tau_ext = initial_tau_measured - initial_gravity;
tau_error_integral.setZero();
Eigen::Vector3d initial_position;
double time = 0.0;
return Eigen::Vector3d(robot_state.O_T_EE[12], robot_state.O_T_EE[13],
robot_state.O_T_EE[14]);
};
time += period.toSec();
if (time == 0.0) {
initial_position = get_position(robot_state);
}
if (time > 0 && (get_position(robot_state) - initial_position).norm() > 0.01) {
throw std::runtime_error("Aborting; too far away from starting pose!");
}
std::array<double, 42> jacobian_array =
model.
zeroJacobian(franka::Frame::kEndEffector, robot_state);
Eigen::Map<const Eigen::Matrix<double, 6, 7>> jacobian(jacobian_array.data());
Eigen::Map<const Eigen::Matrix<double, 7, 1>> tau_measured(robot_state.
tau_J.data());
Eigen::Map<const Eigen::Matrix<double, 7, 1>> gravity(gravity_array.data());
Eigen::VectorXd tau_d(7), desired_force_torque(6), tau_cmd(7), tau_ext(7);
desired_force_torque.setZero();
desired_force_torque(2) = desired_mass * -9.81;
tau_ext << tau_measured - gravity - initial_tau_ext;
tau_d << jacobian.transpose() * desired_force_torque;
tau_error_integral += period.toSec() * (tau_d - tau_ext);
tau_cmd << tau_d + k_p * (tau_d - tau_ext) + k_i * tau_error_integral;
desired_mass = filter_gain * target_mass + (1 - filter_gain) * desired_mass;
std::array<double, 7> tau_d_array{};
Eigen::VectorXd::Map(&tau_d_array[0], 7) = tau_cmd;
return tau_d_array;
};
std::cout << "WARNING: Make sure sure that no endeffector is mounted and that the robot's last "
"joint is "
"in contact with a horizontal rigid surface before starting. Keep in mind that "
"collision thresholds are set to high values."
<< std::endl
<< "Press Enter to continue..." << std::endl;
std::cin.ignore();
robot.
control(force_control_callback);
} catch (const std::exception& ex) {
std::cout << ex.what() << std::endl;
}
return 0;
}
Represents a duration with millisecond resolution.
Definition duration.h:19
Calculates poses of joints and dynamic properties of the robot.
Definition model.h:52
std::array< double, 42 > zeroJacobian(Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept
Calculates the gravity vector.
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition robot.h:68
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
Starts a control loop for sending joint-level torque commands.
void setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds_acceleration, const std::array< double, 7 > &upper_torque_thresholds_acceleration, const std::array< double, 7 > &lower_torque_thresholds_nominal, const std::array< double, 7 > &upper_torque_thresholds_nominal, const std::array< double, 6 > &lower_force_thresholds_acceleration, const std::array< double, 6 > &upper_force_thresholds_acceleration, const std::array< double, 6 > &lower_force_thresholds_nominal, const std::array< double, 6 > &upper_force_thresholds_nominal)
Changes the collision behavior.
Model loadModel()
Loads the model library from the robot.
virtual RobotState readOnce()
Waits for a robot state update and returns it.
Stores joint-level torque commands without gravity and friction.
Definition control_types.h:45
Contains the franka::Duration type.
Contains common types and functions for the examples.
Contains exception definitions.
Contains model library types.
Contains the franka::Robot type.
Describes the robot state.
Definition robot_state.h:34
std::array< double, 7 > tau_J
Measured link-side joint torque sensor signals.
Definition robot_state.h:215