Вода один, калибровка руки-глаза + робот-манипулятор jaka

искусственный интеллект
Вода один, калибровка руки-глаза + робот-манипулятор jaka

Всем привет, меня зовут Сяочжи. В прошлые выходные я сделал дома 3D-реконструкцию робота-манипулятора + лидар и снял демонстрационное видео. Однако, поскольку эта платформа не поддерживает это, заинтересованные студенты могут подписаться на официальный аккаунт:остроумие,Проверять

Недавно я публиковал статьи, связанные с калибровкой рук и глаз.Вчера днем ​​я думал, что мои одноклассники завершили калибровку программы с руками вне глаз.Я чувствовал, что код, который я написал ранее, был не очень дружелюбным, поэтому я решил обновить его снова На следующей неделе лекция о том, как использовать робот-манипулятор jaka для выполнения калибровки руки и глаза.

jaka机械臂.png

О яке

Роботизированная рука Jaka заставляет Xiaozhi чувствовать, что хорошо то, что их обучающая подвеска очень удобна в использовании.Это нужно похвалить, но есть и недостатки.Когда вы хотите разрабатывать во второй раз, SDK не очень прост в использовании. , это уроки крови.

Метод, представленный на этот раз, использует позу конца манипулятора, полученную протоколом связи TCP компании jaka, поэтому вам необходимо настроить IP-адрес манипулятора в программе.

  jaka标定程序会自己订阅两个话题的数据,一个是机械臂的位姿话题和相机中标定物的位姿话题。
  本次文章默认大家已经学会使用aruco获取到标定板在机械臂中的位姿,如果有不清楚的可以关注公众号:机智人
  后台回复手眼标定获取相关文章,项目开源地址:https://gitee.com/ohhuo/handeye-calib

手眼标定位姿关系.png

Принцип ручной калибровки

  jaka标定程序会自己订阅两个话题的数据,一个是机械臂的位姿话题和相机中标定物的位姿话题。

Тему робота-манипулятора можно получить, запустив jaka_comuniate.launch в пакете jaka_comuniate в этом репозитории. Для получения информации о позах маркеров в камере вы можете обратиться к предыдущей статье или ответить на калибровку рук и глаз в фоновом режиме, чтобы получить руководство.

Загрузите исходный код:

git clone https://gitee.com/ohhuo/handeye-calib.git
cd handeye-calib
catkin_make or catkin build

После завершения загрузки вам необходимо настроить параметр jaka_host как хост, на котором находится ваша роботизированная рука jaka, и убедиться, что компьютер, который вы сейчас используете, можетpingпройти ИП.

Будет опубликовано после запуска узлаjaka_poseтему и запустить

Используется TCP-связь манипулятора jaka.Порт по умолчанию 10000. Нет необходимости устанавливать его здесь.Если есть какие-либо изменения, их можно изменить в программе.

<launch>
    <arg  name="jaka_host"   default="192.168.1.103" />
    <node pkg="jaka_comuniate" type="jaka_comuniate" name="jaka_comuniate" output="screen" >
         <param name="jaka_host" value="$(arg jaka_host)" />
    </node>
</launch>

Запустите узел JAKA

source devel/setup.bash
roslaunch jaka_comuniate jaka_comuniate.launch 

Запустите программу идентификации калибровочной пластины

source devel/setup.bash
roslaunch handeye-calib aruco_start_usb_cam.launch

Настройте информацию о теме, необходимую для калибровки

Основными параметрами конфигурации являютсяjaka_pose_topic,camera_pose_topic. Представляют коммуникационный адрес манипулятора jaka и тему позы маркера в камере соответственно.

通过这两个话题我们就可以拿到机械臂和标志物在相机中的位姿信息.
<launch>
  <!-- The arm tool Pose Topic,Use ros geometry_msgs::Pose-->
  <arg   name="jaka_pose_topic"   default="/jaka_pose" />
  <!-- The arm marker in camera Pose Topic,Use ros geometry_msgs::Pose-->
  <arg   name="camera_pose_topic"   default="/aruco_single/pose" />

  <node pkg="handeye-calib" type="jaka_hand_on_eye_calib.py" name="jaka_hand_on_eye_calib" output="screen" >
       <param name="jaka_pose_topic" value="$(arg jaka_pose_topic)" />
       <param name="camera_pose_topic" value="$(arg camera_pose_topic)" />
  </node>
</launch>

Запустите процедуру калибровки

source devel/setup.bash
roslaunch handeye-calib jaka_hand_on_eye_calib.launch

начать калибровку

Когда программа запустится, она обнаружит данные темы. Сначала она обнаружит, получены ли данные манипулятора робота. Если нет, она будет ждать вечно. Когда будет обнаружено, что данные были получены, появится командная строка. Команды определены следующим образом:

r  rocord    记录一组手眼数据(当记录的数据大于程序计算所需的数据量之后会进行自动计算)
c  calculate 计算当前数据
s  save      保存数据
p  print     打印当前数据到屏幕上(格式为 type,x,y,z,rx,ry,rz 角度制)
q  quit      退出标定程序
[INFO] [1612856654.307437]: Get topic from param server: jaka_pose_topic:/jaka_pose camera_pose_topic:/aruco_single/pose
[INFO] [1612856655.311045]: Waiting jaka pose topic data ...
[INFO] [1612856656.313039]: Waiting jaka pose topic data ...
[INFO] [1612856657.314364]: Waiting jaka pose topic data ...
input:  r     record,c    calculate,s     save,q    quit:

