1. 程式人生 > >開發ROS 程式包控制機械臂

開發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裡主要編寫三個程式程式碼:訊息傳送程式包ros_uarm.cpp、訊息接收程式包get_msg.cpp和話題uarm_keyboard.msg。他們的程式碼如下:

1) 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[11]; void keyboardCallback(const keyboard_resolve::uarm_keyboard& omni_velocity) { if (omni_velocity.hand_catch) { SerialBuf[10] = 1; } if (omni_velocity.hand
_release) { SerialBuf[10] = 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[7] = arm_robot.height & 0xff; SerialBuf[6] = (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[3] = arm_robot.rotate & 0xff; SerialBuf[2] = (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[5] = arm_robot.stretch & 0xff; SerialBuf[4] = (arm_robot.stretch >> 8) & 0xff; } if (omni_velocity.reset) { arm_robot.stretch = 0; arm_robot.rotate = 0; arm_robot.height = 0; SerialBuf[0] = 0xFF; SerialBuf[1] = 0xAA; SerialBuf[3] = arm_robot.rotate & 0xff; SerialBuf[2] = (arm_robot.rotate >> 8) & 0xff; SerialBuf[5] = arm_robot.stretch & 0xff; SerialBuf[4] = (arm_robot.stretch >> 8) & 0xff; SerialBuf[7] = arm_robot.height & 0xff; SerialBuf[6] = (arm_robot.height >> 8) & 0xff; SerialBuf[8] = 0; SerialBuf[9] = 0; SerialBuf[10] = 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:k()) { 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[0] = 0xFF; SerialBuf[1] = 0xAA; SerialBuf[3] = arm_robot.rotate & 0xff; SerialBuf[2] = (arm_robot.rotate >> 8) & 0xff; SerialBuf[5] = arm_robot.stretch & 0xff; SerialBuf[4] = (arm_robot.stretch >> 8) & 0xff; SerialBuf[7] = arm_robot.height & 0xff; SerialBuf[6] = (arm_robot.height >> 8) & 0xff; SerialBuf[8] = 0; SerialBuf[9] = 0; SerialBuf[10] = 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[0] = 0xFF; SerialBuf[1] = 0xAA; SerialBuf[3] = arm_robot.rotate & 0xff; SerialBuf[2] = (arm_robot.rotate >> 8) & 0xff; SerialBuf[5] = arm_robot.stretch & 0xff; SerialBuf[4] = (arm_robot.stretch >> 8) & 0xff; SerialBuf[7] = arm_robot.height & 0xff; SerialBuf[6] = (arm_robot.height >> 8) & 0xff; SerialBuf[8] = 0; SerialBuf[9] = 0; SerialBuf[10] = 0; ser.write(SerialBuf, 11); return 0; }

2) 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