Package intera_interface :: Module head :: Class Head
[hide private]
[frames] | no frames]

Class Head

source code

object --+
         |
        Head

Interface class for the head on an Intera Robot.

Used to control the head pan angle.

Instance Methods [hide private]
 
__init__(self)
Constructor.
source code
 
_on_head_state(self, msg) source code
bool
blocked(self)
Check if the head is currently blocked from movement.
source code
 
pan_mode(self)
Get the mode the head is currently acting in.
source code
float
pan(self)
Get the current pan angle of the head.
source code
bool
panning(self)
Check if the head is currently panning.
source code
 
set_pan(self, angle, speed=1.0, timeout=10.0, active_cancellation=False)
Pan at the given speed to the desired angle.
source code

Inherited from object: __delattr__, __format__, __getattribute__, __hash__, __new__, __reduce__, __reduce_ex__, __repr__, __setattr__, __sizeof__, __str__, __subclasshook__

Properties [hide private]

Inherited from object: __class__

Method Details [hide private]

__init__(self)
(Constructor)

source code 

Constructor.

Overrides: object.__init__

blocked(self)

source code 

Check if the head is currently blocked from movement. Get the current pan angle of the head. This can only be true if 'pan_mode' is ACTIVE_CANCELLATION_MODE.

Returns: bool
True if the head is currently blocked, False otherwise.

pan_mode(self)

source code 

Get the mode the head is currently acting in.

@rtype: string
@return: current mode -
         'PASSIVE_MODE'(0) : Compliant to user-induced external movement
         'ACTIVE_MODE' (1)  : Actively responds to absolute commanded
                            position
                            Command limits are actual joint limits.
         'ACTIVE_CANCELLATION_MODE' (2) : Actively responds to commanded
                                   head position relative to the
                                   current position of robot base frame

pan(self)

source code 

Get the current pan angle of the head.

Returns: float
current angle in radians

panning(self)

source code 

Check if the head is currently panning.

Returns: bool
True if the head is currently panning, False otherwise.

set_pan(self, angle, speed=1.0, timeout=10.0, active_cancellation=False)

source code 

Pan at the given speed to the desired angle.

Parameters:
  • angle (float) - Desired pan angle in radians.
  • speed (int) - Desired speed to pan at, range is 0-1.0 [1.0]
  • timeout (float) - Seconds to wait for the head to pan to the specified angle. If 0, just command once and return. [10]
  • active_cancellation (bool) - Specifies if the head should aim at a location in the base frame. If this is set to True, the "angle" param is measured with respect to the "/base" frame, rather than the actual head joint value. Valid range is [-pi, pi) radians.