Enum franka_interface::Robot
source · [−]pub enum Robot {
Sim(FrankaSim),
Real(FrankaReal),
}
Expand description
An abstraction over a robot. Can either be a real robot or a robot in the simulation.
Variants
Sim(FrankaSim)
Real(FrankaReal)
Implementations
sourceimpl Robot
impl Robot
sourcepub fn set_angular_damping(&mut self, damping: f64)
pub fn set_angular_damping(&mut self, damping: f64)
sets the angular damping for a simulated robot
sourcepub fn set_joint_friction_force(&mut self, force: f64)
pub fn set_joint_friction_force(&mut self, force: f64)
sets the static friction (“stiction”) for a simulated robot for torque control.
sourcepub fn joint_motion(&mut self, speed_factor: f64, q_goal: Vector7)
pub fn joint_motion(&mut self, speed_factor: f64, q_goal: Vector7)
point to point motion in joint space.
Arguments
speed_factor
- General speed factor in range [0, 1].q_goal
- Target joint positions.
sourcepub fn control_joint_positions<F: FnMut(&RobotState, &Duration) -> JointPositions>(
&mut self,
control_callback: F
)
pub fn control_joint_positions<F: FnMut(&RobotState, &Duration) -> JointPositions>(
&mut self,
control_callback: F
)
Starts a control loop for a joint position motion generator
Example
let mut initial_joint_positions = Vector7::zeros();
let mut time = 0.;
robot.control_joint_positions(|state, time_step| {
time += time_step.as_secs_f64();
if time == 0. {
initial_joint_positions = state.joint_positions;
}
let mut out = JointPositions::from(initial_joint_positions);
let delta_angle = PI / 8. * (1. - f64::cos(PI / 2.5 * time));
out.joint_positions[3] += delta_angle;
out.joint_positions[4] += delta_angle;
out.joint_positions[6] += delta_angle;
if time >= 5.0 {
println!("Finished motion, shutting down example");
out.is_finished = true;
}
out
})
sourcepub fn control_torques<F: FnMut(&RobotState, &Duration) -> Torques>(
&mut self,
control_callback: F
)
pub fn control_torques<F: FnMut(&RobotState, &Duration) -> Torques>(
&mut self,
control_callback: F
)
Starts a control loop for sending joint-level torque commands
Example
let mut time = 0.;
let mut rotation_force: f64 = 0.01;
robot.control_torques(|state, time_step| {
time += time_step.as_secs_f64();
if state.joint_positions[6] > PI / 4. + 0.1 && rotation_force.is_sign_positive() {
rotation_force *= -1.;
}
if state.joint_positions[6] < PI / 4. - 0.1 && rotation_force.is_sign_negative() {
rotation_force *= -1.;
}
let mut torques = Torques::from(Vector7::from_column_slice(&[
0.,
0.,
0.,
0.,
0.,
0.,
rotation_force,
]));
if time > 10. {
torques.is_finished = true;
}
torques
});
sourcepub fn control_cartesian_pose<F: FnMut(&RobotState, &Duration) -> CartesianPose>(
&mut self,
control_callback: F
)
pub fn control_cartesian_pose<F: FnMut(&RobotState, &Duration) -> CartesianPose>(
&mut self,
control_callback: F
)
Starts a control loop for a Cartesian pose motion generator
Example
let mut time = 0.;
let mut initial_pose = CartesianPose::from(Isometry3::identity());
robot.control_cartesian_pose(|state, time_step| {
time += time_step.as_secs_f64();
if time == 0. {
initial_pose.pose = state.end_effector_pose;
}
let radius = 0.3;
let angle = PI / 4. * (1. - f64::cos(PI / 5. * time));
let delta_x = radius * f64::sin(angle);
let delta_z = radius * (f64::cos(angle) - 1.);
let mut out = CartesianPose::from(initial_pose.pose);
out.pose.translation.x += delta_x;
out.pose.translation.z += delta_z;
if time > 10. {
out.is_finished = true;
}
out
});
sourcepub fn open_gripper(&mut self, width: f64)
pub fn open_gripper(&mut self, width: f64)
sourcepub fn close_gripper(&mut self)
pub fn close_gripper(&mut self)
closes the gripper
sourcepub fn get_state(&mut self) -> RobotState
pub fn get_state(&mut self) -> RobotState
queries the robot state
sourcepub fn get_gripper_state(&mut self) -> GripperState
pub fn get_gripper_state(&mut self) -> GripperState
queries the gripper state
sourcepub fn get_jacobian(&mut self) -> Matrix6x7
pub fn get_jacobian(&mut self) -> Matrix6x7
queries the current space jacobian
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 Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
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<T> Pointable for T
impl<T> Pointable for T
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
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.