![]() |
Bioscara
DALSA's DIY SCARA Robot Arm.
|
Child class implementing control of the hardware gripper. More...
#include <mGripper.h>
Public Member Functions | |
| Gripper (float reduction, float offset, float min, float max, float backup_init_pos) | |
| Construct a new Gripper object. | |
| err_type_t | enable (void) override |
| Activates the the hardware. | |
| err_type_t | disable (void) override |
| Deactivates the hardware. | |
| err_type_t | setPosition (float width) override |
| Sets the gripper width in m. | |
| err_type_t | setServoPosition (float angle) |
| Sets the servo position of the gripper actuator in degrees. | |
Public Member Functions inherited from bioscara_hardware_drivers::BaseGripper | |
| BaseGripper (float reduction, float offset, float min, float max, float backup_init_pos) | |
| Construct a new BaseGripper object. | |
| ~BaseGripper (void) | |
| Destroy the BaseGripper object. | |
| virtual err_type_t | init (void) |
| Initializes the gripper. | |
| virtual err_type_t | deinit (void) |
| Deinitializes the gripper. | |
| virtual err_type_t | getPosition (float &width) |
| Gets the gripper width. | |
| virtual void | setReduction (float reduction) |
| Manually set reduction. | |
| virtual void | setOffset (float offset) |
| Manually set offset. | |
Protected Attributes | |
| RPI_PWM | _pwm |
| RPI_PWM object to generate PWM voltage for servo control. | |
| int | _freq = 50 |
| PWM frequency in Hz. | |
Protected Attributes inherited from bioscara_hardware_drivers::BaseGripper | |
| float | _reduction = 1 |
| gripper width to actuator reduction ratio | |
| float | _offset = 0 |
| gripper width position offset | |
| float | _min = 0 |
| gripper width lower limit | |
| float | _max = 0 |
| gripper width upper limit | |
| float | _backup_init_pos = 0.0 |
| Initial position assumed if none can be retrieved from the buffer file. | |
| float | _pos = _backup_init_pos |
| stored position | |
| float | _pos_get = _pos |
| reported position | |
Additional Inherited Members | |
Protected Member Functions inherited from bioscara_hardware_drivers::BaseGripper | |
| err_type_t | save_last_position (float pos) |
| Stores the latest position to the buffer file. | |
| err_type_t | retrieve_last_position (float &pos) |
| Retrieves the stored position from the buffer file. | |
Child class implementing control of the hardware gripper.
Use this class if you wish to control the actual hardware by generating a PWM voltage on GPIO18 of the Raspberry Pi.
| bioscara_hardware_drivers::Gripper::Gripper | ( | float | reduction, |
| float | offset, | ||
| float | min, | ||
| float | max, | ||
| float | backup_init_pos | ||
| ) |
Construct a new Gripper object.
see the BaseGripper constructor for a description of the parameters.
|
overridevirtual |
Deactivates the hardware.
Invokes BaseGripper::disable() and stops the servo by disableing the PWM generation.
Reimplemented from bioscara_hardware_drivers::BaseGripper.
|
overridevirtual |
Activates the the hardware.
Invokes BaseGripper::enable() and starts the PWM generation but does not set a position. Must be called before a position is set. The PWM pin is GPIO18 on the Raspberry Pi 4. PWM chip is 0, channel 0.
Reimplemented from bioscara_hardware_drivers::BaseGripper.
|
overridevirtual |
Sets the gripper width in m.
Invokes BaseGripper::setPosition(), transforms the desired gripper width to a servo angle using the JOINT2ACTUATOR() macro and finally sets the servo position using setServoPosition()
| width | width in m. |
Reimplemented from bioscara_hardware_drivers::BaseGripper.
| err_type_t bioscara_hardware_drivers::Gripper::setServoPosition | ( | float | angle | ) |
Sets the servo position of the gripper actuator in degrees.
Calculates a PWM dutycycle for the desired servo angle and invokes RPI_PWM::setDutyCycle() to set it.
| angle | in degrees. |
|
protected |
PWM frequency in Hz.
|
protected |
RPI_PWM object to generate PWM voltage for servo control.