-
Notifications
You must be signed in to change notification settings - Fork 14
HAPTIX Matlab and Octave API
이번 튜토리얼에서는 손의 설명을 요청하고 조인트 명령을 보내고 상태 업데이트를 받기위하여 사용하는 Matlab(윈도우)이나 Octave(리눅스)를 사용하는 법을 설명한다.
이미 설치 과정을 마쳤다고 가정한다.
데스크탑 아이콘 haptixStart
를 더블클릭한다.
Matlab을 열기 전에 환경변수 'IGN_IP'가 셋팅되어있는지 확인해라. 자세한 설명은 설치 과정으로 가서 Network Configration 장을 확인해라.
Matlab을 열고 Browse for folder
아이콘을 클릭하여라.
새로운 팝업 윈도우가 나타날 것이다. HAPTIX 클라이언트 라이브러리 SDK의 압축을 푼 디렉토리에서 matlab\
폴더를 찾는다. HAPTIX 클라이언트 라이브러리 SDK에는 Matlab 콘솔 또는 .m 파일에서 hx_connect()
, hx_robot_info()
, hx_update()
, hx_read_sensors()
및 hx_close()
함수를 호출 할 수있는 mex
파일이 있다. MATLAB에서 hx_matlab_controller.m
파일을 열고 Matlab 명령 창에 다음을 입력한다:
hx_matlab_controller
아래 controller visualization 비디오와 같은 팔의 움직임을 볼 수 있다.
만약 준비가 되어있지 않다면 먼저 Octave를 설치한다.
sudo apt-get install octave liboctave-dev
그리고 설치된 haptix-comm
의 하위 디렉토리인 octave
디렉토리로 이동한다. 이 디렉토리에는 몇개의 .m
파일이 있다.
cd /usr/lib/x86_64-linux-gnu/haptix-comm/octave
만약에 위 디렉토리가 없다면, 아래 명령을 시도해 보아라:
cd /usr/lib/haptix-comm/octave
Octave를 시작한다.
octave
Octave에서 hx_connect()
, hx_robot_info()
, hx_update()
, hx_read_sensors()
및 hx_close()
를 호출 할 수 있어야한다(괄호는 선택 사항임).
시뮬레이트된 팔(arm)에 대한 컨트롤러를 실행하려면 다음과 같이 입력하라:
hx_matlab_controller
아래 controller visualization 비디오와 같은 팔의 움직임을 볼 수 있다.
컨드롤러가 실행되는 동안 가제보 상의 손가락은 부드러운 경로를 따라 움직인다.
counter = 0;
hx_connect();
deviceInfo = hx_robot_info();
% Uncomment this block to start logging.
% hxs_start_logging('/tmp/log/')
while counter < 250
cmdSent = tic;
% Initialize the command scalar structure.
cmd.ref_pos = [];
cmd.ref_vel = [];
cmd.ref_vel_max = [];
cmd.gain_pos = [];
cmd.gain_vel = [];
% Indicate that the positions we set should be used.
cmd.ref_pos_enabled = 1;
% We're not setting it, so indicate that ref_vel should be ignored.
cmd.ref_vel_enabled = 0;
% We're not setting it, so indicate that ref_vel_max should be ignored.
cmd.ref_vel_max_enabled = 0;
% We're not setting it, so indicate that gain_pos should be ignored.
cmd.gain_pos_enabled = 0;
% We're not setting it, so indicate that gain_vel should be ignored.
cmd.gain_vel_enabled = 0;
% Create a new command based on a sinusoidal wave.
for n = 0:deviceInfo.motor_count
cmd.ref_pos(end + 1) = 350 * 0.5 * sin(0.05 * 2.0 * pi * counter * 0.08);
% We could set a desired maximum velocity
% cmd.ref_vel(end + 1) = 1.0;
% cmd.ref_vel_max(end + 1) = 1.0;
% We could set a desired controller position gain
% cmd.gain_pos(end + 1) = 1.0;
% We could set a desired controller velocity gain
% cmd.gain_vel(end + 1) = 1.0;
end
% Send the new joint command and receive the state update.
state = hx_update(cmd);
counter = counter + 1;
% Busy wait. pause() is not accurate enough on Windows.
elapsedCmd = toc(cmdSent);
while elapsedCmd < 0.02
elapsedCmd = toc(cmdSent);
end
end
% Uncomment this block to stop logging.
% hxs_stop_logging()
hx_close();
HAPTIX Matlab/Octave API는 hx_connect()
, hx_robot_info()
, hx_update()
, hx_read_sensors()
및 hx_close()
의 다섯 가지 함수로 구성된다. hx_connect()
와 hx_close()
는 Gazebo 시뮬레이터에서는 선택 사항이지만 MuJoCo와의 호환성을 위해 포함되어 있다.
hx_robot_info()
는 주어진 장치로부터 정보를 요청한다. 이 튜토리얼에서 장치는 Gazebo에서 시뮬레이션 된 손이다. 이 호출은 응답이 수신 될 때까지 차단된다.
hx_robot_info()
의 결과 값은 요청된 장치에 대한 모터, 조인트, 접촉 센서, IMU 및 조인트 제한 수를 포함하는 구조체이다. 또한 장치가 업데이트되는 빈도인 업데이트 속도도 포함됩니다.
장치 정보를 확인하면 손 제어 명령을 보낼 수 있다. hx_update()
함수는 새로운 명령을 보내고 현재 손의 상태를받는 역할을 담당한다.
각 조인트의 위치, 속도 및 이득을 포함하는 명령 구조체를 채울 필요가 있습니다. 이 예제에서 사용하는 필드에 대해 동일한 이름을 사용하는 것이 중요하다.
명령을 적용한 후 명령의 센서 상태를 나타내는 구조체를 반환하는 hx_update()
함수를 호출한다.
-
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]