-
Notifications
You must be signed in to change notification settings - Fork 14
Spawn Atlas into a custom world
이번 장에서는 Gazebo world를 어떻게 생성하고 거기에 Atlas 로봇을 추가 할 수 있는지에 대해서 설명합니다.
다음과 같이 패키지를 생성한다.
cd ~/catkin_ws/src
catkin_create_pkg world_create_tutorial drcsim_gazebo
cd world_create_tutorial
mkdir worlds launch
이제 다음의 launch 파일 here을 다운 받아서 ~/catkin_ws/src/world_create_tutorial/launch/atlas.launch
이 경로에 저장을 한다.
<launch>
<arg name="gzname" default="gazebo"/>
<arg name="gzworld" default="$(find world_create_tutorial)/worlds/myworld.world"/>
<arg name="hand_suffix" default=""/>
<arg name="extra_gazebo_args" default="-q" />
<arg name="model_args" default="" />
<arg name="inertia_args" default="" /> <!-- _with_v1_inertia -->
<param name="/atlas/time_to_unpin" type="double" value="1.0"/>
<param name="/atlas/startup_mode" type="string" value="bdi_stand"/>
<!-- start gazebo with the Atlas -->
<include file="$(find drcsim_gazebo)/launch/atlas_no_controllers.launch">
<arg name="gzname" value="$(arg gzname)"/>
<arg name="gzworld" value="$(arg gzworld)"/>
<arg name="extra_gazebo_args" value="$(arg extra_gazebo_args)"/>
</include>
<!-- to trigger synchronization delay, set
atlas_msgs::AtlasCommand::desired_controller_period_ms to non-zero -->
<param name="/atlas/delay_window_size" type="double" value="5.0"/>
<param name="/atlas/delay_max_per_window" type="double" value="0.25"/>
<param name="/atlas/delay_max_per_step" type="double" value="0.025"/>
<!-- Robot Description -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find atlas_description)/robots/atlas$(arg model_args)$(arg inertia_args)$(arg hand_suffix).urdf.xacro'" />
<param name="robot_initial_pose/x" value="0" type="double"/>
<param name="robot_initial_pose/y" value="0" type="double"/>
<param name="robot_initial_pose/z" value="0.90" type="double"/>
<param name="robot_initial_pose/roll" value="0" type="double"/>
<param name="robot_initial_pose/pitch" value="0" type="double"/>
<param name="robot_initial_pose/yaw" value="0" type="double"/>
<include file="$(find drcsim_gazebo)/launch/atlas$(arg hand_suffix)_bringup.launch">
<arg name="model_args" value="$(arg model_args)"/>
</include>
</launch>
만약 당신 Atlas 로봇의 초기 위치를 다른 위치에 놓기를 원한다면 robot_initial_pose/x
와 robot_initial_pose/y
를 바꾸면 된다.
가제보를 실행하여라.
gazebo
당신은 빈 세계를 볼 수 있다.
이제 툴바에서의 아이콘들을 활용하여 간단한 형태의 모델들을 추가 해보아라. 박스와 구 실린더를 추가 할 수 있다.
"Insert Models" tab에 있는 환경들 또한 추가 할 수 있다.
위의 작업을 끝내고 world를 저장하기 위해서 "File"에 "Save World As"를 클릭하여라. 혹은 단축키 CTRL-SHIFT-S를 누르면 된다. 이후 `~/catkin_ws/src/world_create_tutorial/worlds'에 'myworld.world'의 이름으로 저장하고 Gazebo를 빠져 나오면 된다.
이제 'myworld.world'를 열고 다음의 내용을 파일에 삽입하고 저장하여라. 이때 <world></world>
tag 내부에 삽입 하여야 한다.
<plugin filename="libVRCPlugin.so" name="vrc_plugin">
<atlas>
<model_name>atlas</model_name>
<pin_link>utorso</pin_link>
</atlas>
<drc_vehicle>
<model_name>golf_cart</model_name>
<seat_link>chassis</seat_link>
</drc_vehicle>
<drc_fire_hose>
<fire_hose_model>fire_hose</fire_hose_model>
<coupling_link>coupling</coupling_link>
<standpipe_model>standpipe</standpipe_model>
<spout_link>standpipe</spout_link>
<thread_pitch>-1000</thread_pitch>
<coupling_relative_pose>1.17038e-05 -0.125623 0.35 -0.0412152 -1.57078 1.61199</coupling_relative_pose>
</drc_fire_hose>
</plugin>
이 plugin 요소는 Atlas 로봇을 불러온다. VRCPlugin은 로봇의 자세 컨트롤러, 컨트롤러 인터페이스를 관리한다.
다음을 통해 자기가 만든 새로운 world에 Atlas 로봇을 불러오게 된다.
roslaunch world_create_tutorial atlas.launch
-
Robot Simulators
-
Build a Robot
- Model structure and requirements
- How to contribute a model
- Make a model
- Make a Mobile Robot
- The relationship among Link, Joint and Axis
- Import Meshes
- Attach Meshes
- Add a Sensor to a Robot
- Make a Simple Gripper
- Attach Gripper to Robot
- Nested model
- Model Editor
- Animated Box
- Make an animated model(actor)
- Inertial parameters of triangle meshes
- Visibility layers
-
Model Editor
-
Build a World
-
Tools and utilities
-
Write a plugin
-
Plugins
-
Sensors
-
User input
-
Transport Library
-
Rendering Library
-
Connect to ROS
-
Ros Control - Advanced
-
DRCSIM for ROS Kinetic (Ubuntu16.04)
-
DRCSIM
- DRC Simulator installation
- Launchfile options
- Spawn Atlas into a custom world
- Animate joints
- Atlas Keyboard Teleoperation over ROS
- Teleoperate atlas with a music mixer
- Visualization and logging
- Atlas MultiSense SL head
- How to use the Atlas Sim Interface
- Atlas fake walking
- Grasp with Sandia hands
- DRC vehicle tele-operation
- DRC vehicle tele operation with Atlas
- Sending joint commands with ROS
- Atlas control over ROS with python
- Modify environment
- Atlas switching control modes
- Atlas Controller Synchronization over ROS Topics
- Changing Viscous Damping Coefficients Over ROS Service
- Running BDI controller demo
- Using the RobotiQ 3 Finger Adaptive Robot Gripper
- BDI Atlas Robot Interface 3.0.0 Stand In Example
-
HAPTIX
- HAPTIX software install and update
- HAPTIX C API
- HAPTIX Matlab and Octave API
- HAPTIX Simulation World API
- HAPTIX Teleoperation
- HAPTIX environment setup
- HAPTIX Optitrack Control
- HAPTIX Tactor Glove
- HAPTIX Simulation World API with Custom World Example
- HAPTIX logging
- HAPTIX DEKA Luke hand installation
- HAPTIX Simulation Scoring Plugin Example
-
MoveIt!
-
Rviz & rqt & ROSBAG
- Control Theory
- TroubleShooting
- Solidworks model to URDF
- ROS-Gazebo with MATLab
- MATLab installation in Linux
- [Gazebo simulation with MATLab]