Skip to content

Commit

Permalink
Improving basic examples
Browse files Browse the repository at this point in the history
  • Loading branch information
bourumir-wyngs committed Dec 14, 2024
1 parent f14fe8f commit d8e7b04
Show file tree
Hide file tree
Showing 4 changed files with 53 additions and 21 deletions.
4 changes: 2 additions & 2 deletions Cargo.lock

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

6 changes: 3 additions & 3 deletions Cargo.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
name = "rs-opw-kinematics"
version = "1.3.3"
version = "1.3.4"
edition = "2021"
authors = ["Bourumir Wyngs <bourumir.wyngs@gmail.com>"]
description = "Inverse and forward kinematics for 6 axis robots with a parallel base and spherical wrist."
Expand All @@ -19,7 +19,7 @@ maintenance = { status = "actively-developed" }
nalgebra = ">=0.32.1, <=0.33.2"# All versions in the range confirmed to work

# Others are only needed to read YAML or convert from URDF
yaml-rust2 = { version = "0.8.0", optional = true }
yaml-rust2 = { version = ">=0.8.0, <=0.9.0", optional = true }
sxd-document = { version = "0.3", optional = true }
regex = { version = "1.10.4", optional = true }
clap = { version = "4.5.4", features = ["derive"], optional = true }
Expand All @@ -29,7 +29,7 @@ default = ["allow_filesystem"]
allow_filesystem = ["yaml-rust2", "sxd-document", "regex", "clap"]

# To disable filesystem:
#rs-opw-kinematics = { version = "1.3.3", default-features = false }
#rs-opw-kinematics = { version = "1.3.4", default-features = false }

[dev-dependencies]
rand = "0.8.5"
Expand Down
39 changes: 28 additions & 11 deletions examples/constraints.rs
Original file line number Diff line number Diff line change
@@ -1,25 +1,40 @@
use std::f64::consts::PI;
use rs_opw_kinematics::constraints::{Constraints, BY_CONSTRAINS, BY_PREV};
use rs_opw_kinematics::kinematic_traits::{Joints, Kinematics, Pose, CONSTRAINT_CENTERED};
use rs_opw_kinematics::kinematics_impl::OPWKinematics;
use rs_opw_kinematics::parameters::opw_kinematics::Parameters;
use rs_opw_kinematics::utils::{dump_solutions};
use rs_opw_kinematics::constraints::{BY_CONSTRAINS, BY_PREV, Constraints};
use rs_opw_kinematics::utils::dump_solutions;
use std::f64::consts::PI;

fn main() {
// Create robot specifying parameters. This is ABB IRB 4600 industrial arm:
let robot = OPWKinematics::new_with_constraints(
Parameters::irb2400_10(), Constraints::new(
Parameters {
a1: 0.175,
a2: -0.175,
b: 0.000,
c1: 0.495,
c2: 0.900,
c3: 0.960,
c4: 0.135,
offsets: [0.0, 0.0, -180.0_f64.to_radians(), 0.0, 0.0, 0.0],
sign_corrections: [1; 6],
},
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>
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.");
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);

Expand All @@ -28,12 +43,14 @@ fn main() {
dump_solutions(&solutions);

let robot = OPWKinematics::new_with_constraints(
Parameters::irb2400_10(), Constraints::new(
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);
}
}
25 changes: 20 additions & 5 deletions examples/basic.rs → examples/minimal_example.rs
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,21 @@ use rs_opw_kinematics::parameters::opw_kinematics::Parameters;
use rs_opw_kinematics::utils::{dump_joints, dump_solutions};

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]
// Create robot specifying parameters. This is ABB IRB 4600 industrial arm:
let robot = OPWKinematics::new(Parameters {
a1: 0.175,
a2: -0.175,
b: 0.000,
c1: 0.495,
c2: 0.900,
c3: 0.960,
c4: 0.135,
offsets: [0.0, 0.0, -180.0_f64.to_radians(), 0.0, 0.0, 0.0],
sign_corrections: [1; 6]
});

// Joints are alias of [f64; 6], values in radians
let joints: Joints = [0.0, 0.1, 0.2, 0.3, 0.0, 0.5];
println!("Initial joints with singularity J5 = 0: ");
dump_joints(&joints);

Expand All @@ -25,8 +38,10 @@ fn main() {
let solutions = robot.inverse_continuing(&pose, &when_continuing_from_j6_0);
dump_solutions(&solutions);

println!("If 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.");
println!(
"If 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);
}
}

0 comments on commit d8e7b04

Please sign in to comment.