rs_opw_kinematics::visualization

Function visualize_robot

Source
pub fn visualize_robot(
    robot: KinematicsWithShape,
    intial_angles: [f32; 6],
    tcp_box: [RangeInclusive<f64>; 3],
)
Expand description

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.

Examples found in repository?
examples/complete_visible_robot.rs (line 170)
164
165
166
167
168
169
170
171
fn visualize(
    robot: KinematicsWithShape,
    initial_angles: [f32; 6],
    tcp_box: [RangeInclusive<f64>; 3],
) {
    use rs_opw_kinematics::visualization;
    visualization::visualize_robot(robot, initial_angles, tcp_box);
}