Pick and Place avec Matlab
V.1.1
Difficulté : difficile
Temps : ~45 min
Note
- Ce tutoriel est fonctionnel à partir de :
- La version v4.1.0 de la ned_ros_stackLa version v4.1.0 de Niryo Studio
Introduction
Ce processus consiste à prendre n’importe quel type d’objet à un endroit spécifique et à le placer à un autre endroit de manière plus ordonnée.
Objectifs
Montrez un des exemples d’applications que vous pouvez faire avec Matlab et Ned/Ned2
Avoir une première approche avec des processus industriels qui peuvent être réalisés avec Ned/Ned2
Apprendre les bases de la programmation Matlab tout en utilisant le Ned/Ned2
Prérequis
Connaissances de base de Matlab
Etre capable d’utiliser Ned/Ned2
Avoir regardé le tutoriel : Configurer Matlab et la Toolbox ROS pour Ned/Ned2
Note
Vous devez être dans cette situation pour démarrer le tutoriel
Sinon, faites ce tutoriel d’abord.
Indication
Nous vous conseillons de faire ce tutoriel avant de commencer et de vous entraîner à déplacer le robot.
Ce dont vous aurez besoin
Un Ned ou un Ned2
Un gripper (celui que vous voulez)
Un convoyeur (optionnel)
Matlab (version 2014 ou ultérieure)
Robotics System Toolbox : https://fr.mathworks.com/products/robotics.html
Une communication Wi-Fi
Note
Pour réaliser cet exemple nous avons utilisé Windows10, Matlab2022a and a Ned2.
Détails du code
ipaddress = "http://IP_OF_NED:11311"; %IP of the Ned
rosshutdown; %to be sure that an other ROS network is not actually working
setenv('ROS_MASTER_URI',ipaddress) %IP of the Ned
setenv('ROS_IP','IP_HOST_COMPUTER') %IP of the computer
rosinit(ipaddress)
Vous devez être dans cette situation.
Premièrement, essayez d’ouvrir et de fermer la pince en utilisant la toolbox Ros. De la même manière que pour le déplacement du robot, vous devez créer et envoyer un message Ros. Cette fois-ci, le sujet du message n’est pas un Point, mais un ToolGoal.
Essayez d’écrire le code vous-même. Si vous rencontrez des difficultés, vous pourrez trouver un exemple de code dans la fenêtre déroulante ci-dessous.
Ouvrir et fermer le gripper
NedState2 = rossubscriber("/niryo_robot_tools_commander/action_server/goal");
NedCmd2 = rospublisher("/niryo_robot_tools_commander/action_server/goal");
CmdMsg2 = rosmessage(NedCmd2);
CmdGoal = rosmessage('niryo_robot_tools_commander/ToolGoal');
CmdGoal.Cmd.ToolId=11;
CmdGoal.Cmd.CmdType=1; %Or 2 if you want to close the gripper
CmdGoal.Cmd.MaxTorquePercentage=100;
CmdGoal.Cmd.HoldTorquePercentage=100;
CmdGoal.Cmd.Speed=500;
CmdGoal.Cmd.Activate=1;
CmdMsg2.Header.Stamp = rostime("now") + rosduration(0.05);
CmdMsg2.GoalId.Stamp = rostime("now") + rosduration(0.05);
CmdMsg2.GoalId.Id="OPENGRIPPER"; %Or CLOSEGRIPPER
CmdMsg2.Goal=CmdGoal;
send(NedCmd2,CmdMsg2);
Avertissement
Note
Si la pince ne s’ouvre pas (ou ne se ferme pas), assurez-vous que vous avez scanné l’outil dans Niryo Studio et essayez de l’ouvrir et de le fermer, puis réessayez le script matlab.
Pour rendre le programme le plus clair possible, faites des fonctions Matlab de manière à les appeler plusieurs fois facilement. Ici, le mieux est de faire une fonction par action (move, pick et place) afin de séparer les étapes (mais vous pouvez aussi tout faire ensemble) :
Créer les fonctions Matlab
Avertissement
Pour que les fonctions fonctionnent, assurez-vous de sauvegarder les fichiers de fonction (.m) avec le même nom que la fonction.
Fonction Pick :
function pick(toolID)
NedState2 = rossubscriber("/niryo_robot_tools_commander/action_server/goal");
NedCmd2 = rospublisher("/niryo_robot_tools_commander/action_server/goal");
CmdMsg2 = rosmessage(NedCmd2);
CmdGoal = rosmessage('niryo_robot_tools_commander/ToolGoal');
CmdGoal.Cmd.ToolId=toolID;
CmdGoal.Cmd.CmdType=2;
CmdGoal.Cmd.MaxTorquePercentage=100;
CmdGoal.Cmd.HoldTorquePercentage=100;
CmdGoal.Cmd.Speed=500;
CmdGoal.Cmd.Activate=1;
CmdMsg2.Header.Stamp = rostime("now") + rosduration(0.05);
CmdMsg2.GoalId.Stamp = rostime("now") + rosduration(0.05);
CmdMsg2.GoalId.Id="CLOSEGRIPPER";
CmdMsg2.Goal=CmdGoal;
send(NedCmd2,CmdMsg2);
Fonction Place :
function pick(toolID)
NedState2 = rossubscriber("/niryo_robot_tools_commander/action_server/goal");
NedCmd2 = rospublisher("/niryo_robot_tools_commander/action_server/goal");
CmdMsg2 = rosmessage(NedCmd2);
CmdGoal = rosmessage('niryo_robot_tools_commander/ToolGoal');
CmdGoal.Cmd.ToolId=toolID;
CmdGoal.Cmd.CmdType=2;
CmdGoal.Cmd.MaxTorquePercentage=100;
CmdGoal.Cmd.HoldTorquePercentage=100;
CmdGoal.Cmd.Speed=500;
CmdGoal.Cmd.Activate=1;
CmdMsg2.Header.Stamp = rostime("now") + rosduration(0.05);
CmdMsg2.GoalId.Stamp = rostime("now") + rosduration(0.05);
CmdMsg2.GoalId.Id="CLOSEGRIPPER";
CmdMsg2.Goal=CmdGoal;
send(NedCmd2,CmdMsg2);
Fonction Move :
function move(ned,vect,eul)
ik = inverseKinematics("RigidBodyTree", ned);
weight = [0.1 0.1 0 1 1 1];
initialguess = ned.homeConfiguration;
XYZ=vect;
RPY=eul;
postform=trvec2tform(XYZ);
eultform=eul2tform(RPY,'ZYX');
tform=postform*eultform;
configSoln = ik("end_effector", tform, weight, initialguess);
cell = struct2cell(configSoln);
Joint = cell(2,:,:);
matrixJoints = cell2mat(Joint);
NedState = rossubscriber("/niryo_robot_follow_joint_trajectory_controller/state");
NedCmd = rospublisher("/niryo_robot_follow_joint_trajectory_controller/command");
CmdMsg = rosmessage(NedCmd);
CmdPoint = rosmessage('trajectory_msgs/JointTrajectoryPoint');
for i=1:6
CmdPoint.Positions(i) = matrixJoints(i);
end
CmdPoint.Velocities = zeros(1,6);
CmdPoint.Accelerations = zeros(1,6);
CmdPoint.TimeFromStart = ros.msg.Duration(3);
CmdMsg.Header.Stamp = rostime("now") + rosduration(0.05);
CmdMsg.JointNames = {'joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6'};
CmdMsg.Points = CmdPoint;
send(NedCmd,CmdMsg);
Note
Pour la fonction move, vous devez d’abord écrire les lignes suivantes dans votre fichier principal, avant d’appeler la fonction.
ned=importrobot(ned.urdf);
eeoffset = 0
eeBody = robotics.RigidBody("end_effector")
setFixedTransform(eeBody.Joint, trvec2tform([eeoffset,0,0]))
addBody(niryo_one, eeBody, "tool_link");
Pour finir cet exemple, essayez de faire une boucle pour répéter le mouvement. Ainsi, vous pouvez reproduire le mouvement comme dans une ligne de production. Voici le code final :
Faire une boucle
ned=importrobot(ned.urdf);
eeoffset = 0
eeBody = robotics.RigidBody("end_effector")
setFixedTransform(eeBody.Joint, trvec2tform([eeoffset,0,0]))
addBody(niryo_one, eeBody, "tool_link");
while 1
%Pick
move(ned,[0.25 -0.2 0.3],[0 0 0]);
pause(4);
pick(11);
pause(0.5);
%Intermediate position
move(ned,[0.35 0 0.3],[0 0 0]);
pause(0.5);
%Place
move(ned,[0.25 0.2 0.3],[0 0 0]);
pause(4);
place(11);
pause(0.5);
end
Maintenant tout ce que vous avez à faire est de changer les positions de pick et de place, choisir lebon ToolID, et vous pouvez faire un pick and place avec Matlab.
Note
Vous pouvez trouver toutes les informations concernant l’utilisation de Ned/Ned2 avec Matlab et la ROS Toolbox en suivant les deux tutoriels ci-dessous :