Перетащите манипулятор или переместите манипулятор с калибратором, но убедитесь, что калибровочная плата все еще видна в поле зрения камеры. входитьrНабор данных руки-глаза записывается.

Сгенерировать параметры

После завершения калибровки введите s для сохранения, и данные результатов калибровки и данные, использованные в расчете, будут сохранены. Анализ ошибок результатов калибровки Размер стандартного отклонения результатов расчета наблюдаемых данных.

После каждого расчета программа будет выводить среднее значение, дисперсию и стандартное отклонение точек результата калибровки по различным алгоритмам.

由于标定过程中标定板是没有发生移动的,所以我们通过机械臂的末端位置、标定结果(手眼矩阵)、标记物在相机中的位姿即可
计算出标定板在机器人基坐标系下的位姿,如果标定结果准确该位姿应该是没有变化的。

Колебание окончательных данных можно сравнить, чтобы определить качество результата калибровки.

Например:

Позиция 1 калибровочной доски в базовой системе координат манипулятора:

Tsai-Lenz               x            y             z            rx            ry           rz     distance
-----------  ------------  -----------  ------------  ------------  ------------  -----------  -----------
point0       -0.45432      0.0488783     0.000316595   0.0420852    -0.0245641    1.52064      0.456941
point1       -0.457722     0.054523      0.0121959    -0.0266793     0.0050922    1.53391      0.461119
point2       -0.457198     0.0535639     0.00246136    0.0252805    -0.0329136    1.51927      0.460331
point3       -0.453302     0.0618366     0.00165179    0.0405718    -0.0472311    1.53318      0.457503
point4       -0.455802     0.0589413     0.000377679   0.0222521    -0.0360589    1.51963      0.459598
point5       -0.455392     0.0615103     0.00584822    0.0365886    -0.033448     1.50684      0.459565
point6       -0.451144     0.0571198     0.00498852    0.0618337    -0.0170326    1.52463      0.454773
point7       -0.452829     0.0588266    -0.000827528   0.0324858    -0.0292652    1.52268      0.456635
point8       -0.454238     0.063634      0.00488078    0.0411648    -0.0373725    1.51611      0.458699
point9       -0.453579     0.0631788     0.00390939    0.0339742    -0.0645821    1.53168      0.457974
point10      -0.454952     0.066057     -0.00144969    0.0399135     0.0029201    1.5053       0.459725
point11      -0.459518     0.0553877    -0.00209946    0.0450864    -0.0147387    1.50702      0.462848
point12      -0.454928     0.0590754    -0.0045181     0.0297534    -0.0296122    1.52043      0.45877
point13      -0.455234     0.0527075    -0.00389213    0.0358822    -0.0260668    1.51244      0.458292
mean         -0.455011     0.0582314     0.0017031     0.0328709    -0.027491     1.51955      0.45877
var           4.21677e-06  2.16484e-05   1.84365e-05   0.000357231   0.000305579  8.29112e-05  3.79771e-06
std           0.00205348   0.00465279    0.00429378    0.0189005     0.0174808    0.00910556   0.00194877

Позиция 2 калибровочной доски в базовой системе координат манипулятора:

Tsai-Lenz              x            y            z           rx            ry           rz     distance
-----------  -----------  -----------  -----------  -----------  ------------  -----------  -----------
point0       -0.428394    0.052448     0.0353171    0.0259549    -0.0541487    1.57929      0.433035
point1       -0.427841    0.0448442    0.0345359    0.0454481    -0.0371304    1.55639      0.431569
point2       -0.424889    0.0486165    0.0278942    0.0455775    -0.0438353    1.57073      0.42857
point3       -0.421985    0.0485442    0.0311218    0.0138094    -0.0307286    1.55606      0.425906
point4       -0.428353    0.0454091    0.0326252    0.039192     -0.0492181    1.59177      0.431987
point5       -0.432111    0.0458869    0.0359774    0.04632      -0.0383476    1.55942      0.436028
mean         -0.427262    0.0476248    0.0329119    0.0360503    -0.0422348    1.56894      0.431183
var           9.9672e-06  6.79218e-06  7.71397e-06  0.000148499   6.11379e-05  0.000174299  1.03945e-05
std           0.00315709  0.00260618   0.0027774    0.012186      0.00781908   0.0132022    0.00322405

Мы можем наблюдать стандартное отклонение расстояния между двумя результатами калибровки.Стандартное отклонение в первый раз меньше, чем стандартное отклонение во второй раз, что означает, что результат калибровки в первый раз лучше, чем во второй раз.

标准差越小,数据越聚集。

Если есть что-то неясное или неправильное, пожалуйста, оставьте сообщение. Наконец, приглашаем всех подписаться, поставить лайк и поделиться ~

В следующей лекции я расскажу в целом, как использовать библиотеку с открытым исходным кодом на роботизированной руке AUBO, пожалуйста, продолжайте обращать внимание~

Отсканируйте код, чтобы следоватьостроумие, позвольте вам сделать самого умного робота