[−][src]Struct gear::JointPathPlannerWithIK
Joint path planner which supports inverse kinematics
Fields
path_planner: JointPathPlanner<T>
Joint Path Planner to be used to find collision free path
Currently, JointPathPlanner<N, k::Chain<N>>
is used.
ik_solver: I
Inverse kinematics solver to find the goal joint angles
Implementations
impl<T, I> JointPathPlannerWithIK<T, I> where
T: RealField + SubsetOf<f64> + Float,
I: InverseKinematicsSolver<T>,
[src]
T: RealField + SubsetOf<f64> + Float,
I: InverseKinematicsSolver<T>,
pub fn new(path_planner: JointPathPlanner<T>, ik_solver: I) -> Self
[src]
Create instance from JointPathPlannerBuilder
and InverseKinematicsSolver
Example
// Create path planner with loading urdf file and set end link name let planner = gear::JointPathPlannerBuilder::from_urdf_file("sample.urdf") .unwrap() .collision_check_margin(0.01) .finalize(); // Create inverse kinematics solver let solver = gear::JacobianIKSolver::default(); // Create path planner with IK solver let _planner = gear::JointPathPlannerWithIK::new(planner, solver);
pub fn urdf_robot(&self) -> &Option<Robot>
[src]
pub fn solve_ik(
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>
) -> Result<(), Error>
[src]
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>
) -> Result<(), Error>
Just solve IK and do not plan
pub fn solve_ik_with_constraints(
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
c: &Constraints
) -> Result<(), Error>
[src]
&mut self,
arm: &SerialChain<T>,
target_pose: &Isometry3<T>,
c: &Constraints
) -> Result<(), Error>
Just solve IK with constraints and do not plan
pub fn colliding_link_names(&self, objects: &Compound<T>) -> Vec<String>
[src]
pub fn plan_with_ik(
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>
) -> Result<Vec<Vec<T>>, Error>
[src]
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>
) -> Result<Vec<Vec<T>>, Error>
Solve IK and get the path to the final joint positions
pub fn plan_with_ik_with_constraints(
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>,
constraints: &Constraints
) -> Result<Vec<Vec<T>>, Error>
[src]
&mut self,
target_name: &str,
target_pose: &Isometry3<T>,
objects: &Compound<T>,
constraints: &Constraints
) -> Result<Vec<Vec<T>>, Error>
Solve IK with constraints and get the path to the final joint positions
pub fn plan_joints<K>(
&mut self,
use_joints: &Chain<T>,
start_angles: &[T],
goal_angles: &[T],
objects: &Compound<T>
) -> Result<Vec<Vec<T>>, Error>
[src]
&mut self,
use_joints: &Chain<T>,
start_angles: &[T],
goal_angles: &[T],
objects: &Compound<T>
) -> Result<Vec<Vec<T>>, Error>
Do not solve IK but get the path to the target joint positions
pub fn update_transforms(&self) -> Vec<Isometry3<T>>
[src]
Calculate the transforms of all of the links
pub fn joint_names(&self) -> Vec<String>
[src]
Get the names of the links
Auto Trait Implementations
impl<T, I> !RefUnwindSafe for JointPathPlannerWithIK<T, I>
[src]
impl<T, I> Send for JointPathPlannerWithIK<T, I> where
I: Send,
T: Scalar,
[src]
I: Send,
T: Scalar,
impl<T, I> Sync for JointPathPlannerWithIK<T, I> where
I: Sync,
T: Scalar,
[src]
I: Sync,
T: Scalar,
impl<T, I> Unpin for JointPathPlannerWithIK<T, I> where
I: Unpin,
T: Scalar + Unpin,
[src]
I: Unpin,
T: Scalar + Unpin,
impl<T, I> !UnwindSafe for JointPathPlannerWithIK<T, I>
[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>,