rs_opw_kinematics::urdf

Function from_urdf_file

Source
pub fn from_urdf_file<P: AsRef<Path>>(path: P) -> OPWKinematics
Expand description

Simplified reading from URDF file. This function assumes sorting of results by closest to previous (BY_PREV) and no joint offsets (zero offsets). URDF file is expected in the input but XACRO file may also work. Robot joints must be named joint1 to joint6 in the file (as macro prefix, underscore and non-word chars is dropped, it can also be something like ${prefix}JOINT_1). It may be more than one robot described in URDF file but they must all be identical.

§Parameters

  • path: the location of URDF or XACRO file to load from.

§Returns

  • Returns an instance of OPWKinematics, which contains the kinematic parameters extracted from the specified URDF file, including constraints as defined there.

§Example

let kinematics = rs_opw_kinematics::urdf::from_urdf_file("src/tests/data/fanuc/m6ib_macro.xacro");
println!("{:?}", kinematics);

§Errors

  • The function might panic if the file cannot be found, is not accessible, or is incorrectly formatted. Users should ensure the file path is correct and the file is properly formatted as URDF or XACRO file.