pub fn dump_solutions(solutions: &Solutions)
Expand description
Print joint values for all solutions, converting radianst to degrees.
Examples found in repository?
examples/complete_visible_robot.rs (line 143)
135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156
fn main() {
// The robot itself.
let robot = create_rx160_robot();
// Do some inverse kinematics to show the concept.
let pose = Isometry3::from_parts(Translation3::new(0.0, 0.0, 1.5), UnitQuaternion::identity());
let solutions = robot.inverse(&pose);
dump_solutions(&solutions);
if robot.collides(&[173_f64.to_radians(), 0., -94_f64.to_radians(), 0., 0., 0.]) {
println!("Collision detected");
}
// In which position to show the robot on startup
let initial_angles = [173., -8., -94., 6., 83., 207.];
// Boundaries for XYZ draw-bars in visualization GUI
let tcp_box: [RangeInclusive<f64>; 3] = [-2.0..=2.0, -2.0..=2.0, 1.0..=2.0];
visualize(robot, initial_angles, tcp_box);
}
More examples
examples/frame.rs (line 29)
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
fn main() {
let robot = OPWKinematics::new(Parameters::irb2400_10());
// Shift not too much to have values close to previous
let frame_transform = Frame::translation(
Point3::new(0.0, 0.0, 0.0),
Point3::new(0.011, 0.022, 0.033));
let framed = Frame {
robot: Arc::new(robot),
frame: frame_transform,
};
let joints_no_frame: [f64; 6] = [0.0, 0.11, 0.22, 0.3, 0.1, 0.5]; // without frame
println!("No frame transform:");
dump_joints(&joints_no_frame);
println!("Possible joint values after the frame transform:");
let (solutions, _transformed_pose) = framed.forward_transformed(
&joints_no_frame, &joints_no_frame);
dump_solutions(&solutions);
let framed = robot.forward(&solutions[0]).translation;
let unframed = robot.forward(&joints_no_frame).translation;
println!("Distance between framed and not framed pose {:.3} {:.3} {:.3}",
framed.x - unframed.x, framed.y - unframed.y, framed.z - unframed.z);
}
examples/constraints.rs (line 24)
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
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_PREV,
));
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5]; // Joints are alias of [f64; 6]
let when_continuing_from_j6_0: [f64; 6] = [0.0, 0.11, 0.22, 0.8, 0.1, 0.0];
let pose: Pose = robot.forward(&joints); // Pose is alias of nalgebra::Isometry3<f64>
println!("If we do not have the previous pose yet, we can now ask to prever the pose \
closer to the center of constraints.");
let solutions = robot.inverse_continuing(&pose, &CONSTRAINT_CENTERED);
dump_solutions(&solutions);
println!("With constraints, sorted by proximity to the previous pose");
let solutions = robot.inverse_continuing(&pose, &when_continuing_from_j6_0);
dump_solutions(&solutions);
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,
));
println!("With constraints, sorted by proximity to the center of constraints");
let solutions = robot.inverse_continuing(&pose, &when_continuing_from_j6_0);
dump_solutions(&solutions);
}
examples/tool_and_base.rs (line 45)
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
fn main() {
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.4, 0.5]; // Joints are alias of [f64; 6]
dump_joints(&joints);
// 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_on_base_with_tool = rs_opw_kinematics::tool::Tool {
robot: Arc::new(robot_with_base),
tool: tool_translation,
};
let tcp_pose: Pose = robot_on_base_with_tool.forward(&joints);
println!("The sword tip is at: {:?}", tcp_pose);
// robot_complete implements Kinematics so have the usual inverse kinematics methods available.
let inverse = robot_on_base_with_tool.inverse_continuing(&tcp_pose, &joints);
dump_solutions(&inverse);
}
examples/basic.rs (line 17)
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
fn main() {
let robot = OPWKinematics::new(Parameters::irb2400_10());
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5]; // Joints are alias of [f64; 6]
println!("\nInitial joints with singularity J5 = 0: ");
dump_joints(&joints);
println!("\nSolutions (original angle set is lacking due singularity there: ");
let pose: Pose = robot.forward(&joints); // Pose is alias of nalgebra::Isometry3<f64>
let solutions = robot.inverse(&pose); // Solutions is alias of Vec<Joints>
dump_solutions(&solutions);
println!("\nSolutions assuming we continue from somewhere close. The 'lost solution' returns");
let when_continuing_from: [f64; 6] = [0.0, 0.11, 0.22, 0.3, 0.1, 0.5];
let solutions = robot.inverse_continuing(&pose, &when_continuing_from);
dump_solutions(&solutions);
println!("\nSame pose, all J4+J6 rotation assumed to be previously concentrated on J4 only");
let when_continuing_from_j6_0: [f64; 6] = [0.0, 0.11, 0.22, 0.8, 0.1, 0.0];
let solutions = robot.inverse_continuing(&pose, &when_continuing_from_j6_0);
dump_solutions(&solutions);
println!("\nIf we do not have the previous position, we can assume we want J4, J6 close to 0.0 \
The solution appears and the needed rotation is now equally distributed between J4 and J6.");
let solutions = robot.inverse_continuing(&pose, &JOINTS_AT_ZERO);
dump_solutions(&solutions);
println!("\n5 DOF, J6 at fixed angle 77 degrees");
let solutions5dof = robot.inverse_5dof(&pose, 77.0_f64.to_radians());
dump_solutions(&solutions5dof);
println!("The XYZ location of TCP is still as in the original pose x = {:.3}, y = {:.3}, z = {:.3}:",
pose.translation.x, pose.translation.y, pose.translation.z);
for solution in &solutions {
let translation = robot.forward(solution).translation;
println!("Translation: x = {:.3}, y = {:.3}, z = {:.3}", translation.x, translation.y, translation.z);
}
}