Struct openrr_client::RobotClient [−][src]
Implementations
impl<S, M, N> RobotClient<S, M, N> where
S: Speaker,
M: MoveBase,
N: Navigation,
[src]
S: Speaker,
M: MoveBase,
N: Navigation,
pub fn try_new(
config: OpenrrClientsConfig,
raw_joint_trajectory_clients: HashMap<String, Arc<dyn JointTrajectoryClient>>,
speaker: S,
move_base: Option<M>,
navigation: Option<N>
) -> Result<Self, Error>
[src]
config: OpenrrClientsConfig,
raw_joint_trajectory_clients: HashMap<String, Arc<dyn JointTrajectoryClient>>,
speaker: S,
move_base: Option<M>,
navigation: Option<N>
) -> Result<Self, Error>
pub fn set_raw_clients_joint_positions_to_full_chain_for_collision_checker(
&self
) -> Result<(), Error>
[src]
&self
) -> Result<(), Error>
pub fn is_raw_joint_trajectory_client(&self, name: &str) -> bool
[src]
pub fn is_joint_trajectory_client(&self, name: &str) -> bool
[src]
pub fn is_collision_check_client(&self, name: &str) -> bool
[src]
pub fn is_ik_client(&self, name: &str) -> bool
[src]
pub fn joint_trajectory_clients(
&self
) -> &HashMap<String, Arc<dyn JointTrajectoryClient>>
[src]
&self
) -> &HashMap<String, Arc<dyn JointTrajectoryClient>>
pub fn self_collision_checkers(
&self
) -> &HashMap<String, Arc<SelfCollisionChecker>>
[src]
&self
) -> &HashMap<String, Arc<SelfCollisionChecker>>
pub fn ik_solvers(&self) -> &HashMap<String, Arc<IkSolverWithChain>>
[src]
pub fn ik_clients(
&self
) -> &HashMap<String, Arc<IkClient<Arc<dyn JointTrajectoryClient>>>>
[src]
&self
) -> &HashMap<String, Arc<IkClient<Arc<dyn JointTrajectoryClient>>>>
pub async fn send_joint_positions(
&self,
name: &str,
positions: &[f64],
duration_sec: f64
) -> Result<(), Error>
[src]
&self,
name: &str,
positions: &[f64],
duration_sec: f64
) -> Result<(), Error>
pub async fn current_joint_positions(
&self,
name: &str
) -> Result<Vec<f64>, Error>
[src]
&self,
name: &str
) -> Result<Vec<f64>, Error>
pub async fn send_joints_pose(
&self,
name: &str,
pose_name: &str,
duration_sec: f64
) -> Result<(), Error>
[src]
&self,
name: &str,
pose_name: &str,
duration_sec: f64
) -> Result<(), Error>
pub async fn current_end_transform(
&self,
name: &str
) -> Result<Isometry3<f64>, Error>
[src]
&self,
name: &str
) -> Result<Isometry3<f64>, Error>
pub async fn transform(
&self,
name: &str,
pose: &Isometry3<f64>
) -> Result<Isometry3<f64>, Error>
[src]
&self,
name: &str,
pose: &Isometry3<f64>
) -> Result<Isometry3<f64>, Error>
pub async fn move_ik(
&self,
name: &str,
target_pose: &Isometry3<f64>,
duration_sec: f64
) -> Result<(), Error>
[src]
&self,
name: &str,
target_pose: &Isometry3<f64>,
duration_sec: f64
) -> Result<(), Error>
pub async fn move_ik_with_interpolation(
&self,
name: &str,
target_pose: &Isometry3<f64>,
duration_sec: f64
) -> Result<(), Error>
[src]
&self,
name: &str,
target_pose: &Isometry3<f64>,
duration_sec: f64
) -> Result<(), Error>
pub async fn send_joint_positions_with_pose_interpolation(
&self,
name: &str,
positions: &[f64],
duration_sec: f64
) -> Result<(), Error>
[src]
&self,
name: &str,
positions: &[f64],
duration_sec: f64
) -> Result<(), Error>
pub fn raw_joint_trajectory_clients_names(&self) -> Vec<String>
[src]
pub fn joint_trajectory_clients_names(&self) -> Vec<String>
[src]
pub fn collision_check_clients_names(&self) -> Vec<String>
[src]
pub fn ik_clients_names(&self) -> Vec<String>
[src]
pub fn full_chain_for_collision_checker(&self) -> &Option<Arc<Chain<f64>>>
[src]
Trait Implementations
impl<S, M, N> MoveBase for RobotClient<S, M, N> where
S: Speaker,
M: MoveBase,
N: Navigation,
[src]
S: Speaker,
M: MoveBase,
N: Navigation,
fn send_velocity(&self, velocity: &BaseVelocity) -> Result<(), ArciError>
[src]
fn current_velocity(&self) -> Result<BaseVelocity, ArciError>
[src]
impl<S, M, N> Navigation for RobotClient<S, M, N> where
S: Speaker,
M: MoveBase,
N: Navigation,
[src]
S: Speaker,
M: MoveBase,
N: Navigation,
fn send_pose<'life0, 'life1, 'async_trait>(
&'life0 self,
goal: Isometry2<f64>,
frame_id: &'life1 str,
timeout: Duration
) -> Pin<Box<dyn Future<Output = Result<(), ArciError>> + Send + 'async_trait>> where
'life0: 'async_trait,
'life1: 'async_trait,
Self: 'async_trait,
[src]
&'life0 self,
goal: Isometry2<f64>,
frame_id: &'life1 str,
timeout: Duration
) -> Pin<Box<dyn Future<Output = Result<(), ArciError>> + Send + 'async_trait>> where
'life0: 'async_trait,
'life1: 'async_trait,
Self: 'async_trait,
fn current_pose(&self) -> Result<Isometry2<f64>, ArciError>
[src]
fn cancel(&self) -> Result<(), ArciError>
[src]
impl<S, M, N> Speaker for RobotClient<S, M, N> where
S: Speaker,
M: MoveBase,
N: Navigation,
[src]
S: Speaker,
M: MoveBase,
N: Navigation,
Auto Trait Implementations
impl<S, M, N> !RefUnwindSafe for RobotClient<S, M, N>
[src]
impl<S, M, N> Send for RobotClient<S, M, N>
[src]
impl<S, M, N> Sync for RobotClient<S, M, N>
[src]
impl<S, M, N> Unpin for RobotClient<S, M, N> where
M: Unpin,
N: Unpin,
S: Unpin,
[src]
M: Unpin,
N: Unpin,
S: Unpin,
impl<S, M, N> !UnwindSafe for RobotClient<S, M, N>
[src]
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
pub fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> Downcast for T where
T: Any,
T: Any,
pub fn into_any(self: Box<T, Global>) -> Box<dyn Any + 'static, Global>
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
pub fn as_any(&self) -> &(dyn Any + 'static)
pub fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
impl<T> DowncastSync for T where
T: Send + Sync + Any,
T: Send + Sync + Any,
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<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>,
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<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
pub fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
pub fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
V: MultiLane<T>,