Struct arci::DummyJointTrajectoryClient [−][src]
pub struct DummyJointTrajectoryClient { pub joint_names: Vec<String>, pub positions: Arc<Mutex<Vec<f64>>>, pub last_trajectory: Arc<Mutex<Vec<TrajectoryPoint>>>, }
Expand description
Dummy JointTrajectoryClient for debug or tests.
Fields
joint_names: Vec<String>
positions: Arc<Mutex<Vec<f64>>>
last_trajectory: Arc<Mutex<Vec<TrajectoryPoint>>>
Implementations
Trait Implementations
Returns names of joints that this client handles.
Returns the current joint positions.
fn send_joint_positions(
&self,
positions: Vec<f64>,
_duration: Duration
) -> Result<WaitFuture, Error>
fn send_joint_positions(
&self,
positions: Vec<f64>,
_duration: Duration
) -> Result<WaitFuture, Error>
Send the specified joint positions and returns a future that waits until complete the move joints. Read more
fn send_joint_trajectory(
&self,
full_trajectory: Vec<TrajectoryPoint>
) -> Result<WaitFuture, Error>
fn send_joint_trajectory(
&self,
full_trajectory: Vec<TrajectoryPoint>
) -> Result<WaitFuture, Error>
Send the specified joint trajectory and returns a future that waits until complete the move joints. Read more
Auto Trait Implementations
impl RefUnwindSafe for DummyJointTrajectoryClient
impl Send for DummyJointTrajectoryClient
impl Sync for DummyJointTrajectoryClient
impl Unpin for DummyJointTrajectoryClient
impl UnwindSafe for DummyJointTrajectoryClient
Blanket Implementations
Mutably borrows from an owned value. Read more
Instruments this type with the provided Span
, returning an
Instrumented
wrapper. Read more
type Output = T
type Output = T
Should always be Self
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.