pub struct Robot { /* private fields */ }
Expand description

Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot.

Nominal end effector frame NE

The nominal end effector frame is configured outside of libfranka-rs and cannot be changed here.

End effector frame EE

By default, the end effector frame EE is the same as the nominal end effector frame NE (i.e. the transformation between NE and EE is the identity transformation). With set_EE, a custom transformation matrix can be set.

Stiffness frame K

The stiffness frame is used for Cartesian impedance control, and for measuring and applying forces. It can be set with set_K.

Motion generation and joint-level torque commands

The following methods allow to perform motion generation and/or send joint-level torque commands without gravity and friction by providing callback functions.

Only one of these methods can be active at the same time; a ControlException is thrown otherwise.

When a robot state is received, the callback function is used to calculate the response: the desired values for that time step. After sending back the response, the callback function will be called again with the most recently received robot state. Since the robot is controlled with a 1 kHz frequency, the callback functions have to compute their result in a short time frame in order to be accepted. Callback functions take two parameters:

  • A &franka::RobotState showing the current robot state.
  • A &std::time::Duration to indicate the time since the last callback invocation. Thus, the duration is zero on the first invocation of the callback function!

The following incomplete example shows the general structure of a callback function:

use franka::robot::robot_state::RobotState;
use franka::robot::control_types::{JointPositions, MotionFinished};
use std::time::Duration;
let mut time = 0.;
let callback = |state: &RobotState, time_step: &Duration| -> JointPositions {
    time += time_step.as_secs_f64();
    let out: JointPositions = your_function_which_generates_joint_positions(time);
    if time >= 5.0 {
        return out.motion_finished();
    }
    return out;
    };

Commands

Commands are executed by communicating with the robot over the network. These functions should therefore not be called from within control or motion generator loops.

Implementations

Establishes a connection with the robot.

Arguments
  • franka_address - IP/hostname of the robot.
  • realtime_config - if set to Enforce, an exception will be thrown if realtime priority cannot be set when required. Setting realtime_config to Ignore disables this behavior. Default is Enforce
  • log_size - sets how many last states should be kept for logging purposes. The log is provided when a ControlException is thrown.
Example
use franka::{FrankaResult, RealtimeConfig, Robot};
fn main() -> FrankaResult<()> {
    // connects to the robot using real-time scheduling and a default log size of 50.
    let mut robot = Robot::new("robotik-bs.de", None, None)?;
    // connects to the robot without using real-time scheduling and a log size of 1.
    let mut robot = Robot::new("robotik-bs.de", RealtimeConfig::Ignore, 1)?;
    Ok(())
}
Errors
  • NetworkException if the connection is unsuccessful.
  • IncompatibleVersionException if this version of libfranka-rs is not supported.

Starts a loop for reading the current robot state.

Cannot be executed while a control or motion generator loop is running.

This minimal example will print the robot state 100 times:

use franka::{Robot, RobotState, FrankaResult};
fn main() -> FrankaResult<()> {
    let mut robot = Robot::new("robotik-bs.de",None,None)?;
    let mut count = 0;
    robot.read(| robot_state:&RobotState | -> bool {
        println!("{:?}", robot_state);
        count += 1;
        count <= 100
    })
}
Arguments
  • read_callback - Callback function for robot state reading. The callback hast to return true as long as it wants to receive further robot states.
Error

Waits for a robot state update and returns it.

Return

Current robot state.

Error

See Robot::read for a way to repeatedly receive the robot state.

Changes the collision behavior.

Set separate torque and force boundaries for acceleration/deceleration and constant velocity movement phases.

Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.

Arguments
  • lower_torque_thresholds_acceleration - Contact torque thresholds during acceleration/deceleration for each joint in [Nm]
  • upper_torque_thresholds_acceleration - Collision torque thresholds during acceleration/deceleration for each joint in [Nm]
  • lower_torque_thresholds_nominal - Contact torque thresholds for each joint in [Nm]
  • upper_torque_thresholds_nominal - Collision torque thresholds for each joint in [Nm]
  • lower_force_thresholds_acceleration -Contact force thresholds during acceleration/deceleration for (x,y,z,R,P,Y) in [N].
  • upper_force_thresholds_acceleration - Collision force thresholds during acceleration/deceleration for (x,y,z,R,P,Y) in [N].
  • lower_force_thresholds_nominal - Contact force thresholds for (x,y,z,R,P,Y) in [N]
  • upper_force_thresholds_nominal - Collision force thresholds for (x,y,z,R,P,Y) in [N]
Errors
See also

Sets the impedance for each joint in the internal controller.

User-provided torques are not affected by this setting.

Arguments
  • K_theta - Joint impedance values K_{\theta}.
Errors

Sets the Cartesian impedance for (x, y, z, roll, pitch, yaw) in the internal controller.

User-provided torques are not affected by this setting.

Arguments
  • K_x - Cartesian impedance values

K_x=(x \in [10,3000] \frac{N}{m}, y \in [10,3000] \frac{N}{m}, z \in [10,3000] \frac{N}{m}, R \in [1,300] \frac{Nm}{rad}, P \in [1,300] \frac{Nm}{rad}, Y \in [1,300]  \frac{Nm}{rad})

Errors

Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).

