0. 目標(biāo)
目標(biāo):把Solidworks的機(jī)器人模型導(dǎo)入Webots,保存運(yùn)動(dòng)副關(guān)系,導(dǎo)入后直接控制。所有操作都在win10環(huán)境進(jìn)行。
思路:使用Solidworks - SW2URDF插件導(dǎo)出URDF文件,然后使用python - urdf2webots模組,生成proto文件導(dǎo)入Webots。
程序版本:Solidworks 2018 SP5.0(或更新), Webots R2023a,python模組urdf2webots V2.0.3,版本不兼容會(huì)導(dǎo)致錯(cuò)誤。
提示:有坑,需仔細(xì)閱讀正文。
1. SW導(dǎo)出URDF
Solidworks必須是2018 SP5.0或更新的版本,不然和插件不兼容。
下載并安裝Solidworks插件SW2URDF:ROS.org網(wǎng)站鏈接,Github鏈接。
我是從Github下載的,注意里面根據(jù)Solidworks版本分了好幾個(gè),選擇下載。第一個(gè)鏈接里也說明了SW的版本要求。
只下載exe文件就行,雙擊安裝。如果安裝的時(shí)候SW還開著,需要在安裝后重啟SW。
找到SW頂部一行的齒輪圖標(biāo),點(diǎn)下拉菜單里的插件:
在插件窗口里面,滑動(dòng)到底部,勾選SW2URDF插件:
然后準(zhǔn)備機(jī)器人裝配體模型。我是從機(jī)械模型轉(zhuǎn)換,原模型細(xì)節(jié)很多,需要簡化,把內(nèi)部軸承、電路板等看不到的零件都刪掉,螺絲孔和其他不需要的特征也刪掉,減小面數(shù)。
最后生成一個(gè)用來仿真的裝配體:
我的模型是很多零件裝配而成的四輪小車,但對(duì)于仿真軟件來說,整個(gè)機(jī)器人是一個(gè)機(jī)身和4個(gè)輪子,共5個(gè)剛體,聯(lián)接而成的。所以我把每個(gè)剛體都另存為了SW零件,再組成整個(gè)機(jī)器人,條理清晰。沒有試過用子裝配體組成的模型導(dǎo)出,可能也行吧。
注意,裝配體的原點(diǎn)需要定在機(jī)器人根部件上,如果偏的太遠(yuǎn),可能會(huì)影響后面仿真。
怎么調(diào)節(jié)機(jī)器人相對(duì)原點(diǎn)的位置:先把根部件取消固定,然后在機(jī)器人和三個(gè)基準(zhǔn)面之間添加配合,以此約束機(jī)器人的位置。
打開插件:SW頂部菜單欄>>工具>>File(在菜單最底下)>>Export as URDF:
然后設(shè)置機(jī)器人的運(yùn)動(dòng)副關(guān)系,看圖:
按照上圖說明,彈出URDF導(dǎo)出窗口。
注意這時(shí)候插件會(huì)在SW里面自動(dòng)生成運(yùn)動(dòng)副的坐標(biāo)系和軸,之后就不要輕易改動(dòng)裝配體了,不然會(huì)導(dǎo)致轉(zhuǎn)軸位置錯(cuò)誤。
回到導(dǎo)出窗口,首先是關(guān)節(jié)屬性,保持默認(rèn)即可,點(diǎn)Next:
部件設(shè)置頁面,參考下圖說明:
按照上圖,最后導(dǎo)出的機(jī)器人,是每個(gè)部件一個(gè)顏色。上圖右下有個(gè)"Texture"應(yīng)該可以設(shè)置貼圖然后實(shí)現(xiàn)彩色部件,還沒研究怎么用。
導(dǎo)出時(shí)設(shè)置名稱,不能以數(shù)字開頭,整個(gè)路徑和文件名都不能含中文,比如我的是“PipeRob6DOF”,導(dǎo)出后會(huì)生成一個(gè)同名文件夾,里面有幾個(gè)子文件夾,存放URDF文件和各種模型資源:
2. 新建Webots工程
Webots版本采用R2023a,根據(jù)引導(dǎo),新建項(xiàng)目目錄和世界(world),
勾選“Add a rectangle arena”,即生一個(gè)平臺(tái),方便后面測試。
3. URDF轉(zhuǎn)proto
轉(zhuǎn)換工具是python環(huán)境下的urdf2webots模組,需要電腦已經(jīng)安裝了python(我的是python 3)。
在Webots項(xiàng)目文件夾里,有個(gè)protos文件夾,把前面SW導(dǎo)出的“PipeRob6DOF”文件夾放進(jìn)去。
進(jìn)入PipeRob6DOF/urdf子文件夾,可以看到里面有一個(gè)PipeRob6DOF.urdf。按Shift+右鍵,在此處打開PowerShell窗口(等同于cmd窗口):
首次使用,需安裝python的urdf2webots模組,執(zhí)行以下命令: pip install urdf2webots
這樣會(huì)安裝最新版(V2.0.3),本文介紹的是V2新版用法。模組V1版本用法是不一樣的,具體可參考另一篇文章或模組官網(wǎng)。
輸入以下命令,由urdf文件生成proto文件: python -m urdf2webots.importer --input=PipeRob6DOF.urdf
由于我們是在urdf文件所在位置打開的命令窗口,所以這里直接把PipeRob6DOF.urdf作為輸入?yún)?shù),不需要冗長的路徑。讀者需要把上面“PipeRob6DOF”改成自己的機(jī)器人名稱。
運(yùn)行成功的話會(huì)返回機(jī)器人部件數(shù)量和關(guān)節(jié)數(shù)量,同時(shí)生成一個(gè)proto文件。
proto文件是Webots采用的一種文件格式,可以理解為“預(yù)設(shè)”,實(shí)現(xiàn)仿真世界中機(jī)器人或模型的復(fù)用。
一個(gè)proto文件本質(zhì)上就是文本文檔,里面定義了機(jī)器人的組成結(jié)構(gòu),各個(gè)部件的屬性,以及網(wǎng)格模型鏈接。
采用python模組生成的proto文件存在一些缺陷,用Notepad++或記事本打開proto文件,然后:
(1)修正STL路徑格式錯(cuò)誤(必做):按Ctrl+H調(diào)用替換窗口,把所有 \ 替換為 / ;
(2)把STL文件改為相對(duì)路徑(可選),以便在其他電腦上運(yùn)行。比如原本是: url "D:/JiangxuDesk/OneDrive/PipeRob/Webots/PipeRobWB23/protos/PipeRob6DOF/meshes/body.STL"
替換為: url "../meshes/body.STL"
(3)設(shè)置部件顏色:搜索baseColor,可以看到SW導(dǎo)出時(shí),所定義的各種材料的顏色定義,是取值0-1的RGB。
修改完成后保存,可以暫時(shí)不用關(guān)閉。后面重新修改保存后,在Webots里重新載入場景,可以隨時(shí)調(diào)整。
4. proto文件導(dǎo)入Webots
Webots里面點(diǎn)工具欄加號(hào):
Webots會(huì)讀取項(xiàng)目目錄protos文件夾里所有的proto文件,不出意外會(huì)顯示前面導(dǎo)出的機(jī)器人名稱:
機(jī)器人就進(jìn)來了。如果導(dǎo)入錯(cuò)誤會(huì)在Console提示。
調(diào)整地板大小和機(jī)器人的位置(避免干涉),保存之后開始仿真(Webots操作我就不介紹了),可以看到機(jī)器人重力作用下掉到地板上了:
上圖中小車是全白的。根據(jù)前文,在proto文件里搜索baseColor的地方設(shè)置各個(gè)部件顏色,保存后重新載入場景:
可見顏色更新了:
5. 控制機(jī)器人
Webots里新建一個(gè)C語言的控制器,進(jìn)行編程:
/*
* File: my_controller.c
* Date:
* Description:
* Author:
* Modifications:
*/
/*
* You may need to add include files like <webots/distance_sensor.h> or
* <webots/motor.h>, etc.
*/
#include <webots/robot.h>
#include <webots/motor.h>
/*
* You may want to add macros here.
*/
#define TIME_STEP 8
//using namespace webots;
/*
* This is the main program.
* The arguments of the main function can be specified by the
* "controllerArgs" field of the Robot node
*/
int main(int argc, char **argv) {
/* necessary to initialize webots stuff */
// 實(shí)現(xiàn)差速轉(zhuǎn)向效果,需要在WorldInfo里面設(shè)置forceDependentSlip > 0.
wb_robot_init();
WbDeviceTag mot[4];
char mot_names[4][3]={{"a1"},{"a2"},{"a3"},{"a4"}};
for(int i=0;i<4;i++){
mot[i] = wb_robot_get_device(mot_names[i]);
wb_motor_set_position(mot[i], INFINITY);
// wb_motor_set_velocity(mot[i], 4);
}
float v = 4;
wb_motor_set_velocity(mot[0], -v);
wb_motor_set_velocity(mot[1], -v);
wb_motor_set_velocity(mot[2], v);
wb_motor_set_velocity(mot[3], v);
/*
* You should declare here WbDeviceTag variables for storing
* robot devices like this:
* WbDeviceTag my_sensor = wb_robot_get_device("my_sensor");
* WbDeviceTag my_actuator = wb_robot_get_device("my_actuator");
*/
/* main loop
* Perform simulation steps of TIME_STEP milliseconds
* and leave the loop when the simulation is over
*/
int t = 0;
while (wb_robot_step(TIME_STEP) != -1) {
t+=TIME_STEP;
/*
* Read the sensors :
* Enter here functions to read sensor data, like:
* double val = wb_distance_sensor_get_value(my_sensor);
*/
/* Process sensor data here */
/*
* Enter here functions to send actuator commands, like:
* wb_motor_set_position(my_actuator, 10.0);
*/
};
/* Enter your cleanup code here */
/* This is necessary to cleanup webots resources */
wb_robot_cleanup();
return 0;
}
控制器里面,先獲取電機(jī),電機(jī)名稱就是導(dǎo)出URDF的時(shí)候,設(shè)置的關(guān)節(jié)名稱。然后把位置設(shè)置為無窮大,再設(shè)置一個(gè)速度,讓它一直跑。
編譯控制器,把控制器賦給機(jī)器人,開始仿真。如果一切正常,機(jī)器人會(huì)開始運(yùn)動(dòng)。如果不穩(wěn)定,可以把仿真周期調(diào)小。
6. 添加傳感器
要給機(jī)器人添加測距儀、相機(jī)等傳感器,可參考:Webots中給proto格式機(jī)器人添加傳感器
文章來源:http://www.zghlxwxcb.cn/news/detail-725997.html
參考:
將solidworks裝配體模型導(dǎo)入webots并進(jìn)行控制
利用插件將solidworks模型轉(zhuǎn)化為URDF文件,再轉(zhuǎn)化為proto文件并導(dǎo)入Webots
文章來源地址http://www.zghlxwxcb.cn/news/detail-725997.html
到了這里,關(guān)于Solidworks機(jī)器人導(dǎo)出URDF文件,導(dǎo)入Webots并控制的文章就介紹完了。如果您還想了解更多內(nèi)容,請(qǐng)?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!