openrr_client

Type Alias ArcRobotClient

Source
pub type ArcRobotClient = RobotClient<Arc<dyn Localization>, Arc<dyn MoveBase>, Arc<dyn Navigation>>;

Aliased Type§

struct ArcRobotClient { /* 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>