Struct franka::robot::control_types::CartesianPose [−][src]
pub struct CartesianPose { pub O_T_EE: [f64; 16], pub elbow: Option<[f64; 2]>, // some fields omitted }
Stores values for Cartesian pose motion generation.
Fields
O_T_EE: [f64; 16]
Homogeneous transformation , column major, that transforms from
the end effector frame EE
to base frame O
.
Equivalently, it is the desired end effector pose in base frame.
elbow: Option<[f64; 2]>
Elbow configuration.
If “None” the elbow will be controlled by the robot
The values of the array are:
- [0] Position of the 3rd joint in [rad].
- [1] Sign of the 4th joint. Can be +1 or -1.
Implementations
impl CartesianPose
[src]
impl CartesianPose
[src]pub fn new(cartesian_pose: [f64; 16], elbow: Option<[f64; 2]>) -> Self
[src]
Creates a new CartesianPose instance.
Arguments
-
cartesian_pose
- Desired vectorized homogeneous transformation matrix , column major, that transforms from the end effector frameEE
to base frameO
. Equivalently, it is the desired end effector pose in base frame. -
elbow
- Elbow configuration. See elbow
pub fn has_elbow(&self) -> bool
[src]
Determines whether there is a stored elbow configuration.
pub fn check_elbow(elbow: &[f64; 2])
[src]
Determines whether the elbow configuration is valid and has finite values
pub fn is_valid_elbow(elbow: &[f64; 2]) -> bool
[src]
Determines whether the given elbow configuration is valid or not.
Trait Implementations
impl Clone for CartesianPose
[src]
impl Clone for CartesianPose
[src]fn clone(&self) -> CartesianPose
[src]
pub fn clone_from(&mut self, source: &Self)
1.0.0[src]
impl Copy for CartesianPose
[src]
impl Copy for CartesianPose
[src]impl<'de> Deserialize<'de> for CartesianPose
[src]
impl<'de> Deserialize<'de> for CartesianPose
[src]fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error> where
__D: Deserializer<'de>,
[src]
__D: Deserializer<'de>,
impl Finishable for CartesianPose
[src]
impl Finishable for CartesianPose
[src]fn is_finished(&self) -> bool
[src]
fn set_motion_finished(&mut self, finished: bool)
[src]
fn convert_motion(
&self,
robot_state: &RobotState,
command: &mut MotionGeneratorCommand,
cutoff_frequency: f64,
limit_rate: bool
)
[src]
&self,
robot_state: &RobotState,
command: &mut MotionGeneratorCommand,
cutoff_frequency: f64,
limit_rate: bool
)
impl From<Isometry<f64, U3, Unit<Quaternion<f64>>>> for CartesianPose
[src]
impl From<Isometry<f64, U3, Unit<Quaternion<f64>>>> for CartesianPose
[src]impl Serialize for CartesianPose
[src]
impl Serialize for CartesianPose
[src]Auto Trait Implementations
impl RefUnwindSafe for CartesianPose
impl RefUnwindSafe for CartesianPose
impl Send for CartesianPose
impl Send for CartesianPose
impl Sync for CartesianPose
impl Sync for CartesianPose
impl Unpin for CartesianPose
impl Unpin for CartesianPose
impl UnwindSafe for CartesianPose
impl UnwindSafe for CartesianPose
Blanket Implementations
impl<T> DeserializeOwned for T where
T: for<'de> Deserialize<'de>,
[src]
impl<T> DeserializeOwned for T where
T: for<'de> Deserialize<'de>,
[src]impl<T> MotionFinished for T where
T: Finishable + Copy,
[src]
impl<T> MotionFinished for T where
T: Finishable + Copy,
[src]pub fn motion_finished(Self) -> T
[src]
impl<T> Same<T> for T
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn is_in_subset(&self) -> bool
pub fn to_subset_unchecked(&self) -> SS
pub fn from_subset(element: &SS) -> SP
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
impl<V, T> VZip<V> for T where
V: MultiLane<T>,