openarm_teleop/src/controller/dynamics.hpp

73 lines
2.3 KiB
C++
Raw Normal View History

2025-07-23 06:33:37 +00:00
// Copyright 2025 Enactic, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include <string.h>
2025-10-01 07:59:19 +00:00
#include <unistd.h>
#include <urdf_parser/urdf_parser.h>
#include <Eigen/Dense>
#include <fstream>
#include <iostream>
2025-07-23 06:33:37 +00:00
#include <kdl/chain.hpp>
#include <kdl/chaindynparam.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/chainjnttojacsolver.hpp>
2025-10-01 07:59:19 +00:00
#include <kdl_parser/kdl_parser.hpp>
2025-07-23 06:33:37 +00:00
#include <sstream>
2025-10-01 07:59:19 +00:00
#include <vector>
2025-07-23 06:33:37 +00:00
/*
* Compute gravity and inertia compensation using Orocos
* Kinematics and Dynamics Library (KDL).
*/
2025-10-01 07:59:19 +00:00
class Dynamics {
private:
std::shared_ptr<urdf::ModelInterface> urdf_model_interface;
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
std::string urdf_path;
std::string start_link;
std::string end_link;
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
KDL::JntSpaceInertiaMatrix inertia_matrix;
KDL::JntArray q;
KDL::JntArray q_d;
KDL::JntArray coriolis_forces;
KDL::JntArray gravity_forces;
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
KDL::JntArray biasangle;
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
KDL::Tree kdl_tree;
KDL::Chain kdl_chain;
std::unique_ptr<KDL::ChainDynParam> solver;
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
public:
Dynamics(std::string urdf_path, std::string start_link, std::string end_link);
~Dynamics();
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
bool Init();
void GetGravity(const double *motor_position, double *gravity);
void GetCoriolis(const double *motor_position, const double *motor_velocity, double *coriolis);
void GetMassMatrixDiagonal(const double *motor_position, double *inertia_diag);
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
void GetJacobian(const double *motor_position, Eigen::MatrixXd &jacobian);
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
void GetNullSpace(const double *motor_positon, Eigen::MatrixXd &nullspace);
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
void GetNullSpaceTauSpace(const double *motor_position, Eigen::MatrixXd &nullspace_T);
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
void GetEECordinate(const double *motor_position, Eigen::Matrix3d &R, Eigen::Vector3d &p);
2025-07-23 06:33:37 +00:00
2025-10-01 07:59:19 +00:00
void GetPreEECordinate(const double *motor_position, Eigen::Matrix3d &R, Eigen::Vector3d &p);
2025-07-23 06:33:37 +00:00
};