Haply hAPI  V4.0
Haply Haptic API
Actuator Class Reference

Public Member Functions

 Actuator ()
 
 Actuator (int actuator, int direction, int port)
 
void set_actuator (int actuator)
 
void set_direction (int direction)
 
void set_port (int port)
 
void set_torque (float torque)
 
int get_actuator ()
 
int get_direction ()
 
int get_port ()
 
float get_torque ()
 

Constructor & Destructor Documentation

◆ Actuator() [1/2]

Actuator.Actuator ( )

Creates an Actuator using motor port position 1

◆ Actuator() [2/2]

Actuator.Actuator ( int  actuator,
int  direction,
int  port 
)

Creates an Actuator using the given motor port position

Parameters
actuatoractuator index
portmotor port position for actuator

Member Function Documentation

◆ get_actuator()

int Actuator.get_actuator ( )
Returns
actuator index

◆ get_direction()

int Actuator.get_direction ( )
Returns
actuator direction

◆ get_port()

int Actuator.get_port ( )
Returns
current motor port position in use

◆ get_torque()

float Actuator.get_torque ( )
Returns
current torque information

◆ set_actuator()

void Actuator.set_actuator ( int  actuator)

Set actuator index parameter of sensor

Parameters
actuatorindex

◆ set_direction()

void Actuator.set_direction ( int  direction)

Set actuator rotation direction

Parameters
directionof rotation

◆ set_port()

void Actuator.set_port ( int  port)

Sets motor port position to be used by Actuator

Parameters
portmotor port position

◆ set_torque()

void Actuator.set_torque ( float  torque)

Sets torque variable to the given torque value

Parameters
torquenew torque value for update

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