Loading a Robot Model
In this tutorial, we will cover how to load a robot model into Optima. The code for this example is as follows:
extern crate optima; use optima::robot_modules::robot::Robot; use optima::utils::utils_robot::robot_module_utils::RobotNames; fn main () { // load the given robot let robot = Robot::new_from_names(RobotNames::new("ur5", None)); // prints a summary of the robot configuration robot.robot_configuration_module().print_summary(); // prints a summary of the robot's degrees of freedom robot.robot_joint_state_module().print_dof_summary(); }
Let's take a look through the code. The important part of this code is line 8 where the ur5 robot model is loaded. The easiest way to load a robot is using the new_from_names
function. This function takes a RobotNames
parameter, which has two parameters of its own. The first parameter here is the name of the robot ("ur5"
in this case). This string literal parameter could be any robot in the directory optima_toolbox/optima_assets/optima_robots
. The second parameter is a Rust Option that can, as the name implies, serve as an optional string parameter specifying the name of a robot configuration. Robot configurations will be covered in a following section, so in this case, the configuration is specifies as None
, meaning the loaded robot model will simply be its base configuration.
A Robot
in Optima is a large struct that aggregates smaller structs that contain specialized code to perform particular tasks, referred to as modules. For instance, a Robot
contains a RobotConfigurationModule
, a RobotJointStateModule
, a RobotKinematicsModule
, and so on. For details on each module, refer to the Optima API documentation. Lines 11 and 14 here print a summary of the configuration module and joint state module, respectively, to the console.
The code for this tutorial can be found in the file optima_toolbox/optima/examples/0_load_robot.rs
and can be run from the optima_toolbox/optima
directory using the following command:
cargo run --example 0_robots
The output of this example should be the following:
Link index: 0 Link name: base_link Present: true
Link index: 1 Link name: shoulder_link Present: true
Link index: 2 Link name: upper_arm_link Present: true
Link index: 3 Link name: forearm_link Present: true
Link index: 4 Link name: wrist_1_link Present: true
Link index: 5 Link name: wrist_2_link Present: true
Link index: 6 Link name: wrist_3_link Present: true
Link index: 7 Link name: ee_link Present: true
Link index: 8 Link name: base Present: true
Link index: 9 Link name: tool0 Present: true
Link index: 10 Link name: world Present: true
>> Joint index: 0 Joint name: shoulder_pan_joint Num dofs: 1 Present: true
-- Joint sub idx 0: Rotation about axis [[0.0, 0.0, 1.0]], Not fixed.
>> Joint index: 1 Joint name: shoulder_lift_joint Num dofs: 1 Present: true
-- Joint sub idx 0: Rotation about axis [[0.0, 1.0, 0.0]], Not fixed.
>> Joint index: 2 Joint name: elbow_joint Num dofs: 1 Present: true
-- Joint sub idx 0: Rotation about axis [[0.0, 1.0, 0.0]], Not fixed.
>> Joint index: 3 Joint name: wrist_1_joint Num dofs: 1 Present: true
-- Joint sub idx 0: Rotation about axis [[0.0, 1.0, 0.0]], Not fixed.
>> Joint index: 4 Joint name: wrist_2_joint Num dofs: 1 Present: true
-- Joint sub idx 0: Rotation about axis [[0.0, 0.0, 1.0]], Not fixed.
>> Joint index: 5 Joint name: wrist_3_joint Num dofs: 1 Present: true
-- Joint sub idx 0: Rotation about axis [[0.0, 1.0, 0.0]], Not fixed.
>> Joint index: 6 Joint name: ee_fixed_joint Num dofs: 0 Present: true
>> Joint index: 7 Joint name: base_link-base_fixed_joint Num dofs: 0 Present: true
>> Joint index: 8 Joint name: wrist_3_link-tool0_fixed_joint Num dofs: 0 Present: true
>> Joint index: 9 Joint name: world_joint Num dofs: 0 Present: true
DOF Joint Axis 0 ---> JointAxis { joint_idx: 0, joint_sub_dof_idx: 0, fixed_value: None, axis_as_unit: [[0.0, 0.0, 1.0]], axis: [[0.0, 0.0, 1.0]], axis_primitive_type: Rotation, bounds: (-6.2831853, 6.2831853) }
DOF Joint Axis 1 ---> JointAxis { joint_idx: 1, joint_sub_dof_idx: 0, fixed_value: None, axis_as_unit: [[0.0, 1.0, 0.0]], axis: [[0.0, 1.0, 0.0]], axis_primitive_type: Rotation, bounds: (-6.2831853, 6.2831853) }
DOF Joint Axis 2 ---> JointAxis { joint_idx: 2, joint_sub_dof_idx: 0, fixed_value: None, axis_as_unit: [[0.0, 1.0, 0.0]], axis: [[0.0, 1.0, 0.0]], axis_primitive_type: Rotation, bounds: (-6.2831853, 6.2831853) }
DOF Joint Axis 3 ---> JointAxis { joint_idx: 3, joint_sub_dof_idx: 0, fixed_value: None, axis_as_unit: [[0.0, 1.0, 0.0]], axis: [[0.0, 1.0, 0.0]], axis_primitive_type: Rotation, bounds: (-6.2831853, 6.2831853) }
DOF Joint Axis 4 ---> JointAxis { joint_idx: 4, joint_sub_dof_idx: 0, fixed_value: None, axis_as_unit: [[0.0, 0.0, 1.0]], axis: [[0.0, 0.0, 1.0]], axis_primitive_type: Rotation, bounds: (-6.2831853, 6.2831853) }
DOF Joint Axis 5 ---> JointAxis { joint_idx: 5, joint_sub_dof_idx: 0, fixed_value: None, axis_as_unit: [[0.0, 1.0, 0.0]], axis: [[0.0, 1.0, 0.0]], axis_primitive_type: Rotation, bounds: (-6.2831853, 6.2831853) }