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
sourceimpl Robot
impl Robot
sourcepub fn new<RtConfig: Into<Option<RealtimeConfig>>, LogSize: Into<Option<usize>>>(
franka_address: &str,
realtime_config: RtConfig,
log_size: LogSize
) -> FrankaResult<Robot>
pub fn new<RtConfig: Into<Option<RealtimeConfig>>, LogSize: Into<Option<usize>>>(
franka_address: &str,
realtime_config: RtConfig,
log_size: LogSize
) -> FrankaResult<Robot>
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 Enforcelog_size
- sets how many last states should be kept for logging purposes. The log is provided when aControlException
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.
sourcepub fn read<F: FnMut(&RobotState) -> bool>(
&mut self,
read_callback: F
) -> FrankaResult<()>
pub fn read<F: FnMut(&RobotState) -> bool>(
&mut self,
read_callback: F
) -> FrankaResult<()>
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
NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn read_once(&mut self) -> FrankaResult<RobotState>
pub fn read_once(&mut self) -> FrankaResult<RobotState>
Waits for a robot state update and returns it.
Return
Current robot state.
Error
NetworkException
if the connection is lost, e.g. after a timeout.
See Robot::read
for a way to repeatedly receive the robot state.
sourcepub fn set_collision_behavior(
&mut self,
lower_torque_thresholds_acceleration: [f64; 7],
upper_torque_thresholds_acceleration: [f64; 7],
lower_torque_thresholds_nominal: [f64; 7],
upper_torque_thresholds_nominal: [f64; 7],
lower_force_thresholds_acceleration: [f64; 6],
upper_force_thresholds_acceleration: [f64; 6],
lower_force_thresholds_nominal: [f64; 6],
upper_force_thresholds_nominal: [f64; 6]
) -> FrankaResult<()>
pub fn set_collision_behavior(
&mut self,
lower_torque_thresholds_acceleration: [f64; 7],
upper_torque_thresholds_acceleration: [f64; 7],
lower_torque_thresholds_nominal: [f64; 7],
upper_torque_thresholds_nominal: [f64; 7],
lower_force_thresholds_acceleration: [f64; 6],
upper_force_thresholds_acceleration: [f64; 6],
lower_force_thresholds_nominal: [f64; 6],
upper_force_thresholds_nominal: [f64; 6]
) -> FrankaResult<()>
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
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
See also
RobotState::cartesian_contact
RobotState::cartesian_collision
RobotState::joint_contact
RobotState::joint_collision
automatic_error_recovery
for performing a reset after a collision.
sourcepub fn set_joint_impedance(&mut self, K_theta: [f64; 7]) -> FrankaResult<()>
pub fn set_joint_impedance(&mut self, K_theta: [f64; 7]) -> FrankaResult<()>
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 .
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn set_cartesian_impedance(&mut self, K_x: [f64; 6]) -> FrankaResult<()>
pub fn set_cartesian_impedance(&mut self, K_x: [f64; 6]) -> FrankaResult<()>
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
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn set_guiding_mode(
&mut self,
guiding_mode: [bool; 6],
elbow: bool
) -> FrankaResult<()>
pub fn set_guiding_mode(
&mut self,
guiding_mode: [bool; 6],
elbow: bool
) -> FrankaResult<()>
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
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn set_K(&mut self, EE_T_K: [f64; 16]) -> FrankaResult<()>
pub fn set_K(&mut self, EE_T_K: [f64; 16]) -> FrankaResult<()>
Sets the transformation 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 , column-major.
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
See Stiffness frame K for an explanation of the stiffness frame.
sourcepub fn set_EE(&mut self, NE_T_EE: [f64; 16]) -> FrankaResult<()>
pub fn set_EE(&mut self, NE_T_EE: [f64; 16]) -> FrankaResult<()>
Sets the transformation 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 , column-major.
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
See also
RobotState::NE_T_EE
RobotState::O_T_EE
RobotState::F_T_EE
- NE and EE for an explanation of those frames
sourcepub fn set_load(
&mut self,
load_mass: f64,
F_x_Cload: [f64; 3],
load_inertia: [f64; 9]
) -> FrankaResult<()>
pub fn set_load(
&mut self,
load_mass: f64,
F_x_Cload: [f64; 3],
load_inertia: [f64; 9]
) -> FrankaResult<()>
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 in [m]load_inertia
- Inertia matrix in [kg \times m^2], column-major.
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn set_filters(
&mut self,
joint_position_filter_frequency: f64,
joint_velocity_filter_frequency: f64,
cartesian_position_filter_frequency: f64,
cartesian_velocity_filter_frequency: f64,
controller_filter_frequency: f64
) -> FrankaResult<()>
👎 Deprecated: please use low_pass_filter
instead
pub fn set_filters(
&mut self,
joint_position_filter_frequency: f64,
joint_velocity_filter_frequency: f64,
cartesian_position_filter_frequency: f64,
cartesian_velocity_filter_frequency: f64,
controller_filter_frequency: f64
) -> FrankaResult<()>
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
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn automatic_error_recovery(&mut self) -> FrankaResult<()>
pub fn automatic_error_recovery(&mut self) -> FrankaResult<()>
Runs automatic error recovery on the robot.
Automatic error recovery e.g. resets the robot after a collision occurred.
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn stop(&mut self) -> FrankaResult<()>
pub fn stop(&mut self) -> FrankaResult<()>
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
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn get_virtual_wall(&mut self, id: i32) -> FrankaResult<VirtualWallCuboid>
pub fn get_virtual_wall(&mut self, id: i32) -> FrankaResult<VirtualWallCuboid>
Returns the parameters of a virtual wall.
Arguments
id
- ID of the virtual wall.
Return
Parameters of virtual wall.
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn control_joint_positions<F: FnMut(&RobotState, &Duration) -> JointPositions, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_joint_positions<F: FnMut(&RobotState, &Duration) -> JointPositions, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 impedancelimit_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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
Panics
- if joint position commands are NaN or infinity.
See new
to change behavior if realtime priority cannot be set.
sourcepub fn control_joint_velocities<F: FnMut(&RobotState, &Duration) -> JointVelocities, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_joint_velocities<F: FnMut(&RobotState, &Duration) -> JointVelocities, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 impedancelimit_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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
Panics
- if joint velocity commands are NaN or infinity.
See new
to change behavior if realtime priority cannot be set.
sourcepub fn control_cartesian_pose<F: FnMut(&RobotState, &Duration) -> CartesianPose, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_cartesian_pose<F: FnMut(&RobotState, &Duration) -> CartesianPose, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 impedancelimit_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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
Panics
- if Cartesian pose command elements are NaN or infinity.
See new
to change behavior if realtime priority cannot be set.
sourcepub fn control_cartesian_velocities<F: FnMut(&RobotState, &Duration) -> CartesianVelocities, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_cartesian_velocities<F: FnMut(&RobotState, &Duration) -> CartesianVelocities, CM: Into<Option<ControllerMode>>, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
motion_generator_callback: F,
controller_mode: CM,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 impedancelimit_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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
Panics
- if Cartesian velocity command elements are NaN or infinity.
See new
to change behavior if realtime priority cannot be set.
sourcepub fn control_torques_and_joint_velocities<F: FnMut(&RobotState, &Duration) -> JointVelocities, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_torques_and_joint_velocities<F: FnMut(&RobotState, &Duration) -> JointVelocities, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
Panics
- if joint-level torque or joint velocity commands are NaN or infinity.
See new
to change behavior if realtime priority cannot be set.
sourcepub fn control_torques_and_joint_positions<F: FnMut(&RobotState, &Duration) -> JointPositions, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_torques_and_joint_positions<F: FnMut(&RobotState, &Duration) -> JointPositions, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
Panics
- if joint-level torque or joint position commands are NaN or infinity.
See new
to change behavior if realtime priority cannot be set.
sourcepub fn control_torques_and_cartesian_pose<F: FnMut(&RobotState, &Duration) -> CartesianPose, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_torques_and_cartesian_pose<F: FnMut(&RobotState, &Duration) -> CartesianPose, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
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.
sourcepub fn control_torques_and_cartesian_velocities<F: FnMut(&RobotState, &Duration) -> CartesianVelocities, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_torques_and_cartesian_velocities<F: FnMut(&RobotState, &Duration) -> CartesianVelocities, T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
motion_generator_callback: F,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if realtime priority cannot be set for the current thread.
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.
sourcepub fn control_torques<T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
pub fn control_torques<T: FnMut(&RobotState, &Duration) -> Torques, L: Into<Option<bool>>, CF: Into<Option<f64>>>(
&mut self,
control_callback: T,
limit_rate: L,
cutoff_frequency: CF
) -> FrankaResult<()>
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 toMAX_CUTOFF_FREQUENCY
to disable. Default is 100 Hz
Errors
ControlException
if an error related to torque control or motion generation occurred.NetworkException
if the connection is lost, e.g. after a timeout.RealTimeException
if real-time priority cannot be set for the current thread.
Panics
- if joint-level torque commands are NaN or infinity.
See new
to change behavior if real-time priority cannot be set.
sourcepub fn set_default_behavior(&mut self) -> FrankaResult<()>
pub fn set_default_behavior(&mut self) -> FrankaResult<()>
Sets a default collision behavior, joint impedance and Cartesian impedance.
Errors
CommandException
if the Control reports an error.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn joint_motion(
&mut self,
speed_factor: f64,
q_goal: &[f64; 7]
) -> FrankaResult<()>
pub fn joint_motion(
&mut self,
speed_factor: f64,
q_goal: &[f64; 7]
) -> FrankaResult<()>
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.
sourcepub fn load_model(&mut self, persistent: bool) -> FrankaResult<Model>
pub fn load_model(&mut self, persistent: bool) -> FrankaResult<Model>
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
ModelException
if the model library cannot be loaded.NetworkException
if the connection is lost, e.g. after a timeout.
sourcepub fn server_version(&self) -> u16
pub fn server_version(&self) -> u16
Returns the software version reported by the connected server.
Return
Software version of the connected server.
Auto Trait Implementations
impl RefUnwindSafe for Robot
impl Send for Robot
impl Sync for Robot
impl Unpin for Robot
impl UnwindSafe for Robot
Blanket Implementations
sourceimpl<T> BorrowMut<T> for T where
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
const: unstable · sourcefn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.