Compare commits

...

7 Commits

Author SHA1 Message Date
Estevan BIAU-LOYER 4599d0e980 Update 'README.md' 2023-03-16 21:20:45 +01:00
Estevan BIAU-LOYER 5bf32466cb Merge branch 'estevan' into main 2023-03-16 21:02:43 +01:00
Estevan BIAU-LOYER fcbce8ff8a a 2023-03-16 21:02:05 +01:00
Estevan BIAU-LOYER 1717146c04 commitado del finalo 2023-03-16 20:59:49 +01:00
Estevan BIAU-LOYER 36053ed29c Last commit 2023-03-16 20:55:48 +01:00
Estevan BIAU-LOYER 8360eda477 amongus commitado 2023-03-10 09:45:04 +01:00
Estevan BIAU-LOYER 507b6489f8 first commit 2023-03-10 08:21:20 +01:00
6 changed files with 125 additions and 2 deletions

1
DynamixelSDK Submodule

@ -0,0 +1 @@
Subproject commit ef7ae1f6fc7f58f7276859244acc231297632d4d

11
Makefile Normal file
View File

@ -0,0 +1,11 @@
all: dynamixel main
g++ DynamixelHandler.o main.o -L/usr/local/lib -ldxl_x64_cpp -lrt
dynamixel: /home/estevan/EENG3/robotarm/toolkit-dynamixel/src/DynamixelHandler.cpp
g++ -c /home/estevan/EENG3/robotarm/toolkit-dynamixel/src/DynamixelHandler.cpp -I./toolkit-dynamixel/include toolkit-dynamixel/src/DynamixelHandler.cpp
main: main.cpp
g++ -c main.cpp -I./toolkit-dynamixel/include main.cpp
clean:
rm *.o
rm *.exe

View File

@ -1,3 +1,3 @@
# robotarm
We love robots UwU
make a robot arm works

109
main.cpp Normal file
View File

@ -0,0 +1,109 @@
#include <iostream>
#include <chrono>
#include <thread>
#include "DynamixelHandler.h"
// Global variables
DynamixelHandler _oDxlHandler;
std::string _poppyDxlPortName = "/dev/ttyUSB0";
float _poppyDxlProtocol = 2.0;
int _poppyDxlBaudRate = 1000000;
int _nbJoints = 6;
int i = 0;
float _minJointCmd = 0;
float _maxJointCmd = 1023;
float _minJointAngle = -180.0f;
float _maxJointAngle = 180.0f;
int convertAnglesToJointCmd(float fJointAngle)
{
// y = ax + b
float a = (_maxJointCmd-_minJointCmd) / (_maxJointAngle - _minJointAngle);
float b = _minJointCmd - a * _minJointAngle;
float jointCmd = a * fJointAngle + b;
return (int)jointCmd;
}
void goToHomePosition() // This function sets all the servos to their home position except the gripper servo
{
std::vector<uint16_t> l_vTargetJointPosition;
for (int l_joint = 1; l_joint < _nbJoints; l_joint++)
{
l_vTargetJointPosition.push_back(convertAnglesToJointCmd(0.0f));
}
int l_joint=6;
if (l_joint= 6)
{
l_vTargetJointPosition.push_back(convertAnglesToJointCmd(30.0f));
}
_oDxlHandler.sendTargetJointPosition(l_vTargetJointPosition);
}
void gripperControl() // This function sets all the servos to their current position(meaning they wont move from whichever position they were in) And closes the gripper to hold the cube
{
std::vector<uint16_t> l_vCurrentJointPosition;
_oDxlHandler.readCurrentJointPosition(l_vCurrentJointPosition);
// display current joint position
// Calculate the target joint command based on the desired angle
std::vector<uint16_t> l_vTargetJointPosition;
for (int l_joint = 1; l_joint < _nbJoints; l_joint++)
{
l_vTargetJointPosition.push_back(convertAnglesToJointCmd(l_vCurrentJointPosition[l_joint]));
}
int l_joint=6;
if (l_joint= 6)
{
l_vTargetJointPosition.push_back(convertAnglesToJointCmd(30.0f));
}
_oDxlHandler.sendTargetJointPosition(l_vTargetJointPosition);
}
int main()
{
std::cout << "===Initialization of the Dynamixel Motor communication====" << std::endl;
_oDxlHandler.setDeviceName(_poppyDxlPortName);
_oDxlHandler.setProtocolVersion(_poppyDxlProtocol);
_oDxlHandler.openPort();
_oDxlHandler.setBaudRate(_poppyDxlBaudRate);
_oDxlHandler.enableTorque(true);
std::cout << std::endl;
// read current joint position
std::vector<uint16_t> l_vCurrentJointPosition;
_oDxlHandler.readCurrentJointPosition(l_vCurrentJointPosition);
// display current joint position
std::cout << "vCurrentJointPosition= (" << std::endl;
for (int l_joint=0; l_joint < l_vCurrentJointPosition.size(); l_joint++)
{
std::cout << l_vCurrentJointPosition[l_joint] << ", ";
}
std::cout << ")" << std::endl;
std::vector<uint16_t> l_vTargetJointPosition;
_oDxlHandler.readCurrentJointPosition(l_vTargetJointPosition);
std::cout << "vCurrentJointPosition= (" << std::endl;
for (int l_joint=0; l_joint < l_vCurrentJointPosition.size(); l_joint++)
std::cout << l_vCurrentJointPosition[l_joint] << ", ";
std::cout << ")" << std::endl;
gripperControl(); // Catch the cube
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
goToHomePosition(); //Take the cube up to home position
// wait 1s
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
std::cout << "===Closing the Dynamixel Motor communication====" << std::endl;
_oDxlHandler.enableTorque(false);
_oDxlHandler.closePort();
std::cout << std::endl;
return 0;
}

1
toolkit-dynamixel Submodule

@ -0,0 +1 @@
Subproject commit 94e8849aa1dce1c20b6ef1d0245d06a765cccaca

1
toolkit-kinematics Submodule

@ -0,0 +1 @@
Subproject commit e1f43f40ba62381baa2ce328c3dfe910ecf75a30