安装gazebo_手把手教你用Gazebo仿真UUV水下机器人
前言
本節(jié)教程演示UUV的一些玩法,基于開源項(xiàng)目UUV,官方介紹文檔uuvsimulator??https://uuvsimulator.github.io/packages/uuv_simulator/intro/
仿真環(huán)境
系統(tǒng):ubuntu16.04
軟件:ROS – kinetic
仿真:gazebo7
安裝仿真軟件
官網(wǎng)介紹目前支持的版本有三個(gè):kunetic、lunar、melodic
安裝命令:
kinetic版本:sudo apt install ros-kinetic-uuv-simulatorlunar版本:sudo apt install ros-lunar-uuv-simulatormelodic版本:sudo apt install ros-melodic-uuv-simulator如果希望從源碼安裝的朋友參考這里:
源碼安裝教程 ? https://uuvsimulator.github.io/installation/
這里不推薦源碼安裝,因?yàn)榭戳讼耮ithub項(xiàng)目的issue中很多人顯示安裝報(bào)錯(cuò),所以emmm省的折騰。
啟動(dòng)AUV海底世界
啟動(dòng)帶海底的世界執(zhí)行命令:
roslaunch uuv_gazebo_worlds auv_underwater_world.launch水世界效果圖如下(還是很帥的天空的云和海水都是在動(dòng)的):啟動(dòng)赫爾庫勒斯沉船的世界執(zhí)行命令:roslaunch uuv_gazebo_worlds herkules_ship_wreck.launch啟動(dòng)湖泊roslaunch uuv_gazebo_worlds lake.launch
其他的一些場景roslaunch uuv_gazebo_worlds mangalia.launchroslaunch uuv_gazebo_worlds munkholmen.launchroslaunch uuv_gazebo_worlds ocean_waves.launch!注意這里的海浪都只是視覺效果不會(huì)將波浪的載荷加載在水下機(jī)器人上
水下機(jī)器人運(yùn)動(dòng)控制
啟動(dòng)環(huán)境和水下機(jī)器人pid控制
執(zhí)行命令:roslaunch uuv_gazebo start_pid_demo_with_teleop.launch這里機(jī)器人的速度控制還是經(jīng)典的cmd_vel話題,我們可以自己創(chuàng)建速度控制腳本teletop.py:#!/usr/bin/env pythonimport rospyfrom geometry_msgs.msg import Twistimport sys, select, osif os.name == 'nt': import msvcrtelse: import tty, termiosFETCH_MAX_LIN_VEL = 5FETCH_MAX_ANG_VEL = 2.84LIN_VEL_STEP_SIZE = 0.01ANG_VEL_STEP_SIZE = 0.1msg = """Control Your Robot!---------------------------Moving around: w a s d x"""e = """Communications Failed"""def getKey(): if os.name == 'nt': return msvcrt.getch() tty.setraw(sys.stdin.fileno()) rlist, _, _ = select.select([sys.stdin], [], [], 0.1) if rlist: key = sys.stdin.read(1) else: key = '' termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) return keydef vels(target_linear_vel, target_angular_vel): return "currently:\tlinear vel %s\t angular vel %s " % (target_linear_vel,target_angular_vel)def makeSimpleProfile(output, input, slop): if input > output: output = min( input, output + slop ) elif input < output: output = max( input, output - slop ) else: output = input return outputdef constrain(input, low, high): if input < low: input = low elif input > high: input = high else: input = input return inputdef checkLinearLimitVelocity(vel): vel = constrain(vel, -FETCH_MAX_LIN_VEL, FETCH_MAX_LIN_VEL) return veldef checkAngularLimitVelocity(vel): vel = constrain(vel, -FETCH_MAX_ANG_VEL, FETCH_MAX_ANG_VEL) return velif __name__=="__main__": if os.name != 'nt': settings = termios.tcgetattr(sys.stdin) rospy.init_node('fetch_teleop') pub = rospy.Publisher('/rexrov/cmd_vel', Twist, queue_size=10) status = 0 target_linear_vel = 0.0 target_angular_vel = 0.0 control_linear_vel = 0.0 control_angular_vel = 0.0 try: print(msg) while(1): key = getKey() if key == 'w' : target_linear_vel = checkLinearLimitVelocity(target_linear_vel + LIN_VEL_STEP_SIZE) status = status + 1 print(vels(target_linear_vel,target_angular_vel)) elif key == 'x' : target_linear_vel = checkLinearLimitVelocity(target_linear_vel - LIN_VEL_STEP_SIZE) status = status + 1 print(vels(target_linear_vel,target_angular_vel)) elif key == 'a' : target_angular_vel = checkAngularLimitVelocity(target_angular_vel + ANG_VEL_STEP_SIZE) status = status + 1 print(vels(target_linear_vel,target_angular_vel)) elif key == 'd' : target_angular_vel = checkAngularLimitVelocity(target_angular_vel - ANG_VEL_STEP_SIZE) status = status + 1 print(vels(target_linear_vel,target_angular_vel)) elif key == ' ' or key == 's' : target_linear_vel = 0.0 control_linear_vel = 0.0 target_angular_vel = 0.0 control_angular_vel = 0.0 print(vels(target_linear_vel, target_angular_vel)) else: if (key == '\x03'): break if status == 20 : print(msg) status = 0 twist = Twist() control_linear_vel = makeSimpleProfile(control_linear_vel, target_linear_vel, (LIN_VEL_STEP_SIZE/2.0)) twist.linear.x = control_linear_vel; twist.linear.y = 0.0; twist.linear.z = 0.0 control_angular_vel = makeSimpleProfile(control_angular_vel, target_angular_vel, (ANG_VEL_STEP_SIZE/2.0)) twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = control_angular_vel pub.publish(twist) except: print(e) finally: twist = Twist() twist.linear.x = 0.0; twist.linear.y = 0.0; twist.linear.z = 0.0 twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = 0.0 pub.publish(twist) if os.name != 'nt': termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)運(yùn)行腳本就可以控制船運(yùn)動(dòng)了:python teletop.py生成螺旋線控制水下機(jī)器人運(yùn)動(dòng)執(zhí)行命令啟動(dòng)pid控制和環(huán)境:roslaunch uuv_gazebo start_pid_demo_with_teleop.launch生成螺旋線并巡線(這里我生成的是2股螺旋線):roslaunch uuv_control_utils start_helical_trajectory.launch uuv_name:=rexrov n_turns:=2發(fā)布一組導(dǎo)航點(diǎn)導(dǎo)航執(zhí)行命令啟動(dòng)pid控制和環(huán)境:roslaunch uuv_gazebo start_pid_demo_with_teleop.launch執(zhí)行命令生成直線路徑:roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov interpolator:=linear機(jī)器人路徑根據(jù)貝塞爾曲線原理生成,可以保證軌跡上的點(diǎn)速度方向是連續(xù)的,并且規(guī)定路徑點(diǎn)生成的整條路徑是必過路徑點(diǎn)的。
小編這里寫了個(gè)二維三階貝賽爾曲線的路徑生成的代碼:https://github.com/xmy0916/bezier大家可以參考參考!執(zhí)行命令生成三維貝賽爾曲線路徑:
roslaunch uuv_control_utils send_waypoints_file.launch uuv_name:=rexrov interpolator:=cubic更多操作參考:項(xiàng)目官方文檔??https://uuvsimulator.github.io/packages/uuv_simulator/intro/項(xiàng)目github地址https://github.com/uuvsimulator/古月居原創(chuàng)作者簽約計(jì)劃已開啟,網(wǎng)站(guyuehome.com)已上線【投稿】功能,歡迎大家積極投稿,原創(chuàng)優(yōu)質(zhì)文章作者將有機(jī)會(huì)成為古月居簽約作者。
總結(jié)
以上是生活随笔為你收集整理的安装gazebo_手把手教你用Gazebo仿真UUV水下机器人的全部內(nèi)容,希望文章能夠幫你解決所遇到的問題。
- 上一篇: 中单引号和双引号的区别与联系_VB中Su
- 下一篇: python querystring e