-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathjacobian.rs
63 lines (53 loc) · 2.36 KB
/
jacobian.rs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
use std::f64::consts::PI;
use std::sync::Arc;
use nalgebra::{Isometry3, Translation3, UnitQuaternion, Vector3};
use rs_opw_kinematics::kinematic_traits::{Joints, Kinematics, Pose};
use rs_opw_kinematics::kinematics_impl::OPWKinematics;
use rs_opw_kinematics::parameters::opw_kinematics::Parameters;
use rs_opw_kinematics::constraints::{BY_CONSTRAINS, Constraints};
/// Calculating Jacobian matrices for kinematic analysis.
fn main() {
let robot = OPWKinematics::new_with_constraints(
Parameters::irb2400_10(), Constraints::new(
[-0.1, 0.0, 0.0, 0.0, -PI, -PI],
[PI, PI, 2.0 * PI, PI, PI, PI],
BY_CONSTRAINS,
));
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5]; // Joints are alias of [f64; 6]
let jakobian = rs_opw_kinematics::jacobian::Jacobian::new(&robot, &joints, 1E-6);
let desired_velocity_isometry =
Isometry3::new(Vector3::new(0.0, 1.0, 0.0),
Vector3::new(0.0, 0.0, 1.0));
let joint_velocities = jakobian.velocities(&desired_velocity_isometry);
println!("Computed joint velocities: {:?}", joint_velocities.unwrap());
let desired_force_torque =
Isometry3::new(Vector3::new(0.0, 0.0, 0.0),
Vector3::new(0.0, 0.0, 1.234));
let joint_torques = jakobian.torques(&desired_force_torque);
println!("Computed joint torques: {:?}", joint_torques);
// Robot with the tool, standing on a base:
let robot_alone = OPWKinematics::new(Parameters::staubli_tx2_160l());
// 1 meter high pedestal
let pedestal = 0.5;
let base_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, pedestal).into(),
UnitQuaternion::identity(),
);
let robot_with_base = rs_opw_kinematics::tool::Base {
robot: Arc::new(robot_alone),
base: base_translation,
};
// Tool extends 1 meter in the Z direction, envisioning something like sword
let sword = 1.0;
let tool_translation = Isometry3::from_parts(
Translation3::new(0.0, 0.0, sword).into(),
UnitQuaternion::identity(),
);
// Create the Tool instance with the transformation
let robot_complete = rs_opw_kinematics::tool::Tool {
robot: Arc::new(robot_with_base),
tool: tool_translation,
};
let tcp_pose: Pose = robot_complete.forward(&joints);
println!("The sword tip is at: {:?}", tcp_pose);
}