本文档主要介绍chess_ws下的src文件夹以及各个软件包的功能
-
Computer architecture Linux Ros X86 / ARM Ubuntu 16.04 kinetic
chess_gui软件包主要用于界面显示,以及视觉处理
- launch文件:
-
chess.launch 启动界面
- 节点文件: chess_node.py - 参数: path: 指定标定的文件及图片的地址 ai_ip: 象棋AI的IP地址
-
usb_cam_scara.launch/usb_cam_ur.launch 启动相机
- 参数: device:默认为Video0,请根据实际情况进行修改 pixel_format:图片格式 framerate:帧率
chess_msgs软件包主要包含自定义的消息类型
- 主要用到以下两个文件:
1. Operation.msg
uint32 OPERATION_GO = 0 走棋
uint32 OPERATION_CAPTURE = 1 抓棋
uint32 OPERATION_WAIT = 2 回到等待位置
uint32 POSITION_FAR = 0 无效参数
uint32 POSITION_NEAR = 1 无效参数
uint32 type 操作类型
uint32 pick_type 拿棋子
float32 pick_x pick的x坐标
float32 pick_y pick的y坐标
uint32 place_type 放棋子
float32 place_x 放的棋子的x坐标
float32 place_y 放的棋子的y坐标
2.Step.action
Operation[] ops 任务目标位姿
bool res 向客户端发送任务的执行结果
string msg
string feedback 周期反馈任务运行时的监控数据
chess_scara_pkg软件包主要包含操作scara的代码
-
launch文件:
chess_scara_setup.launch:启动除相机外的所有节点(即开启机器人的服务及操作界面) - 参数: robot_ip: 实体机器人的ip地址 robot_name:实体机器人的名字
-
其启动的launch文件如下:
1. chess_scara_server.launch :启动action服务 * 节点文件:chess_scara_server.cpp(主要头文件scara_move.h) 2. chess.launch : 启动界面 * 节点文件: chess_node.py
-
如何控制Scara运动到某一位置(正向运动学,逆向运动学):
1.Scara通过正运动公司的控制器进行运动规划
2.头文件: zmotion.h 与zaux.h
3.示例代码:
#include <ros/ros.h> #include "chess_scara_pkg/zmotion.h" #include "chess_scara_pkg/zaux.h" ZMC_HANDLE g_handle; int main(int argc, char *argv[])
{ ros::init(argc, argv, "scara_zmotion_test"); ros::AsyncSpinner spinner(1); spinner.start();
//实体Scara的ip地址
std::string ip="192.168.1.110";
char *ipaddr = new char[20];
strcpy(ipaddr, ip.c_str());
//连接实体Scara
int32 iresult = ZMC_OpenEth(ipaddr, &g_handle);
ROS_INFO("zmotion result: %d", iresult);
if(0 == iresult)
{
ROS_INFO("zmotion connect success.");
}
//目标位置
float x,y,r,z;
x = 158.403
y = 366.127
r = 123
z = 20
//控制哪几个轴
uint16 num_axis = 4;
int axislist[4] = {6,7,8,9}; //轴列表
float poslist[4]= {x,y,r,z};
//直线插补至目标位置
ZAux_Direct_Base(g_handle, num_axis, axislist);
ZAux_Direct_MoveAbs(g_handle, num_axis, poslist);
iresult = ZMC_Close(g_handle);
if(0 == iresult)
{
ROS_INFO("zmotion close success.");
}
ros::shutdown();
return 0;
}
```
chess_ur_pkg软件包主要包含操作UR的代码
-
launch文件:
chess_ur_setup.launch :启动除相机外的所有节点(即开启机器人的服务及操作界面) - 参数: robot_ip: 实体机器人的ip地址 robot_name:实体机器人的名字
-
其启动的launch文件如下:
1.ur3_start.launch :启动模拟环境 * demo.launch * ur3_real_start.launch * chess_board.launch * ur_get_point.launch 2. chess_action_server.launch : 启动action服务 * 节点文件:chess_action_server.cpp (主要头文件ur_move.h) 3. chess.launch : 启动界面 * 节点文件: chess_node.py
-
如何控制UR3运动到某一位置(正向运动学,逆向运动学):
1.Ros主要通过Moveit进行运动规划,Moveit解决了机械臂领域几乎所有的方面的问题,从运动规划,运动学分析,碰撞检测,到抓握,取放,还有感知,一应俱全。
2.API:Python的move group接口 / C++的move group interface接口(本代码使用)
3.示例代码
#include <moveit/move_group_interface/move_group_interface.h> #include <geometry_msgs/Pose.h> int main(int argc,char **argv) { ros::init(argc, argv, "move_group_test"); ros::NodeHandle node_handle; ros::AsyncSpinner spinner(1); spinner.start();
//定义控制哪个规划组 moveit::planning_interface::MoveGroupInterface group("manipulator");
// 设置机器人终端的目标位置 geometry_msgs::Pose target_pose1; target_pose1.orientation.w = 0.650578375865; target_pose1.orientation.x= -0.251979405781; target_pose1.orientation.y = 0.658020218454; target_pose1.orientation.z = 0.283308220893; target_pose1.position.x = 0.0600368141071; target_pose1.position.y =-0.461724470293; target_pose1.position.z = 0.04; group.setPoseTarget(target_pose1);
// 进行运动规划,计算机器人移动到目标的运动轨迹,此时只是计算出轨迹,并不会控制机械臂运动 moveit::planning_interface::MoveGroupInterface::Plan my_plan; bool success = (group.plan(my_plan) ==moveit::planning_interface::MoveItErrorCode::SUCCESS);
//运动 if(success) group.execute(my_plan);
ros::shutdown(); return 0; }
<br>
<h2 id="pkgs">pkgs</h2>
> **pkgs软件包为ur六轴机器人驱动以及ros_industrial源码**
>
* 安装ros-i源码:
sudo apt-get install ros-kinetic-industrial-core
ros-kinetic-open-industrial-ros-controllers
- 安装UR机器人的ROS功能包集
sudo apt-get install ros-kinetic-universal-robot
<br>
<h2 id="ur">ur</h2>
> **ur软件包主要为ur六轴机器人的建模和moveit配置**
* ur_description_v1文件夹 : 其urdf文件夹包含UR六轴机器人的建模文件
* 可输入命令 :
roslaunch moveit_setup_assistant setup_assistant.launch
* 后选择ur3_robot.urdf.xacro文件对建模文件进行moveit配置
* ur3_moveit_config_v1文件夹 : moveit配置后输出的文件夹
* 运行:roslaunch ur3_moveit_config_v1 ur3_real_start.launch 即可以与实体UR3连接
* <center>
![](http://m.qpic.cn/psb?/V14EfA5i2CeIPg/.lnJhVXjTwjYaL0sxXPbLpwvVNRw0UwlNvXKZWQJYgQ!/b/dFYBAAAAAAAA&bo=gAIWAwAAAAADB7U!&rf=viewer_4)
</center>
按update按钮生成一个随机目标位姿,再按plan进行规划(模拟),或按plan and execute实体机器人开始运动
* <center>
![](http://m.qpic.cn/psb?/V14EfA5i2CeIPg/fwKU93ySrJPkhhewdnnhuYYEbKMqPv3MAiNl1o9a00o!/b/dEABAAAAAAAA&bo=gAIRAwAAAAADB7I!&rf=viewer_4)
</center>
在Scene Object标签页中添加场景
<br>
<h2 id="usb_cam">usb_cam</h2>
> **usb_cam主要为USB摄像头的驱动**
* 源码:[https://github.com/bosch-ros-pkg/usb_cam.git](https://github.com/bosch-ros-pkg/usb_cam.git)
* 订阅 /usb_cam_node/image_rect_color 主题,即可看到实时视频流
<br>
<h2 id="xfei_speech">xfei_speech</h2>
> **xfei_speech软件包为科大讯飞语音包**
- 要求
1. 需要到科大讯飞网站注册帐号(只需要APPID),[访问科大讯飞网站](http://www.xfyun.cn/)
2. 下载linux版本ROS软件包,已经包含需要SDK库文件 [github库](https://github.com/ncnynl/xf-ros)
3. 安装语音库:sudo apt-get install libasound2-dev (录音)
- 具体教程:[https://www.ncnynl.com/archives/201702/1287.html](https://www.ncnynl.com/archives/201702/1287.html)
- 发布 speech_command 主题
订阅speech_recognize主题
<br>
---
<br>
## <center> 资源文件 </center>
> 该资源文件在chess_ws下的image文件夹,与src文件夹同级
* **棋子图片**
用于模拟界面上,表示当前的棋子位置信息,其文件名如 aa.png
* **空棋盘图片**
由定标1所生产的图片,其文件名如 scara_board.png
* **满棋子图片**
由定标2所生产的图片,其文件名如 scara_stone.png
* **标定文件**
由定标3所生产的txt文件,用于图片坐标与实际坐标的转换,其文件名如 scara_mark.txt
<br>