From 9186600f7c433f3aedfa6ed32e2e08701e0d94dc Mon Sep 17 00:00:00 2001 From: Bourumir Wyngs Date: Fri, 31 May 2024 23:25:14 +0200 Subject: [PATCH] Moving towards 1.3.2 --- Cargo.lock | 2 +- Cargo.toml | 4 ++-- README.md | 18 +++++++++--------- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index 2e7868f..b120653 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -404,7 +404,7 @@ checksum = "adad44e29e4c806119491a7f06f03de4d1af22c3a680dd47f1e6e179439d1f56" [[package]] name = "rs-opw-kinematics" -version = "1.3.1" +version = "1.3.2" dependencies = [ "clap", "nalgebra", diff --git a/Cargo.toml b/Cargo.toml index c09e06f..0da85eb 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,6 +1,6 @@ [package] name = "rs-opw-kinematics" -version = "1.3.1" +version = "1.3.2" edition = "2021" authors = ["Bourumir Wyngs "] description = "Inverse and forward kinematics for 6 axis robots with a parallel base and spherical wrist." @@ -29,7 +29,7 @@ default = ["allow_filesystem"] allow_filesystem = ["yaml-rust2", "sxd-document", "regex", "clap"] # To disable filesystem: -#rs-opw-kinematics = { version = "1.3.1", default-features = false } +#rs-opw-kinematics = { version = "1.3.2", default-features = false } [dev-dependencies] rand = "0.8.5" diff --git a/README.md b/README.md index d6a2aa8..949ef6a 100644 --- a/README.md +++ b/README.md @@ -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.1/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.3.2/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. @@ -81,10 +81,10 @@ Constraints are tested for the range from -2π to 2π, but as angles repeat constraint from -π to π already permits free rotation, covering any angle. # Jacobian: torgues and velocities -Since 1.3.1, it is possible to obtain the [Jacobian](https://docs.rs/rs-opw-kinematics/1.3.1/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.3.2/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.1/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.1/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.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. 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) @@ -94,10 +94,10 @@ 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.1, robot can be equipped with the [tool](https://docs.rs/rs-opw-kinematics/1.3.1/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.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 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.1/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.3.2/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 trait, and implement the Kinematics trait themselves. It is possible to cascade them. @@ -108,7 +108,7 @@ Cargo.toml: ```toml [dependencies] -rs-opw-kinematics = ">=1.3.1, <2.0.0" +rs-opw-kinematics = ">=1.3.2, <2.0.0" ``` main.rs: @@ -256,7 +256,7 @@ Since version 1.2.0, parameters and constraints can also be directly extracted f println!("Reading:\n{}", ¶meters.to_yaml()); ``` -There is also more advanced function [rs_opw_kinematics::urdf::from_urdf](https://docs.rs/rs-opw-kinematics/1.3.1/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.3.2/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. @@ -269,7 +269,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.1, <2.0.0", default-features = false } +rs-opw-kinematics = { version = ">=1.3.2, <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.