About me
home
Portfolio
home

GO1 시뮬2

진행 상태
완료
팀원
마감일
태그
작업 (하위 작업)에 관계됨
3 more properties

GO1 시뮬2

0. 코드

src.zip
147907.7KB
1.
GO1 및 가제보 환경 켜기
roslaunch go1_config gazebo.launch
JavaScript
복사
실행사진
2.
move_base 실행
roslanch champ_gazebo run.launch
JavaScript
복사

1. 환경설정

위 링크에서 simulation을 클릭 한 후 CHAMP를 클릭한다.
Github가 들어가질텐데 Readme 따라 진행, 다음은 Readme 내용
# install sudo apt install -y python-rosdep cd <your_ws>/src git clone --recursive https://github.com/chvmp/champ git clone https://github.com/chvmp/champ_teleop cd .. rosdep install --from-paths src --ignore-src -r -y # build workspace cd <your_ws> catkin_make source <your_ws>/devel/setup.bash
Shell
복사
GO1 URDF 다운로드
# robot install git clone https://github.com/chvmp/robots.git # in robots folder mkdir -p descriptions cd descriptions git clone https://github.com/chvmp/unitree_ros
Shell
복사

2. 실행

Walking demo in RVIZ
# Run the base driver roslaunch go1_config bringup.launch rviz:=true # Run the teleop node roslaunch champ_teleop teleop.launch
Shell
복사
실행영상
SLAM demo
# Run the Gazebo environment # world를 로드하는데 오래걸리므로 5분정도는 기다려 주기 roslaunch go1_config gazebo.launch # Run gmapping package and move_base roslaunch go1_config slam.launch rviz:=true
Shell
복사
실행영상
Autonomous Navigation
# Run the Gazebo environment roslaunch go1_config gazebo.launch # Run amcl and move_base roslaunch go1_config navigate.launch rviz:=true
Shell
복사
Spawning multiple robots in Gazebo
# Run Gazebo and default simulation world roslaunch champ_gazebo spawn_world.launch # You can also load your own world file by passing your world's path to 'gazebo_world' argument roslaunch champ_gazebo spawn_world.launch gazebo_world:=<path_to_world_file> # Spawning a robot roslaunch go1_config spawn_robot.launch robot_name:=<unique_robot_name> world_init_x:=<x_position> world_init_y:=<y_position>
Shell
복사

3. Gazebo환경 코드 실행

move_ex.py
#! /usr/bin/env python # -*- coding: utf-8 -*- import rospy from geometry_msgs.msg import Twist def twist_publisher(): rospy.init_node('twist_publisher_node', anonymous=True) # cmd_vel or cmd_vel/smooth로 움직일 수 있음 pub = rospy.Publisher('/cmd_vel/smooth', Twist, queue_size=10) rate = rospy.Rate(10) while not rospy.is_shutdown(): twist_msg = Twist() twist_msg.linear.x = 0.5 pub.publish(twist_msg) rate.sleep() if __name__ == '__main__': try: twist_publisher() except rospy.ROSInterruptException: pass
Python
복사
실행영상
wego Python code
Unitree_go1_user_manual(Python)_wego.pdf
2318.8KB
#!/usr/bin/python import sys import time import math sys.path.append('../lib/python/amd64') import robot_interface as sdk if __name__ == '__main__': HIGHLEVEL = 0xee LOWLEVEL = 0xff udp = sdk.UDP(HIGHLEVEL, 8080, "192.168.123.161", 8082) cmd = sdk.HighCmd() state = sdk.HighState() udp.InitCmdData(cmd) motiontime = 0 while True: time.sleep(0.002) motiontime = motiontime + 1 udp.Recv() udp.GetRecv(state) # print(motiontime) # print(state.imu.rpy[0]) # print(motiontime, state.motorState[0].q, state.motorState[1].q, state.motorState[2].q) # print(state.imu.rpy[0]) cmd.mode = 0 # 0:idle, default stand 1:forced stand 2:walk continuously cmd.gaitType = 0 cmd.speedLevel = 0 cmd.footRaiseHeight = 0 cmd.bodyHeight = 0 cmd.euler = [0, 0, 0] cmd.velocity = [0, 0] cmd.yawSpeed = 0.0 cmd.reserve = 0 # cmd.mode = 2 # cmd.gaitType = 1 # # cmd.position = [1, 0] # # cmd.position[0] = 2 # cmd.velocity = [-0.2, 0] # -1 ~ +1 # cmd.yawSpeed = 0 # cmd.bodyHeight = 0.1 if(motiontime > 0 and motiontime < 1000): cmd.mode = 1 cmd.euler = [-0.3, 0, 0] if(motiontime > 1000 and motiontime < 2000): cmd.mode = 1 cmd.euler = [0.3, 0, 0] if(motiontime > 2000 and motiontime < 3000): cmd.mode = 1 cmd.euler = [0, -0.2, 0] ...
Python
복사
UDP통신으로 로봇과 연결한 후 하는 것이라 시뮬에서는 안될듯?

