Struct openrr_client::RobotClient

source ·
pub struct RobotClient<L, M, N>
where L: Localization, M: MoveBase, N: Navigation,
{ /* private fields */ }

Implementations§

source§

impl<L, M, N> RobotClient<L, M, N>
where L: Localization, M: MoveBase, N: Navigation,

source

pub fn new( config: OpenrrClientsConfig, raw_joint_trajectory_clients: HashMap<String, Arc<dyn JointTrajectoryClient>>, speakers: HashMap<String, Arc<dyn Speaker>>, localization: Option<L>, move_base: Option<M>, navigation: Option<N>, ) -> Result<Self, Error>

source

pub fn set_raw_clients_joint_positions_to_full_chain_for_collision_checker( &self, ) -> Result<(), Error>

Set the current joint positions to the robot kinematic model.

Returns Error::FullChainNotFound when self.full_chain_for_collision_checker is None.

source

pub fn is_raw_joint_trajectory_client(&self, name: &str) -> bool

source

pub fn is_joint_trajectory_client(&self, name: &str) -> bool

source

pub fn is_collision_avoidance_client(&self, name: &str) -> bool

source

pub fn is_collision_check_client(&self, name: &str) -> bool

source

pub fn is_ik_client(&self, name: &str) -> bool

source

pub fn joint_trajectory_clients( &self, ) -> &HashMap<String, Arc<dyn JointTrajectoryClient>>

source

pub fn self_collision_checkers( &self, ) -> &HashMap<String, Arc<SelfCollisionChecker<f64>>>

source

pub fn ik_solvers(&self) -> &HashMap<String, Arc<IkSolverWithChain>>

source

pub fn collision_avoidance_clients( &self, ) -> &HashMap<String, Arc<CollisionAvoidanceClient<Arc<dyn JointTrajectoryClient>>>>

source

pub fn ik_clients( &self, ) -> &HashMap<String, Arc<IkClient<Arc<dyn JointTrajectoryClient>>>>

source

pub fn send_joint_positions( &self, name: &str, positions: &[f64], duration_sec: f64, ) -> Result<WaitFuture, Error>

source

pub fn current_joint_positions(&self, name: &str) -> Result<Vec<f64>, Error>

source

pub fn joint_names(&self, name: &str) -> Result<Vec<String>, Error>

Returns the joint names which is handled by the joint trajectory client with name

source

pub fn send_joints_pose( &self, name: &str, pose_name: &str, duration_sec: f64, ) -> Result<WaitFuture, Error>

source

pub fn current_end_transform(&self, name: &str) -> Result<Isometry3<f64>, Error>

source

pub fn transform( &self, name: &str, pose: &Isometry3<f64>, ) -> Result<Isometry3<f64>, Error>

source

pub fn move_ik( &self, name: &str, target_pose: &Isometry3<f64>, duration_sec: f64, ) -> Result<WaitFuture, Error>

source

pub fn move_ik_with_interpolation( &self, name: &str, target_pose: &Isometry3<f64>, duration_sec: f64, max_resolution: f64, min_number_of_points: i32, ) -> Result<WaitFuture, Error>

source

pub fn send_joint_positions_with_pose_interpolation( &self, name: &str, positions: &[f64], duration_sec: f64, max_resolution: f64, min_number_of_points: i32, ) -> Result<WaitFuture, Error>

source

pub fn raw_joint_trajectory_clients_names(&self) -> Vec<String>

source

pub fn joint_trajectory_clients_names(&self) -> Vec<String>

source

pub fn collision_avoidance_clients_names(&self) -> Vec<String>

source

pub fn collision_check_clients_names(&self) -> Vec<String>

source

pub fn ik_clients_names(&self) -> Vec<String>

source

pub fn full_chain_for_collision_checker(&self) -> &Option<Arc<Chain<f64>>>

source

pub fn speakers(&self) -> &HashMap<String, Arc<dyn Speaker>>

source

pub fn speak(&self, name: &str, message: &str) -> Result<WaitFuture, Error>

Trait Implementations§

source§

impl<L, M, N> Localization for RobotClient<L, M, N>
where L: Localization, M: MoveBase, N: Navigation,

source§

impl<L, M, N> MoveBase for RobotClient<L, M, N>
where L: Localization, M: MoveBase, N: Navigation,

source§

impl<L, M, N> Navigation for RobotClient<L, M, N>
where L: Localization, M: MoveBase, N: Navigation,

source§

fn send_goal_pose( &self, goal: Isometry2<f64>, frame_id: &str, timeout: Duration, ) -> Result<WaitFuture, ArciError>

source§

fn cancel(&self) -> Result<(), ArciError>

Auto Trait Implementations§

§

impl<L, M, N> Freeze for RobotClient<L, M, N>
where L: Freeze, M: Freeze, N: Freeze,

§

impl<L, M, N> !RefUnwindSafe for RobotClient<L, M, N>

§

impl<L, M, N> Send for RobotClient<L, M, N>

§

impl<L, M, N> Sync for RobotClient<L, M, N>

§

impl<L, M, N> Unpin for RobotClient<L, M, N>
where L: Unpin, M: Unpin, N: Unpin,

§

impl<L, M, N> !UnwindSafe for RobotClient<L, M, N>

Blanket Implementations§

source§

impl<T> Any for T
where T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for T
where T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> Downcast for T
where T: Any,

source§

fn into_any(self: Box<T>) -> Box<dyn Any>

Convert Box<dyn Trait> (where Trait: Downcast) to Box<dyn Any>. Box<dyn Any> can then be further downcast into Box<ConcreteType> where ConcreteType implements Trait.
source§

fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>

Convert Rc<Trait> (where Trait: Downcast) to Rc<Any>. Rc<Any> can then be further downcast into Rc<ConcreteType> where ConcreteType implements Trait.
source§

fn as_any(&self) -> &(dyn Any + 'static)

Convert &Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &Any’s vtable from &Trait’s.
source§

fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)

Convert &mut Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &mut Any’s vtable from &mut Trait’s.
source§

impl<T> DowncastSync for T
where T: Any + Send + Sync,

source§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Sync + Send>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T> Instrument for T

source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
source§

impl<T, U> Into<U> for T
where U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

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

source§

impl<T> IntoEither for T

source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts self into a Left variant of Either<Self, Self> if into_left is true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts self into a Left variant of Either<Self, Self> if into_left(&self) returns true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
source§

impl<T> Pointable for T

source§

const ALIGN: usize = _

The alignment of pointer.
source§

type Init = T

The type for initializers.
source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
source§

impl<T> Same for T

source§

type Output = T

Should always be Self
source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

source§

fn to_subset(&self) -> Option<SS>

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

fn is_in_subset(&self) -> bool

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

fn to_subset_unchecked(&self) -> SS

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

fn from_subset(element: &SS) -> SP

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

impl<T, U> TryFrom<U> for T
where U: Into<T>,

source§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

source§

fn vzip(self) -> V

source§

impl<T> WithSubscriber for T

source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more