19 std::vector<double> cartesian_stiffness_vector;
20 std::vector<double> cartesian_damping_vector;
27 if (!node_handle.
getParam(
"arm_id", arm_id)) {
28 ROS_ERROR_STREAM(
"CartesianImpedanceExampleController: Could not read parameter arm_id");
32 if (!node_handle.
getParam(
"joint_names", joint_names) || joint_names.size() != 7) {
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) {
79 joint_handles_.push_back(effort_joint_interface->getHandle(joint_names[i]));
82 "CartesianImpedanceExampleController: Exception getting joint handles: " << ex.
what());
91 dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>>(
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()));
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(
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());
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.linear() * 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) {
201 const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
202 const Eigen::Matrix<double, 7, 1>& tau_J_d) {
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];
209 return tau_d_saturated;
213 franka_example_controllers::compliance_paramConfig& config,
217 << config.translational_stiffness * Eigen::Matrix3d::Identity();
219 << config.rotational_stiffness * Eigen::Matrix3d::Identity();
223 << 2.0 * sqrt(config.translational_stiffness) * Eigen::Matrix3d::Identity();
225 << 2.0 * sqrt(config.rotational_stiffness) * Eigen::Matrix3d::Identity();
230 const geometry_msgs::PoseStampedConstPtr& msg) {
231 position_d_target_ << msg->pose.position.x, msg->pose.position.y, msg->pose.position.z;
234 msg->pose.orientation.z, msg->pose.orientation.w;
virtual const char * what() const
ros::NodeHandle dynamic_reconfigure_compliance_param_node_
void pseudoInverse(const Eigen::MatrixXd &M_, Eigen::MatrixXd &M_pinv_, bool damped=true)
std::unique_ptr< franka_hw::FrankaStateHandle > state_handle_
ros::Subscriber sub_equilibrium_pose_
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::compliance_paramConfig > > dynamic_server_compliance_param_
void equilibriumPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
void starting(const ros::Time &) override
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
Eigen::Vector3d position_d_target_
Eigen::Matrix< double, 7, 1 > q_d_nullspace_
Eigen::Matrix< double, 6, 6 > cartesian_damping_target_
double nullspace_stiffness_target_
std::array< std::string, 7 > joint_names
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
std::array< double, 7 > q
Eigen::Quaterniond orientation_d_target_
Eigen::Quaterniond orientation_d_
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
double nullspace_stiffness_
const double delta_tau_max_
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_
std::array< double, 16 > O_T_EE
Eigen::Matrix< double, 6, 6 > cartesian_damping_
Eigen::Vector3d position_d_
void complianceParamCallback(franka_example_controllers::compliance_paramConfig &config, uint32_t level)
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_target_
std::array< double, 7 > tau_J_d
bool getParam(const std::string &key, std::string &s) const
std::unique_ptr< franka_hw::FrankaModelHandle > model_handle_
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_ERROR_STREAM(args)
std::vector< hardware_interface::JointHandle > joint_handles_