4. GPS PLUGIN 셋팅

URDF 셋팅(robot < descriptions < unitree_ros < robots < go1_descriptions < xacro < go1.champ.urdf에 다음파일 복붙)
<joint name="gps_joint" type="fixed"> <parent link="trunk"/> <child link="gps_link"/> </joint> <link name="gps_link"> <collision> <origin xyz="0 0 0.1" rpy="0 0 0"/> <geometry> <box size="0.2 0.2 0.2"/> </geometry> </collision> <visual> <origin xyz="0 0 0.1" rpy="0 0 0"/> <geometry> <box size="0.2 0.2 0.2"/> </geometry> <material name="blue"/> </visual> <inertial> <origin xyz="0 0 1" rpy="0 0 0"/> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <gazebo> <plugin name="gazebo_ros_gps" filename="libhector_gazebo_ros_gps.so"> <updateRate>4.0</updateRate> <bodyName>gps_link</bodyName> <frameId>gps_link</frameId> <topicName>/gps/fix</topicName> <velocityTopicName>/gps/fix_velocity</velocityTopicName> <referenceLatitude>-30.06022459407145675</referenceLatitude> <referenceLongitude>-51.173913575780311191</referenceLongitude> <referenceHeading>90</referenceHeading> <referenceAltitude>10</referenceAltitude> <offset>0 0 0</offset> <drift>0.001 0.001 0.001</drift> <gaussianNoise>0.05 0.05 0.05</gaussianNoise> <velocityDrift>0.001 0.001 0.001</velocityDrift> <velocityGaussianNoise>0.5 0.5 0.5</velocityGaussianNoise> </plugin> </gazebo>
JavaScript
복사
gps topic = /gps/fix

5. Lidar plugin 셋팅

URDF셋팅(robot < descriptions < unitree_ros < robots < go1_descriptions < xacro < go1.champ.urdf에 다음파일 복붙)
<!-- lidar --> <joint name="hokuyo_joint" type="fixed"> <origin rpy="0 0 0" xyz="0.0 0.0 0.2"/> <parent link="gps_link"/> <child link="hokuyo_frame"/> </joint> <link name="hokuyo_frame"> <!-- <inertial> <mass value="0.270"/> <origin rpy="0 0 0" xyz="0 0 0.5"/> <inertia ixx="2.632e-4" ixy="0" ixz="0" iyy="2.632e-4" iyz="0" izz="1.62e-4"/> </inertial> --> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> <mesh filename="package://hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.dae"/> </geometry> </visual> <collision> <origin rpy="0 0 0" xyz="0 0 -0.0115"/> <geometry> <box size="0.058 0.058 0.087"/> <!--<mesh filename="package://hector_sensors_description/meshes/hokuyo_utm30lx/hokuyo_utm_30lx.stl"/>--> </geometry> </collision> </link> <gazebo reference="hokuyo_frame"> <sensor name="hokuyo" type="ray"> <always_on>true</always_on> <update_rate>30</update_rate> <pose>0 0 0 0 0 0</pose> <visualize>true</visualize> <ray> <scan> <horizontal> <samples>1040</samples> <resolution>1</resolution> <min_angle>2.26892802759</min_angle> <max_angle>-2.26892802759</max_angle> </horizontal> </scan> <range> <min>0.2</min> <max>30.0</max> <resolution>0.01</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.004</stddev> </noise> </ray> <plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_hokuyo_controller"> <topicName>scan</topicName> <frameName>hokuyo_frame</frameName> </plugin> </sensor> </gazebo>
JavaScript
복사

6. Purepursuit을 적용하여 정해진 경로를 따라 로봇 제어

영상
7.
movebase 실험