MAGIKS  1.1
Manipulator General Inverse Kinematic Solver
 All Classes Namespaces Files Functions Variables Pages
Public Member Functions | Public Attributes | List of all members
Inverse_Kinematics Class Reference
Inheritance diagram for Inverse_Kinematics:

Public Member Functions

def __init__
 
def js_create
 
def run_dls_vdf
 
def moveto_target
 

Public Attributes

 ik_settings
 def init( self, geometry ) : # njoint): More...
 
 run_log
 fklib.Forward_Kinematics.__init__(self, DEEPCOPY(??geometry??) ) # njoint) More...
 
 initial_config
 
 damping_factor
 
 initial_config_list
 

Detailed Description

Inherits all properties and methods of a "Forward_Kinematics" class 
and has some additional properties and methods for inverse kinematic calculations
Method "update" changes the "configuration" property inherited from "Forward_Kinematics"


# goto_target (call from outside)    -- runs the suff on the grid already, calls stepwise_run or run
# stepwise_run()                   -- 
# run()                            -- run() # single run() 
# step_forward (SINGLE STEP)            -- one update_step() 

Definition at line 208 of file inverse_kinematics.py.

Constructor & Destructor Documentation

def __init__ (   self,
  config_settings,
  geo_settings,
  end_settings,
  ik_settings 
)
 

Definition at line 222 of file inverse_kinematics.py.

Member Function Documentation

def js_create (   self,
  phi_end = None,
  traj_capacity = 2,
  traj_type = 'regular' 
)
 

Definition at line 392 of file inverse_kinematics.py.

def moveto_target (   self,
  show = False 
)

Definition at line 624 of file inverse_kinematics.py.

def run_dls_vdf (   self)
runs the IK iterations following Damped Least Squares method with Variable Damping Factor
The damping factor starts from the initial value. 
At each time step, if the error norm is reduced, the joint correction is applied and the damping factor is reduced to half and 
if it is increased, the algorithm returns to previous configuration and the DF is multiplied by 2.
This will continue until the error norm is reduced or maximum number of iterations achieved.

Definition at line 447 of file inverse_kinematics.py.

Member Data Documentation

damping_factor

Definition at line 238 of file inverse_kinematics.py.

ik_settings

def init( self, geometry ) : # njoint):

Definition at line 228 of file inverse_kinematics.py.

initial_config

Definition at line 237 of file inverse_kinematics.py.

initial_config_list

Definition at line 240 of file inverse_kinematics.py.

run_log

fklib.Forward_Kinematics.__init__(self, DEEPCOPY(??geometry??) ) # njoint)

Definition at line 234 of file inverse_kinematics.py.


The documentation for this class was generated from the following file: