Skip to content

Commit

Permalink
1.4.0 (#7)
Browse files Browse the repository at this point in the history
  • Loading branch information
bourumir-wyngs authored Jun 24, 2024
1 parent 5e06989 commit 24b5bff
Show file tree
Hide file tree
Showing 8 changed files with 548 additions and 27 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@
.idea

/src/tests/data/tmp/
/amb/
10 changes: 5 additions & 5 deletions Cargo.lock

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

8 changes: 4 additions & 4 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.2"
version = "1.4.0"
edition = "2021"
authors = ["Bourumir Wyngs <[email protected]>"]
description = "Inverse and forward kinematics for 6 axis robots with a parallel base and spherical wrist."
Expand All @@ -16,20 +16,20 @@ readme = "README.md"
maintenance = { status = "actively-developed" }

[dependencies]
nalgebra = "0.32.5"
nalgebra = "0.32.6"

# Others are only needed to read YAML or convert from URDF
yaml-rust2 = { version = "0.8.1", optional = true }
sxd-document = { version = "0.3", optional = true }
regex = { version = "1.10.4", optional = true }
regex = { version = "1.10.5", optional = true }
clap = { version = "4.5.4", features = ["derive"], optional = true }

[features]
default = ["allow_filesystem"]
allow_filesystem = ["yaml-rust2", "sxd-document", "regex", "clap"]

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

[dev-dependencies]
rand = "0.8.5"
Expand Down
30 changes: 20 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ the ground at "zero."

# Constraints

Since 1.1.0, it is possible to set [constraints](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/constraints/index.html) for the joints. Robot poses where any of the joints are outside
Since 1.1.0, it is possible to set [constraints](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/constraints/index.html) for the joints. Robot poses where any of the joints are outside
the specified constraint range are not included into returned list of solutions. It is also possible to
influence the sorting of the result list by giving some preference to the center of constraints.

Expand All @@ -81,10 +81,10 @@ Constraints are tested for the range from -2&pi; to 2&pi;, but as angles repeat
constraint from -&pi; to &pi; already permits free rotation, covering any angle.

# Jacobian: torgues and velocities
Since 1.3.2, it is possible to obtain the [Jacobian](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/jacobian/struct.Jacobian.html) that represents the relationship between the joint velocities
Since 1.3.2, it is possible to obtain the [Jacobian](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/jacobian/struct.Jacobian.html) that represents the relationship between the joint velocities
and the end-effector velocities. The computed Jacobian object provides:
- Joint [velocities](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/jacobian/struct.Jacobian.html#method.velocities) required to achieve a desired end-effector velocity.
- Joint [torques](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/jacobian/struct.Jacobian.html#method.torques) required to achieve a desired end-effector force/torque.
- Joint [velocities](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/jacobian/struct.Jacobian.html#method.velocities) required to achieve a desired end-effector velocity.
- Joint [torques](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/jacobian/struct.Jacobian.html#method.torques) required to achieve a desired end-effector force/torque.

The same Joints structure is reused, the six values now representing either angular velocities in radians per second
or torgues in Newton meters. For the end effector, it is possible to use either nalgebra::[Isometry3](https://docs.rs/nalgebra/latest/nalgebra/geometry/type.Isometry3.html)
Expand All @@ -94,22 +94,32 @@ These values are useful when path planning for a robot that needs to move very s
overspeed or overtorgue of individual joints.

# The tool and the base
Since 1.3.2, robot can be equipped with the [tool](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/tool/struct.Tool.html), defined as nalgebra::[Isometry3](https://docs.rs/nalgebra/latest/nalgebra/geometry/type.Isometry3.html). The tool isometry defines both
Since 1.3.2, robot can be equipped with the [tool](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/tool/struct.Tool.html), defined as nalgebra::[Isometry3](https://docs.rs/nalgebra/latest/nalgebra/geometry/type.Isometry3.html). The tool isometry defines both
additional translation and additional rotation. The "pose" as defined in forward and inverse kinematics
now becomes the pose of the tool center point, not any part of the robot. The robot can also be placed
on a [base](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/tool/struct.Base.html), further supporting the conditions much closer to the real industrial environment.
on a [base](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/tool/struct.Base.html), further supporting the conditions much closer to the real industrial environment.

"Robot with the tool" and "Robot on the base" can be constructed around any [Kinematics](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/kinematic_traits/trait.Kinematics.html) trait, and implement
"Robot with the tool" and "Robot on the base" can be constructed around any [Kinematics](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/kinematic_traits/trait.Kinematics.html) trait, and implement
this trait themselves. It is possible to cascade them, constructing a robot on a base and with the tool (or
two tools if the first is a receptacle of the tool changer).

# The frame
Since 1.4.0 this package supports the frame transform that allows to transform the robot trajectory (in terms of joint angles)
prepared for one location to make the same kind of movements in another location (translated and rotated).
Frame in robotics is most commonly defined by the 3 pairs of points (to and from) if the transform includes
also rotation, or just a single pair is enough if only shift (but not a rotation) is involved.

Once constructed by specifying original and transformed points, the Frame object can take "canonical" joint angles
and calculated joint angles for the transformed (shifted and rotated) trajector. See the
[frame](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/frame/index.html) documentation for details.

# Example

Cargo.toml:

```toml
[dependencies]
rs-opw-kinematics = ">=1.3.2, <2.0.0"
rs-opw-kinematics = ">=1.4.0, <2.0.0"
```

main.rs:
Expand Down Expand Up @@ -257,7 +267,7 @@ Since version 1.2.0, parameters and constraints can also be directly extracted f
println!("Reading:\n{}", &parameters.to_yaml());
```

There is also more advanced function [rs_opw_kinematics::urdf::from_urdf](https://docs.rs/rs-opw-kinematics/1.3.2/rs_opw_kinematics/urdf/fn.from_urdf.html)
There is also more advanced function [rs_opw_kinematics::urdf::from_urdf](https://docs.rs/rs-opw-kinematics/1.4.0/rs_opw_kinematics/urdf/fn.from_urdf.html)
that takes URDF string rather than the file, provides error handling and much more control over how the solver
is constructed from the extracted values.

Expand All @@ -270,7 +280,7 @@ values. In general, always test in simulator before feeding the output of any so
For security and performance, some users prefer smaller libraries with less dependencies. If YAML and URDF readers
are not in use, the filesystem access can be completely disabled in your Cargo.toml, importing the library like:

rs-opw-kinematics = { version = ">=1.3.2, <2.0.0", default-features = false }
rs-opw-kinematics = { version = ">=1.4.0, <2.0.0", default-features = false }

In this case, import of URDF and YAML files will be unaccessible, and used dependencies
will be limited to the single _nalgebra_ crate.
Expand Down
35 changes: 35 additions & 0 deletions examples/frame.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
use rs_opw_kinematics::utils::{dump_joints, dump_solutions};
use std::sync::Arc;
use nalgebra::Point3;
use rs_opw_kinematics::frame::Frame;
use rs_opw_kinematics::kinematic_traits::Kinematics;
use rs_opw_kinematics::kinematics_impl::OPWKinematics;
use rs_opw_kinematics::parameters::opw_kinematics::Parameters;

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);
}
Loading

0 comments on commit 24b5bff

Please sign in to comment.