formatting

This commit is contained in:
Sharwin24 2025-02-25 11:26:08 -06:00
parent eba2bdbbc6
commit 524ed7ec09

View file

@ -29,7 +29,13 @@ The forward and inverse kinematics were then implemented in C++ following the ap
<div>
<details>
<summary>Forward and Inverse Kinematics C++ Implementation</summary>
```cpp
// this->AL = Active Link Length [mm]
// this->PL = Passive Link Length [mm]
// this->SB = Base Side Length [mm]
// this->SP = Platform (EE) Side Length [mm]
void DeltaKinematics::forwardKinematics(const std::shared_ptr<DeltaFK::Request> request, std::shared_ptr<DeltaFK::Response> response) {
// Locally save the request data (joint angles)
float theta1 = request->joint_angles.theta1;
@ -83,7 +89,7 @@ void DeltaKinematics::forwardKinematics(const std::shared_ptr<DeltaFK::Request>
}
int DeltaKinematics::deltaFK_AngleYZ(float x0, float y0, float z0, float& theta) {
float y1 = -0.5 * tan30 * SB; // Half base * tan(30)
float y1 = -0.5 * tan30 * this->SB; // Half base * tan(30)
y0 -= 0.5 * tan30 * this->SP; // shift center to edge
// z = a + b*y
float a = (x0 * x0 + y0 * y0 + z0 * z0 + this->AL * this->AL - this->PL * this->PL - y1 * y1) / (2 * z0);
@ -124,6 +130,7 @@ void DeltaKinematics::inverseKinematics(const std::shared_ptr<DeltaIK::Request>
response->joint_angles.theta3 = theta3; // [rad]
}
```
</details>
</div>