-
Notifications
You must be signed in to change notification settings - Fork 14
Razer Hydra
Gazebo는 Razer Hydra 컨트롤러를 지원합니다. 이 모션 및 방향 감지 컨트롤러를 사용하여 Gazebo에서 모델과 상호 작용할 수 있습니다.
Razer hydra 컨트롤러는 6자유도 VR 컨트롤러입니다. 하지만 거의 사용하지 않는 오래된 컨트롤러라 다른 기기를 사용하길 추천합니다.
터미널 (CTRL-ALT-T)을 열고 다음 명령을 실행하십시오.
echo -e "ATTRS{idProduct}=="0300",ATTRS{idVendor}=="1532",ATTR{bInterfaceNumber}=="00",TAG="hydra-tracker"\nSUBSYSTEM=="hidraw",TAGS=="hydra-tracker", MODE="0666", SYMLINK+="hydra"" > 90-hydra.rules
그러면 90-hydra.rules라는 파일이 생성됩니다.
루트 액세스없이 컨트롤러에 액세스 할 수 있어야합니다.
sudo cp 90-hydra.rules /etc/udev/rules.d/ sudo udevadm control --reload-rules
optional libusb dependecy를 설치해야합니다.
sudo apt-get install libusb-1.0-0-dev
Hydra가 구성되고 추가 종속성이 만족되면 Hydra 지원 소스에서 Gazebo를 컴파일 할 수 있어야합니다.
Gazebo를 컴파일하려면이 지시 사항을 따르십시오. cmake 명령을 실행하는 동안 SDK가 발견되었음을 확인하는 메시지가 표시됩니다.
-- Looking for libusb-1.0 - found. Razer Hydra support enabled.
가제보에서 히드라를 사용하려면 두 단계가 필요합니다. 첫 번째 단계는 월드 파일에 Hydra 플러그인을로드하는 것입니다
이 플러그인은 주제에 대한 메시지를 자동으로 게시합니다. ~/hydra.
두 번째 단계는 hydra 주제를 구독하고 흥미로운 것을 만드는 플러그인을 작성하는 것입니다. 이 튜토리얼에서는 Hydra의 오른쪽 조이스틱을 사용하여 구체를 이동합니다. HydraDemoPlugin은 Gazebo의 plugins / 디렉토리에서 사용할 수 있습니다.
Plugin code:
#include <boost/bind.hpp> #include <gazebo/gazebo.hh> #include <gazebo/physics/physics.hh> #include "gazebo/transport/transport.hh" #include "HydraDemoPlugin.hh"
using namespace gazebo;
GZ_REGISTER_MODEL_PLUGIN(HydraDemoPlugin)
///////////////////////////////////////////////// HydraDemoPlugin::HydraDemoPlugin() { }
///////////////////////////////////////////////// HydraDemoPlugin::~HydraDemoPlugin() { }
///////////////////////////////////////////////// void HydraDemoPlugin::OnHydra(ConstHydraPtr &_msg) { boost::mutex::scoped_lock lock(this->msgMutex); this->hydraMsgPtr = _msg; }
///////////////////////////////////////////////// void HydraDemoPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr /_sdf/) { // Get the world name. this->model = _parent; this->world = this->model->GetWorld();
// Subscribe to Hydra updates by registering OnHydra() callback. this->node = transport::NodePtr(new transport::Node()); this->node->Init(this->world->GetName()); this->hydraSub = this->node->Subscribe("~/hydra", &HydraDemoPlugin::OnHydra, this);
// Listen to the update event. This event is broadcast every // simulation iteration. this->updateConnection = event::Events::ConnectWorldUpdateBegin( boost::bind(&HydraDemoPlugin::Update, this, _1)); }
///////////////////////////////////////////////// void HydraDemoPlugin::Update(const common::UpdateInfo & /_info/) { boost::mutex::scoped_lock lock(this->msgMutex);
// Return if we don't have messages yet if (!this->hydraMsgPtr) return;
// Read the value of the right joystick. double joyX = this->hydraMsgPtr->right().joy_x(); double joyY = this->hydraMsgPtr->right().joy_y();
// Move the sphere. this->model->SetLinearVel(math::Vector3(-joyX * 0.2, joyY * 0.2, 0));
// Remove the message that has been processed. this->hydraMsgPtr.reset(); }
Gazebo를 시작하기 전에 모델 플러그인을 월드 파일에 포함시켜야합니다. 다음은 튜토리얼의 전체 세계 파일입니다 (world / hydra_demo.world에서도 사용 가능).
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<!-- Load the plugin for Razer Hydra -->
<plugin name="hydra" filename="libHydraPlugin.so">
<pivot>0.04 0 0</pivot>
<grab>0.12 0 0</grab>
</plugin>
<!-- A sphere controlled by Hydra-->
<model name="sphere">
<pose>0 0 0 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</visual>
</link>
<plugin name='sphere_ctroller' filename='libHydraDemoPlugin.so'></plugin>
</model>
가제보를 실행하고 히드라의 오른쪽 조이스틱을 사용하여 구를 움직여야합니다. 히드라 플러그를 잊지 말고 다음을 수행하십시오.
gazebo worlds/hydra_demo.world
-
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]