quadruped_ros2_control/controllers/unitree_guide_controller/src/robot/QuadrupedRobot.cpp

102 lines
3.6 KiB
C++
Raw Normal View History

2024-09-12 13:56:51 +08:00
//
// Created by biao on 24-9-12.
//
2024-09-12 20:04:20 +08:00
#include <iostream>
2024-09-14 17:54:39 +08:00
#include "unitree_guide_controller/control/CtrlComponent.h"
#include "unitree_guide_controller/robot/QuadrupedRobot.h"
2024-09-12 13:56:51 +08:00
2024-09-12 20:04:20 +08:00
void QuadrupedRobot::init(const std::string &robot_description) {
2024-09-12 13:56:51 +08:00
KDL::Tree robot_tree;
kdl_parser::treeFromString(robot_description, robot_tree);
robot_tree.getChain("base", "FR_foot", fr_chain_);
robot_tree.getChain("base", "FL_foot", fl_chain_);
robot_tree.getChain("base", "RR_foot", rr_chain_);
robot_tree.getChain("base", "RL_foot", rl_chain_);
2024-09-12 20:04:20 +08:00
robot_legs_.resize(4);
robot_legs_[0] = std::make_shared<RobotLeg>(fr_chain_);
robot_legs_[1] = std::make_shared<RobotLeg>(fl_chain_);
robot_legs_[2] = std::make_shared<RobotLeg>(rr_chain_);
robot_legs_[3] = std::make_shared<RobotLeg>(rl_chain_);
2024-09-13 15:00:20 +08:00
current_joint_pos_.resize(4);
current_joint_vel_.resize(4);
2024-09-12 20:04:20 +08:00
std::cout << "robot_legs_.size(): " << robot_legs_.size() << std::endl;
2024-09-12 13:56:51 +08:00
// calculate total mass from urdf
2024-09-12 20:04:20 +08:00
mass_ = 0;
2024-09-12 13:56:51 +08:00
for (const auto &[fst, snd]: robot_tree.getSegments()) {
2024-09-12 20:04:20 +08:00
mass_ += snd.segment.getInertia().getMass();
2024-09-12 13:56:51 +08:00
}
}
2024-09-13 15:00:20 +08:00
std::vector<KDL::JntArray> QuadrupedRobot::getQ(const std::vector<KDL::Frame> &pEe_list) const {
2024-09-12 13:56:51 +08:00
std::vector<KDL::JntArray> result;
result.resize(4);
for (int i(0); i < 4; ++i) {
2024-09-13 15:00:20 +08:00
result[i] = robot_legs_[i]->calcQ(pEe_list[i], current_joint_pos_[i]);
2024-09-12 13:56:51 +08:00
}
return result;
}
2024-09-16 21:15:34 +08:00
std::vector<KDL::Frame> QuadrupedRobot::getFeet2BPositions() const {
2024-09-12 13:56:51 +08:00
std::vector<KDL::Frame> result;
result.resize(4);
2024-09-12 20:04:20 +08:00
for (int i = 0; i < 4; i++) {
2024-09-16 21:15:34 +08:00
result[i] = robot_legs_[i]->calcPEe2B(current_joint_pos_[i]);
2024-09-12 13:56:51 +08:00
}
return result;
}
2024-09-12 20:04:20 +08:00
2024-09-13 15:00:20 +08:00
KDL::Frame QuadrupedRobot::getFeet2BPositions(const int index) const {
return robot_legs_[index]->calcPEe2B(current_joint_pos_[index]);
}
KDL::Jacobian QuadrupedRobot::getJacobian(const int index) const {
return robot_legs_[index]->calcJaco(current_joint_pos_[index]);
2024-09-12 20:04:20 +08:00
}
2024-09-13 15:00:20 +08:00
KDL::JntArray QuadrupedRobot::getTorque(
2024-09-17 18:21:04 +08:00
const Vec3 &force, const int index) const {
2024-09-17 14:03:08 +08:00
return robot_legs_[index]->calcTorque(current_joint_pos_[index], force);
2024-09-12 20:04:20 +08:00
}
2024-09-17 18:21:04 +08:00
KDL::JntArray QuadrupedRobot::getTorque(const KDL::Vector &force, int index) const {
return robot_legs_[index]->calcTorque(current_joint_pos_[index], Vec3(force.data));
}
2024-09-16 13:44:08 +08:00
KDL::Vector QuadrupedRobot::getFeet2BVelocities(const int index) const {
const Eigen::Matrix<double, 3, Eigen::Dynamic> jacobian = getJacobian(index).data.topRows(3);
Eigen::VectorXd foot_velocity = jacobian * current_joint_vel_[index].data;
return {foot_velocity(0), foot_velocity(1), foot_velocity(2)};
}
std::vector<KDL::Vector> QuadrupedRobot::getFeet2BVelocities() const {
std::vector<KDL::Vector> result;
result.resize(4);
for (int i = 0; i < 4; i++) {
result[i] = getFeet2BVelocities(i);
}
return result;
}
2024-09-13 15:00:20 +08:00
void QuadrupedRobot::update(const CtrlComponent &ctrlComp) {
2024-09-16 21:15:34 +08:00
if (mass_ == 0) return;
2024-09-13 15:00:20 +08:00
for (int i = 0; i < 4; i++) {
KDL::JntArray pos_array(3);
pos_array(0) = ctrlComp.joint_position_state_interface_[i * 3].get().get_value();
pos_array(1) = ctrlComp.joint_position_state_interface_[i * 3 + 1].get().get_value();
pos_array(2) = ctrlComp.joint_position_state_interface_[i * 3 + 2].get().get_value();
current_joint_pos_[i] = pos_array;
KDL::JntArray vel_array(3);
vel_array(0) = ctrlComp.joint_velocity_state_interface_[i * 3].get().get_value();
vel_array(1) = ctrlComp.joint_velocity_state_interface_[i * 3 + 1].get().get_value();
vel_array(2) = ctrlComp.joint_velocity_state_interface_[i * 3 + 2].get().get_value();
current_joint_vel_[i] = vel_array;
}
2024-09-12 20:04:20 +08:00
}