-
Notifications
You must be signed in to change notification settings - Fork 14
Atlas fake walking
이번 장에서는 Atlas가 마치 바퀴 달린 로봇 처럼 움직이는 방법에 대해서 설명 한다.(걷거나 균형잡는 것 없이)
이번 장에서는 walking controller를 사용하지 않는다. 단순히 Atlas는 다음 그림 처럼 위치 제어로 서있게 유지한다.
drcsim 4.x.x에서 로봇은 서있는 자세로 시작한다.
다리를 포함한 로봇의 모든 조인트 물리적으로 시뮬레이션 되고 컨트롤 된다.
이번 튜토리얼에서 시뮬레이션 되는 로봇은 걸을 수 없지만 여전히 world내에서 움직 이기를 원한다. 시뮬레이션 되는 로봇은 지면에서 이동 및 회전 할 수 있도록 ROS를 통해서 속도 지령을 받는다. 마치 바퀴 달린 로봇 처럼 움직인다.
-
시뮬레이션 시작하기
VRC_CHEATS_ENABLED=1 roslaunch drcsim_gazebo atlas.launch
Note: 변수
VRC_CHEATS_ENABLED=1
를 셋팅 하는 것은/atlas/cmd_vel
을 포함해서 몇 가지 개발 목적의 토픽을 나타낸다. 이것은 VRC 대회에서 초기값으로 사용되지 않는다.시뮬레이션 되는 로봇은 ROS Twist을 기다린다.
atlas/cmd_vel
토픽은 6자유도의 속도이다. rostopic을 체크 해보아라.rostopic info atlas/cmd_vel
다음과 같은 토픽을 확인 할 수 있다.
%%% Type: geometry_msgs/Twist Publishers: None Subscribers:
- /gazebo (http://osrf-Latitude-E6420:35339/) %%%
어디에서든 ROS Twist 메세지를 퍼플리시 할 수 있다. 우선 rosmsg를 사용하여 Twist 메세지 에서 무엇이 있는지 확인 하자.
rosmsg show Twist
다음을 확인 할 수 있다.
%%% [geometry_msgs/Twist]: geometry_msgs/Vector3 linear float64 x float64 y float64 z geometry_msgs/Vector3 angular float64 x float64 y float64 z %%%
이것은 6자유도 속도이다. 3개의 속도(X,Y,Z)와 3개의 각속도(Rx,Ry,Rz)이다. 로봇은 평면에서 움직임이 구속되고 오직 X,Y,Rz로만 움직인다.
-
서있는 자세로 로봇을 위치시킨다.
rostopic pub --once /atlas/mode std_msgs/String "pid_stand"
-
발이 땅에 닿지 않게 하기 위해 로봇을 고정한다.
rostopic pub --once /atlas/mode std_msgs/String "pinned"
-
로봇을 원에서 시계반대 방향으로 움직이게 만든다.
rostopic pub -r 10 atlas/cmd_vel geometry_msgs/Twist '{ linear: { x: 0.5, y: 0.0, z: 0.0 }, angular: { x: 0.0, y: 0.0, z: 0.5 } }'
보내지는 매 cmd_vel
은 연관된 수명이 있다. 속도 지령은 0.1초 동안 Atlas에 적용된다. 그 이후 로봇은 멈출 것이다. 만약 당신이 보낸 이전 'rostopic' 명령어를 보면 -r 10
옵션 변수가 포함되어 있다. 이것은 같은 메세지를 10hz로 퍼블리시 하게 한다. 이는 로봇이 멈추지 않도록 한다.
속도 명령의 시간 초과 값을 설정 가능하다.
-
atlas.launch
파일에 새로운 ROS 파라미터를 추가 해라.<param name="/atlas/cmd_vel_timeout" type="double" value="0.2"/>
-
drcsim을 런치 하기 전에
rosparam
을 실행 하여라.rosparam set /atlas/cmd_vel_timeout 0.2
다음 명령어를 사용하여 전송된 명령어를 확인 할 수 있다.
rostopic echo atlas/cmd_vel
로봇을 멈추게 하기 위해서 CTRL-C를 누르면 된다.
-
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]