背景
仿真是采用软件模拟的方式实现物理上目前不能实现或者物理实现成本很高的过程,其目的是节约成本,有时也为了加快原型迭代速度。在机器人领域,仿真一般来说包括运动学仿真,动力学仿真,有限元仿真。运动学仿真的功能是观察机器人各关节运动范围,机器人工作范围等可视化功能。动力学仿真确定机械臂力平衡,最高运动速度确定等。有限元仿真主要用来计算负载或者重力变形,也可用计算机器人温度场分布。
仿真环境选择
在选择v-rep仿真环境前,曾经对多种仿真环境进行过调研,以下是针对各个仿真环境的简短介绍:
v-rep: 动力学仿真 跨平台 多语言
prescan: 无人驾驶仿真
gym: 强化学习仿真环境
openRAVE: 运动规划相关的运动学仿真,主要用于运动规划算法的开发。
gazebo: 和 ROS集成比较方便,类似的教程较多
openGL: 视觉传感器仿真
SimTrack : 基于仿真的大量目标的跟踪和位姿估计
经过综合考虑,结合我要做的事情,最终选择了V-REP。其中开源,跨平台和多语言是我选择的很重要的因素。v-rep是qt工程,源码公开,可以在windows,mac,Ubuntu系统下编译。支持用c++,python,java,matlab等进行仿真过程的控制。
实现效果
学习软件最好的方法是使用它,V-REP也不例外。在学习一个软件的使用之前,首先要知道该软件的功能,是不是和自己要实现的目标相契合。期望实现的功能是在仿真环境中有传送带,相机,机器人,物流运输车,板式物料,实现机器人的自动上料,相机的位姿类型识别,机器人的自动分拣,物流车的控制等。
v-rep提供了很多的demo,有路径规划,机构运动学正反解,机械臂,末端执行器,全向车,视觉传感器等。如果熟悉了v-rep的仿真环境下元素的组织方式,不用写一行控制代码,单纯复制这些内容就可以搭建自己的仿真环境。在搭建如上图中所示环境时,传送带,机器人和机器人末端的气动吸盘都是从demo仿真环境中复制的,物流车是使用的v-rep提供的模板创建的。
RemoteAPI远程控制
本文要介绍的关键是使用RemoteAPI进行仿真的控制,在前不久根据网上教程写了一个使用Legacy remote API进行仿真环境控制的例子。 。
后来在看v-rep的手册时,发现有B0-based remote API,比Legacy remote API更灵活,是软件开发者推荐使用的方式。
在安装路径\V-REP3\V-REP_PRO_EDU\programming\b0RemoteApiBindings\cpp\simpleTest下有一个工程,是用b0的方式进行仿真过程控制的。与之对应的是B0-basedRemoteApiDemo.ttt仿真环境。simpleTest是一个qt工程,打开后需要修改config.pri文件中的boost和B0路径。v-rep安装文件夹下只有boost的dll(从dll名称可以看出是哪个版本的boost和使用了哪个版本编译器)。所以boost需要另外安装,并且需要编译出lib文件,这里boost最好选用和v-rep编译时使用的一致的boost版本和vs版本。这里我用vs2015编译的1.69的boost的lib文件是能和用vs2017编译的1.68的boost的dll配合使用的,但是多数情况下并不建议如此,以免出现不必要的麻烦。b0是v-rep软件自带的,头文件,lib,dll都有。软件在运行时需要把v-rep的安装根路径加入到环境中,以便能找到所有依赖的dll。
运行编译好的软件,可以在仿真环境中看到结果。
一些实用的技巧
b0remoteapi类使用
b0remoteapi已经被设计为一个类,这个类可以如下实例化
b0RemoteApi* cl=NULL;
b0RemoteApi client("b0RemoteApi_c++Client","b0RemoteApi");
cl=&client; //为了方便在函数中调用时不用传递类对象参数
使用signal
当需要传递少量信息时,不管从c++端到仿真端,还是从仿真端到c++端,都可以使用signal进行传递。比如设置传送带的速度。在c++端:
client.simxSetFloatSignal("conveyorBeltVelocity",0.2,client.simxDefaultPublisher()); //设置带速
在仿真端,每一步仿真时调用
beltVelocity=sim.getFloatSignal("conveyorBeltVelocity")
从仿真端到c++端传递图像传感器数据
首先需要设置回调函数
client.simxGetVisionSensorImage(camera,false,client.simxDefaultSubscriber(camera_CB));
然后写回调函数,该回调函数实现图像数据的获取并转换为opencv的Mat格式显示。
void camera_CB(std::vector<msgpack::object>* msg)
{
std::cout << "Received image." << std::endl;
std::string img(b0RemoteApi::readByteArray(msg,2));
bool su = b0RemoteApi::readBool(msg,0);
std::cout << su << std::endl;
std::vector<int> size;
b0RemoteApi::readIntArray(msg,size,1);
std::cout << size[0] << " " << size[1] << std::endl;
// Mat temp(size[0],size[1],CV_8UC3);
// memcpy(temp.data, img.c_str(), size[0]*size[1]*3);
// cvtColor(temp,temp,COLOR_RGB2BGR);
// namedWindow("temp");
// imshow("temp", temp);
// waitKey(1);
}
取到某一个object的id
std::vector<msgpack::object>* reply=client.simxGetObjectHandle("camera",client.simxServiceCall());
camera=b0RemoteApi::readInt(reply,1);
然后可以根据这个id进行该object的属性设置。
仿真同步和异步模式
同步模式
client.simxSynchronous(true);
while (1) //client.simxGetTimeInMs()<st+100000
{
if (doNextStep)
{
timecount++;
doNextStep=false;
client.simxSynchronousTrigger();
}
client.simxSpinOnce();
}
然后在完成每步仿真时把doNextStep设置为true
异步模式
while (client.simxGetTimeInMs()-lastTimeReceived<2000)
{
//设置object的属性
client.simxSpinOnce();
client.simxSleep(50);
}
常用的回调函数设置
client.simxGetSimulationStepStarted(client.simxDefaultSubscriber(simulationStepStarted_CB));
client.simxGetSimulationStepDone(client.simxDefaultSubscriber(simulationStepDone_CB));
client.simxGetVisionSensorImage(camera,false,client.simxDefaultSubscriber(camera_CB));
仿真开始,仿真接收,接收视觉传感器信息
void simulationStepStarted_CB(std::vector<msgpack::object>* msg)
{
float simTime=0.0;
std::map<std::string,msgpack::object> data=msg->at(1).as<std::map<std::string,msgpack::object>>();
std::map<std::string,msgpack::object>::iterator it=data.find("simulationTime");
if (it!=data.end())
simTime=it->second.as<float>();
std::cout << "Simulation step started. Simulation time: " << simTime << std::endl;
}
void simulationStepDone_CB(std::vector<msgpack::object>* msg)
{
float simTime=0.0;
std::map<std::string,msgpack::object> data=msg->at(1).as<std::map<std::string,msgpack::object>>();
std::map<std::string,msgpack::object>::iterator it=data.find("simulationTime");
if (it!=data.end())
simTime=it->second.as<float>();
std::cout << "Simulation step done. Simulation time: " << simTime << std::endl;
doNextStep=true;
}
实际仿真逻辑示例
c++端
//开始仿真
client.simxStartSimulation(client.simxDefaultPublisher());
//设置速度
int v = 3;
while (1) //client.simxGetTimeInMs()<st+100000
{
if (doNextStep)
{
timecount++;
doNextStep=false;
client.simxSynchronousTrigger();
if(timecount%200==100 && timecount/200 >0 && timecount/200<7)
{
//发送机械臂抓取命令,共抓取6次
client.simxSetIntSignal("grab",1,client.simxDefaultPublisher());
}
if(timecount%200==10 && timecount/200 >-1 && timecount/200<6)
{
//发送板型物流生成命令,共生成6块
client.simxSetIntSignal("drap",1,client.simxDefaultPublisher());
}
if(timecount/200==7)
left(v); //1400仿真步时,使车向左走,以速度v
if(timecount/200==8)
break; //1600仿真步时,结束仿真
}
client.simxSpinOnce();
}
client.simxStopSimulation(client.simxDefaultPublisher());
使车向左走的函数:
void left(int v)
{
cl->simxSetJointTargetVelocity(omniPads[0], v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads[1], v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads[2], -v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads[3], -v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads2[0], v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads2[1], v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads2[2], -v,cl->simxDefaultPublisher());
cl->simxSetJointTargetVelocity(omniPads2[3], -v,cl->simxDefaultPublisher());
}
v-rep端
机械臂
while sim.getSimulationState()~=sim.simulation_advancing_abouttostop do
grab=sim.getIntegerSignal("grab") --关键是此处,接收c++发来的抓取命令
if grab == 1 then
sim.setScriptSimulationParameter(sim.getScriptAssociatedWithObject(suctionPad),'active','true')
sim.moveToPosition(ikTarget,ur10,{grabpos[1],grabpos[2],grabpos[3]},{0,0,0},vel,acc)
sim.wait(0.2)
sim.moveToPosition(ikTarget,ur10,{grabpos[1],grabpos[2],moveh},{0,0,0},vel,acc)
sim.moveToPosition(ikTarget,ur10,{drappos1[1],drappos1[2],moveh},{0,0,0},vel,acc)
sim.moveToPosition(ikTarget,ur10,{drappos1[1],drappos1[2],drappos1[3]},{0,0,0},vel,acc)
sim.setScriptSimulationParameter(sim.getScriptAssociatedWithObject(suctionPad),'active','false')
sim.moveToPosition(ikTarget,ur10,{drappos1[1],drappos1[2],moveh},{0,0,0},vel,acc)
sim.moveToPosition(ikTarget,ur10,{grabpos[1],grabpos[2],moveh},{0,0,0},vel,acc) --back to O point
sim.setIntegerSignal("grab",0)
sim.switchThread()
end
end
板材生成使用类似的逻辑。
使车行走的命令不用再仿真端接收,命令直接从c++端到object。