rs_opw_kinematics

Module visualization

Source
Expand description

Provides visualization window with sliders for angles and pose.

screenshot

The crate::kinematics_with_shape::KinematicsWithShape structure fully integrates kinematics with 3D meshes representing the robot, making it straightforward to visualize. To display the robot, simply pass this structure to the built-in function visualize_robot.

fn main() {
    use std::ops::RangeInclusive;
    use rs_opw_kinematics::kinematics_with_shape::KinematicsWithShape;
    use rs_opw_kinematics::visualization;

    // See `complete_visible_robot example` how to build this structure
    let robot: KinematicsWithShape = ...

    // Define the initial joint angles to display the robot in a specific position
    let initial_angles = [173., -8., -94., 6., 83., 207.];

    // Define boundaries for XYZ drawbars in the visualization GUI
    let tcp_box: [RangeInclusive<f64>; 3] = [-2.0..=2.0, -2.0..=2.0, 1.0..=2.0];

    visualization::visualize_robot(robot, initial_angles, tcp_box);
}

§Purpose

Visualization serves as a verification tool to ensure that parameters, meshes, tool, and base setup are correct, rather than as a production feature. Using Bevy, this visualization displays the robot (mounted on its base and equipped with the tool), various environment objects, and manipulable handles for the robot.

§Features

In the visualization window, joint positions can be adjusted for forward kinematics, or the tool center point can be set using Cartesian coordinates for inverse kinematics.

  • Collision Detection: Active in both kinematics modes but functions differently:
    • Inverse Kinematics: Movement is restricted to avoid collisions entirely (the robot will not move if a collision would occur).
    • Forward Kinematics: Collisions are permitted, but colliding robot joints and environment objects are highlighted.

Functions§

visualize_robot
Visualize the given robot, starting from the given initial angles (given in degrees) The sliders for specifying the tool center point location with take the boundaries from the tcp_box (given in meters). Bevy will be used for visualization.
visualize_robot_with_safety