UARM机械臂试用体验及ROS键盘控制程序开发
本帖最后由 lfshit 于 2015-10-9 23:02 编辑关注EVOL团队研发的UARM机械臂很久了。偶然在Arduino论坛上面发现了帖子:http://www.arduino.cn/forum.php?mod=viewthread&tid=16407&highlight=uarm。竟然可以申请免费拥有UARM机械臂!!! 这对于急切想深入研究机械臂、丰富项目经验的我来说,就像是嚼着馅饼的林黛玉从天而降! 有幸抓住了这个机会,为完成约定,现分享第一篇项目报告!(小弟为新手,求指教、求轻拍)
一、UARM机械臂试用体验 2015年9月23日,收到UARM机械臂,包含机械臂本体、气泵模块。未到的蓝牙模块、手爪模块待下次寄过来。随即,满怀新奇与激动地与几个小伙伴开始研究如何让这个宝贝动起来。 仔细看了使用说明(英文版的,略费劲。建议UARM团队提供中文版说明下载),安装好一些必需的软件和驱动后,第一步需要把 Standard.ino文件烧写到Arduino-Uno板子上去。这时候发现:只要一插上烧程序的USB线,程序就无法编译和下载。没办法了,用小伙伴的Windows 7系统的电脑上试试。竟然可以编译并烧写!后来重装了另一个版本的Arduino,好了!原来是Arduino版本问题,而不是Windows 10系统不兼容导致的。 第二步,将机械臂接上电源,机械臂迅速动作回到初始位置。打开鼠标控制程序MouseControl_V1.0.5.exe,移动鼠标、滚轮、左、右键,即可实现对机械臂前后、左右、上下和抓放的运动控制!!!(另外,在我的笔记本上存在另一个奇怪的问题,就是鼠标控制程序无法捕捉鼠标滚轮的运动。而该鼠标放在别的电脑上控制时,滚轮是好使的。该问题有待进一步攻克!) 仔细研究一番机械臂的动作,主要有两点发现:①UARM机械臂机构设计最大的巧妙之处就是:在相当大的运动范围内,不管大臂小臂如何运动,其末端执行装置,无论是吸盘还是手抓,都能够基本保持水平!这样就保证了吸取或夹取物体的顺畅。②在进行机械臂上下动作控制时发现,执行末端升高或降低这两个看起来简单的动作,其实是靠大臂和小臂的联动实现的。即单片机在实现执行末端上下运动时,对大臂和小臂进行了逆运动学解算和合成控制,大臂和小臂的舵机联动。逆运动学建模也是我后续想要深入研究的一个方向。
二、开发ROS 程序包控制机械臂 ROS(Robot Operation System)是一个机器人软件平台,提供一些标准操作系统服务,例如硬件抽象,底层设备控制,常用功能实现,进程间消息以及数据包管理。ROS是基于一种图状架构,从而不同节点的进程能接受,发布,聚合各种信息(例如传感,控制,状态,规划等等)。目前ROS主要支持Ubuntu。ROS(低层)使用BSD许可证,所有都是开源软件,并能免费用于研究和商业用途。由于其强大的功能、全面的信息及方便快捷的开发,使得开源的ROS逐渐成为机器人开发者首选的开发工具和平台。更多学习内容详见网页 http://wiki.ros.org/cn。 为了学习ROS系统,实现ROS系统对单片机的数据通讯和控制,试着通过在Ubuntu虚拟机下编写ROS程序包,使用键盘(也可以是鼠标)控制UARM机械臂。这样,原本控制单片机靠的是在Windows系统上安装的鼠标控制程序MouseControl_V1.0.5.exe,现在要被在Ubuntu系统下运行的ROS程序包所取代。原先已经烧写到单片机内的程序不作更改。 这部分工作是在一位资深搞ROS的小伙伴帮助指导下完成的。在ROS下建立两个节点(NODE)或程序包(PACKAGE)和一个话题(TOPIC),第一个节点负责捕捉电脑键盘信息,并向话题发送消息(MESSAGE);话题收到消息后向外发送;第二个节点接收话题传过来的消息,并向单片机串口发送数据。每帧数据含11个字节。在本项目中,节点间传输的消息为按键按下所表征的机械臂运动信息。 ROS程序编写前需要先获取UARM官方所提供的程序中单片机串口通讯、舵机控制等的相关信息。ROS程序调试过程比较顺利,虽然出现了初始值错误、数据高低八位搞反等低级错误,但还是用3天时间完成了程序的编写和调试。当第一次使用ROS实现了对机械臂的完美控制时,满心欢喜,成就感爆棚~~~
(未完待续...)
能分享更多的过程或代码不 期待可以分享更多有关机械臂与ROS互动的内容~ 本帖最后由 lfshit 于 2015-11-2 23:25 编辑
这个项目里,在ROS里主要编写三个程序代码:消息发送程序包ros_uarm.cpp、消息接收程序包get_msg.cpp和话题uarm_keyboard.msg。他们的代码如下:
ros_uarm.cpp:
#include <ros/ros.h>
#include <keyboard_resolve/uarm_keyboard.h>
#include "UF_ARM.h"
#include "serial/serial.h"
#define delta_increment 2;
#define rotate_delta_increment 1;
std::string port;
std::string keyboard_topic_;
int32_t baud;
serial::Serial ser;
struct motor_velocity
{
int16_t height;
int16_t stretch;
int16_t rotate;
int16_t hand;
};
motor_velocity arm_robot;
uint8_t SerialBuf;
void keyboardCallback(const keyboard_resolve::uarm_keyboard& omni_velocity)
{
if (omni_velocity.hand_catch)
{
SerialBuf = 1;
}
if (omni_velocity.hand_release)
{
SerialBuf = 2;
}
if (omni_velocity.height_down || omni_velocity.height_up)
{
if (omni_velocity.height_down)
{
arm_robot.height -= delta_increment;
}
if (omni_velocity.height_up)
{
arm_robot.height += delta_increment;
}
if (arm_robot.height < ARM_HEIGHT_MIN)
{
arm_robot.height = ARM_HEIGHT_MIN;
}
else if (arm_robot.height > ARM_HEIGHT_MAX)
{
arm_robot.height = ARM_HEIGHT_MAX;
}
SerialBuf = arm_robot.height & 0xff;
SerialBuf = (arm_robot.height >> 8) & 0xff;
}
if (omni_velocity.rotate_left || omni_velocity.rotate_right)
{
if (omni_velocity.rotate_left)
{
arm_robot.rotate -= rotate_delta_increment;
}
if (omni_velocity.rotate_right)
{
arm_robot.rotate += rotate_delta_increment;
}
if (arm_robot.rotate < ARM_ROTATION_MIN)
{
arm_robot.rotate = ARM_ROTATION_MIN;
}
else if (arm_robot.rotate > ARM_ROTATION_MAX)
{
arm_robot.rotate = ARM_ROTATION_MAX;
}
SerialBuf = arm_robot.rotate & 0xff;
SerialBuf = (arm_robot.rotate >> 8) & 0xff;
}
if (omni_velocity.stretch_back || omni_velocity.stretch_up)
{
if (omni_velocity.stretch_back)
{
arm_robot.stretch -= delta_increment;
}
if (omni_velocity.stretch_up)
{
arm_robot.stretch += delta_increment;
}
if (arm_robot.stretch < ARM_STRETCH_MIN)
{
arm_robot.stretch = ARM_STRETCH_MIN;
}
else if (arm_robot.stretch > ARM_STRETCH_MAX)
{
arm_robot.stretch = ARM_STRETCH_MAX;
}
SerialBuf = arm_robot.stretch & 0xff;
SerialBuf = (arm_robot.stretch >> 8) & 0xff;
}
if (omni_velocity.reset)
{
arm_robot.stretch = 0;
arm_robot.rotate = 0;
arm_robot.height = 0;
SerialBuf = 0xFF;
SerialBuf = 0xAA;
SerialBuf = arm_robot.rotate & 0xff;
SerialBuf = (arm_robot.rotate >> 8) & 0xff;
SerialBuf = arm_robot.stretch & 0xff;
SerialBuf = (arm_robot.stretch >> 8) & 0xff;
SerialBuf = arm_robot.height & 0xff;
SerialBuf = (arm_robot.height >> 8) & 0xff;
SerialBuf = 0;
SerialBuf = 0;
SerialBuf = 0;
}
std::cout<<arm_robot.hand<<"\n"<<arm_robot.height<<"\n"<<arm_robot.rotate<<"\n"<<arm_robot.stretch<<"\n";
ser.write(SerialBuf, 11);
std::cout << omni_velocity << "\n";
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "get_msg");
ros::NodeHandle node;
node.param<std::string>("keyboard_topic", keyboard_topic_, "uarm_keyboard");
node.param<std::string>("serial_port", port, "/dev/ttyUSB0");
node.param<int32_t>("baud",baud,9600);
ser.setPort(port);
ser.setBaudrate(baud);
serial::Timeout to = serial::Timeout(50, 50, 0, 50, 0);
ser.setTimeout(to);
if (ser.isOpen())
{
ser.close();
}
ros::Rate wait_serial(1);
int time_count = 0;
while (!ser.isOpen()&&ros::ok())
{
try
{
ser.open();
}
catch (const std::exception& e)
{
ROS_ERROR("Unable to connect to port.");
}
time_count++;
ROS_INFO("wait for about %ds", time_count);
wait_serial.sleep();
}
if (ser.isOpen())
{
ROS_INFO("Successfully connected to serial port.");
}
arm_robot.stretch = 0;
arm_robot.rotate = 0;
arm_robot.height = 0;
SerialBuf = 0xFF;
SerialBuf = 0xAA;
SerialBuf = arm_robot.rotate & 0xff;
SerialBuf = (arm_robot.rotate >> 8) & 0xff;
SerialBuf = arm_robot.stretch & 0xff;
SerialBuf = (arm_robot.stretch >> 8) & 0xff;
SerialBuf = arm_robot.height & 0xff;
SerialBuf = (arm_robot.height >> 8) & 0xff;
SerialBuf = 0;
SerialBuf = 0;
SerialBuf = 0;
ser.write(SerialBuf, 11);
ros::Subscriber sub = node.subscribe(keyboard_topic_, 10, keyboardCallback);//subsribe the topic
ros::spin();
arm_robot.stretch = 0;
arm_robot.rotate = 0;
arm_robot.height = 0;
SerialBuf = 0xFF;
SerialBuf = 0xAA;
SerialBuf = arm_robot.rotate & 0xff;
SerialBuf = (arm_robot.rotate >> 8) & 0xff;
SerialBuf = arm_robot.stretch & 0xff;
SerialBuf = (arm_robot.stretch >> 8) & 0xff;
SerialBuf = arm_robot.height & 0xff;
SerialBuf = (arm_robot.height >> 8) & 0xff;
SerialBuf = 0;
SerialBuf = 0;
SerialBuf = 0;
ser.write(SerialBuf, 11);
return 0;
}
刚刚程序里出现的:o其实是:o ros_uarm.cpp:
#include <ros/ros.h>
#include <keyboard_resolve/uarm_keyboard.h>
#include "key_map.h"
#include <SDL/SDL.h>
struct Key
{
int16_t code;
int16_t modifiers;
};
using namespace std;
int main(int argc, char** argv)
{
ros::init(argc, argv, "keyboard_resolve"); //鍒濆鍖?
ros::NodeHandle n("~");//寤虹珛鑺傜偣鍚?
keyboard_resolve::uarm_keyboard uarm_key;
ros::NodeHandle private_nh;
//private_nh.param<std::string>("frame_id", omni_velocity.header.frame_id, "uarm");
string keyboard_topic_;
double freq;
private_nh.param("keyboard_topic", keyboard_topic_, std::string("uarm_keyboard"));//妯℃澘鍑芥暟
private_nh.param("publishfrequency", freq, 50.0);
ros::Publisher pub_keyboard = private_nh.advertise<keyboard_resolve::uarm_keyboard>(keyboard_topic_, 3);//妯℃澘鍑芥暟publish the topic whose theme title is keyboard/keyboard_velocity_topic
if (SDL_Init(SDL_INIT_VIDEO) < 0) throw std::runtime_error("Could not init SDL");
SDL_EnableKeyRepeat(0, 0);
SDL_WM_SetCaption("ROS keyboard input", "0");
SDL_Surface* window = SDL_SetVideoMode(400, 400, 0, 0);
ros::Rate r(freq);//the frequency is 50Hz;
int count_event = 0;//a flag which is used for monitoring if the key is down or not
Key k;
bool pressed, new_event = 0;//a flag which is to restore the state of the event
//int16_t velocity_level = 0;
while (ros::ok())
{
SDL_Event event;//鎹曟崏閿洏
if (SDL_PollEvent(&event))
{
switch (event.type)
{
case SDL_KEYDOWN:
k.code = event.key.keysym.sym;
k.modifiers = event.key.keysym.mod;
new_event = true;
break;
case SDL_KEYUP:
k.code = 0;
k.modifiers = event.key.keysym.mod;
new_event = false;
break;
default:
k.code = 0;
k.modifiers = event.key.keysym.mod;
new_event = false;
break;
}
}//this block is used formonitoring the down state of the keyboard and get the value of the key
ROS_INFO("the key is pressed,k.code is: %d,k.modifiers is: %d", k.code, k.modifiers);
uarm_key.hand_catch = false;
uarm_key.hand_release = false;
uarm_key.height_down = false;
uarm_key.height_up = false;
uarm_key.reset = false;
uarm_key.rotate_left = false;
uarm_key.rotate_right = false;
uarm_key.stretch_back = false;
uarm_key.stretch_up = false;
ROS_INFO("k.code=%d", k.code);
if (new_event)
{
switch (k.code)
{
case KEY_UP:
uarm_key.stretch_up = true;
break;
case KEY_DOWN:
uarm_key.stretch_back = true;
break;
case KEY_RIGHT:
uarm_key.rotate_right = true;
break;
case KEY_LEFT:
uarm_key.rotate_left = true;
break;
case KEY_KP2:
case KEY_w:
uarm_key.height_up = true;
break;
case KEY_KP0:
case KEY_s:
uarm_key.height_down = true;
//pub_keyboard.publish(omni_velocity);
break;
case KEY_KP1:
case KEY_a:
uarm_key.hand_catch = true;
//pub_keyboard.publish(omni_velocity);
break;
case KEY_KP3:
case KEY_d:
uarm_key.hand_release = true;
//pub_keyboard.publish(omni_velocity);
break;
case KEY_KP_PERIOD:
case KEY_r:
uarm_key.reset = true;
//pub_keyboard.publish(omni_velocity);
break;
default:
uarm_key.hand_catch = false;
uarm_key.hand_release = false;
uarm_key.height_down = false;
uarm_key.height_up = false;
uarm_key.reset = false;
uarm_key.rotate_left = false;
uarm_key.rotate_right = false;
uarm_key.stretch_back = false;
uarm_key.stretch_up = false;
break;
}
}
pub_keyboard.publish(uarm_key);
cout<<uarm_key<<"\n";
//k.header.stamp = ros::Time::now();
// pub_keyboard.publish(k);
ros::spinOnce();
r.sleep();
}
SDL_FreeSurface(window);
SDL_Quit();
ros::waitForShutdown();
}
刚刚:P、:o分别为:P、:o
这个留言平台太淘气了。。。。 uarm_keyboard.msg:
bool rotate_left
bool rotate_right
bool stretch_up
bool stretch_back
bool height_up
bool height_down
bool hand_catch
bool hand_release
bool reset
谢谢您的分享:) optmsn 发表于 2015-10-28 15:13
期待可以分享更多有关机械臂与ROS互动的内容~
谢谢关注,程序已发~欢迎拍砖交流