Classes | Functions
nao_driver::util::nao_footstep_clipping Namespace Reference

Classes

class  Params

Functions

def clip_data
def clip_footstep
def clip_footstep_on_gait_config
def clip_footstep_to_avoid_collision
def clip_footstep_tuple
def clip_footstep_with_ellipse

Function Documentation

def nao_driver.util.nao_footstep_clipping.clip_data (   min,
  max,
  value 
)
Clip value between two extremes. 

Definition at line 32 of file nao_footstep_clipping.py.

def nao_driver.util.nao_footstep_clipping.clip_footstep (   foot,
  is_left_support 
)
Clipping functions to avoid any warnings and undesired effects
    when sending the footsteps to ALMotion.
    foot is an almath.Pose2D (x, y, theta position)
    is_left_support must be set to True if the move is on the right leg
    (the robot is supporting itself on the left leg).

Definition at line 105 of file nao_footstep_clipping.py.

Clip the foot move so that it does not exceed the maximum
    size of steps.
    foot is an almath.Pose2D (x, y, theta position).
    is_left_support must be set to True if the move is on the right leg
    (the robot is supporting itself on the left leg).

Definition at line 44 of file nao_footstep_clipping.py.

Clip the foot move to avoid collision with the other foot.
    foot is an almath.Pose2D (x, y, theta position).
    is_left_support must be set to True if the move is on the right leg
    (the robot is supporting itself on the left leg).

Definition at line 94 of file nao_footstep_clipping.py.

def nao_driver.util.nao_footstep_clipping.clip_footstep_tuple (   foot,
  is_left_support 
)
Wrapper of clip_footstep to handle 'foot' as geometry_msgs.Pose2D.
'foot' is a tuple (x, y, theta). A tuple (x_clip, y_clip, theta_clip) is
returned.

Definition at line 121 of file nao_footstep_clipping.py.

Clip the foot move inside an ellipse defined by the foot's dimansions.
    foot is an almath.Pose2D (x, y, theta position).

Definition at line 68 of file nao_footstep_clipping.py.



nao_driver
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Séverin Lemaignan
autogenerated on Mon Oct 6 2014 02:39:17