If a flag is set to true, movement is unlocked.

Note

Guiding mode can be enabled by pressing the two opposing buttons near the robot’s flange.

Arguments
  • guiding_mode - Unlocked movement in (x, y, z, R, P, Y) in guiding mode.
  • elbow - True if the elbow is free in guiding mode, false otherwise.
Errors

Sets the transformation ^{EE}T_K from end effector frame to stiffness frame.

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

Arguments
  • EE_T_K - Vectorized EE-to-K transformation matrix ^{EE}T_K, column-major.
Errors

See Stiffness frame K for an explanation of the stiffness frame.

Sets the transformation ^{NE}T_{EE} from nominal end effector to end effector frame.

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

Arguments
  • NE_T_EE - Vectorized NE-to-EE transformation matrix ^{NE}T_{EE}, column-major.
Errors
See also

Sets dynamic parameters of a payload.

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

Note

This is not for setting end effector parameters, which have to be set in the administrator’s interface.

Arguments
  • load_mass - Mass of the load in [kg]
  • F_x_Cload - Translation from flange to center of mass of load ^Fx_{C_\text{load}} in [m]
  • load_inertia - Inertia matrix I_\text{load} in [kg \times m^2], column-major.
Errors
👎 Deprecated:

please use low_pass_filter instead

Sets the cut off frequency for the given motion generator or controller.

Allowed input range for all the filters is between 1.0 Hz and 1000.0 Hz. If the value is set to maximum (1000Hz) then no filtering is done.

Arguments
  • joint_position_filter_frequency - Frequency at which the commanded joint position is cut off.
  • joint_velocity_filter_frequency - TFrequency at which the commanded joint velocity is cut off.
  • cartesian_position_filter_frequency - Frequency at which the commanded Cartesian position is cut off.
  • cartesian_velocity_filter_frequency - Frequency at which the commanded Cartesian velocity is cut off.
  • controller_filter_frequency - Frequency at which the commanded torque is cut off
Errors

Runs automatic error recovery on the robot.

Automatic error recovery e.g. resets the robot after a collision occurred.

Errors

Stops all currently running motions.

If a control or motion generator loop is running in another thread, it will be preempted with a ControlException.

Errors

Returns the parameters of a virtual wall.

Arguments
  • id - ID of the virtual wall.
Return

Parameters of virtual wall.

Errors

Starts a control loop for a joint position motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • controller_mode Controller to use to execute the motion. Default is joint impedance
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint position commands are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for a joint velocity motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • controller_mode Controller to use to execute the motion. Default is joint impedance
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint velocity commands are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for a Cartesian pose motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • controller_mode Controller to use to execute the motion. Default is joint impedance
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if Cartesian pose command elements are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for a Cartesian velocity motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • controller_mode Controller to use to execute the motion. Default is joint impedance
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if Cartesian velocity command elements are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for sending joint-level torque commands and joint velocities.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • control_callback Callback function providing joint-level torque commands. See here for more details.
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint-level torque or joint velocity commands are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for sending joint-level torque commands and joint positions.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • control_callback Callback function providing joint-level torque commands. See here for more details.
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint-level torque or joint position commands are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for sending joint-level torque commands and Cartesian poses.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • control_callback Callback function providing joint-level torque commands. See here for more details.
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint-level torque or Cartesian pose command elements are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for sending joint-level torque commands and Cartesian velocities.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • control_callback Callback function providing joint-level torque commands. See here for more details.
  • motion_generator_callback Callback function for motion generation. See here for more details.
  • limit_rate True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint-level torque or Cartesian velocity command elements are NaN or infinity.

See new to change behavior if realtime priority cannot be set.

Starts a control loop for sending joint-level torque commands.

Sets real-time priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Arguments
  • control_callback - Callback function providing joint-level torque commands. See here for more details.
  • limit_rate - True if rate limiting should be activated. True by default. This could distort your motion!
  • cutoff_frequency - Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to MAX_CUTOFF_FREQUENCY to disable. Default is 100 Hz
Errors
Panics
  • if joint-level torque commands are NaN or infinity.

See new to change behavior if real-time priority cannot be set.

Sets a default collision behavior, joint impedance and Cartesian impedance.

Errors

Executes a joint pose motion to a goal position. Adapted from: Wisama Khalil and Etienne Dombre. 2002. Modeling, Identification and Control of Robots (Kogan Page Science Paper edition).

Arguments
  • speed_factor - General speed factor in range [0, 1].
  • q_goal - Target joint positions.

Loads the model library from the robot.

Arguments
  • persistent - If set to true the model will be stored at /tmp/model.so
Return

Model instance.

Errors

Returns the software version reported by the connected server.

Return

Software version of the connected server.

Auto Trait Implementations

Blanket Implementations

Gets the TypeId of self. Read more

Immutably borrows from an owned value. Read more

Mutably borrows from an owned value. Read more

Returns the argument unchanged.

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Should always be Self

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more

Checks if self is actually part of its subset T (and can be converted to it).

Use with care! Same as self.to_subset but without any property checks. Always succeeds.

The inclusion map: converts self to the equivalent element of its superset.

The type returned in the event of a conversion error.

Performs the conversion.

The type returned in the event of a conversion error.

Performs the conversion.