Library for controlling #MeArm from phenoptix (http://www.phenoptix.com/collections/mearm). Solves inverse kinematics of the arm to position gripper in 3D space.
Dependents: wizArm_WIZwiki-W7500ECO wizArm_WIZwiki-W7500ECO MeArm_Lab2_Task1 MeArm_Lab3_Task1 ... more
MeArm Class Reference
Library for controlling the MeArm (https://shop.mime.co.uk) More...
#include <MeArm.h>
Public Member Functions | |
MeArm (PinName middle_pin, PinName left_pin, PinName right_pin, PinName claw_pin) | |
Create a MeArm object connected to the specified pins. | |
~MeArm () | |
Destructor. | |
void | set_claw_calibration_values (int open_val, int closed_val) |
Calibrate the claw servo. | |
void | set_middle_calibration_values (int zero, int ninety) |
Calibrate the middle servo. | |
void | set_left_calibration_values (int zero, int ninety) |
Calibrate the left servo. | |
void | set_right_calibration_values (int zero, int ninety) |
Calibrate the left servo. | |
void | set_claw (float value) |
Control the claw. | |
void | goto_xyz (float x, float y, float z) |
Move end-effector to position. |
Detailed Description
Library for controlling the MeArm (https://shop.mime.co.uk)
Revision 1.1
- Date:
- June 2017
#include "mbed.h" #include "MeArm.h " // create MeArm object - base, shoulder, elbow, gripper MeArm arm(p21,p22,p23,p24); AnalogIn m_pot(p17); AnalogIn l_pot(p18); AnalogIn r_pot(p19); AnalogIn c_pot(p20); int main() { // open , closed arm.set_claw_calibration_values(1450,2160); // 0 , 90 arm.set_middle_calibration_values(1650,2700); arm.set_right_calibration_values(2000,1000); arm.set_left_calibration_values(1870,850); while(1) { float x = 100.0 + 100.0*m_pot.read(); float y = -140.0 + 280.0*l_pot.read(); float z = 150.0*r_pot.read(); float claw_val = c_pot.read(); // 0.0 to 1.0 arm.set_claw(claw_val); arm.goto_xyz(x,y,z); wait(0.2); } }
Definition at line 61 of file MeArm.h.
Constructor & Destructor Documentation
MeArm | ( | PinName | middle_pin, |
PinName | left_pin, | ||
PinName | right_pin, | ||
PinName | claw_pin | ||
) |
Member Function Documentation
void goto_xyz | ( | float | x, |
float | y, | ||
float | z | ||
) |
void set_claw | ( | float | value ) |
void set_claw_calibration_values | ( | int | open_val, |
int | closed_val | ||
) |
void set_left_calibration_values | ( | int | zero, |
int | ninety | ||
) |
void set_middle_calibration_values | ( | int | zero, |
int | ninety | ||
) |
Generated on Wed Jul 13 2022 02:33:16 by 1.7.2