Table of Contents

Integrating ROS 2 with OpenVR SDK

Date: Last modified on <03/09/18>

Motivation and Audience

This tutorial's motivation is to teach the reader how to integrate OpenVR code with ROS 2. Readers of this tutorial are assumed to have the following background and interests:
*Have basic knowledge of CPP
*Have previous experience with ROS 1 or ROS 2
*Have previous experience with OpenVR
*This tutorial may also attract readers who want to learn how to use the windows development environment for ROS 2.0

Note 1: If the reader is unfamiliar with OpenVR please refer to these tutorials:
*Hardware Setup for the HTC Vive
*Setting up OpenVR
*Using HTC Vive to Control Dynamixel Servo
Note 2: If the reader is unfamiliar with ROS 1 or ROS 2 please refer to these texts:
*ROS 1 Introduction
*ROS 2 Introduction

This tutorial will follow the following format:

Parts Lists and Sources

Look at the Hardware Setup for the HTC Vive tutorial for the parts and sources for them needed to run the HTC Vive.

Installing ROS 2 on Windows 10

This tutorial will be using the Ardent Apalone release of ROS 2 on Windows. As time goes on newer releases will become available and installation process may differ. Please refer to the Windows Development Setup tutorial, although there are other windows installation tutorials this is the most in-depth and shows how to build packages. Before going to the tutorial there are a few things readers may not know.



Then edit the Path in System Variables to add a “New” path to the list. You can get to the system




Once you understand these please follow the steps described in the tutorial

Integrating OpenVR into ROS 2 Environment and Adding Controller Input

In this section, we will be utilizing pre-built OpenVR code to modify so that we can build it in the ROS 2 workspace. The OpenVR code is a modified version of the “Hello World” code which shows a matrix of cubes with user-defined pictures on each side and is able to take some controller inputs. We will be trying to publish the controller inputs to ROS 2.

1. Creating a New ROS 2 Package your file explorer create a new package in the src folder of your ROS 2 workspace. This is where we will be putting all of the related code.

2. Copy over the hellovr_opengl_main.cpp file for the OpenVR “hellovr_opengl” example and rename it to main.cpp
Note: Don't worry about the other folders and files. We will make them later on.

3. Adding the ROS 2 Components into the code
First, we need to add the appropriate header files for ROS 2 and the message type you want to use. In this case, we will be using the sensor_msg/joy type(The ros 1 and 2 definitions are the same). Add the following code to the top of the file.

//include files for ros 2
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/utilities.hpp"
#include "sensor_msgs/msg/joy.hpp"
 
//Variables for controller inputs
const int butt_num = 6; //the number of button input. xyz for left and right hands
 
 
//left
short int lb_x = 0;
short int lb_y = 0;
short int lb_z = 0;
float l_new_pos_z = 0;
float l_old_pos_z = 0;
float l_delta_z = 0;
 
//right
short int rb_x = 0;
short int rb_y = 0;
short int rb_z = 0;
float r_new_pos_z = 0;
float r_old_pos_z = 0;
float r_delta_z = 0;
 
//variables to turn on and off ros 2 input
int dirty = 0;



Then find the bool CMainApplication::HandleInput() function and where it is defined. Then add the following code by replacing the for loop under the Process SteamVR controller state with it.

  // Process SteamVR controller state
    for (vr::TrackedDeviceIndex_t unDevice = 0; unDevice < vr::k_unMaxTrackedDeviceCount; unDevice++) {
        if (!m_pHMD->IsTrackedDeviceConnected(unDevice))
            continue;
 
        vr::TrackedDevicePose_t trackedDevicePose;
        vr::TrackedDevicePose_t *devicePose = &trackedDevicePose;
 
        vr::VRControllerState_t controllerState;
        vr::VRControllerState_t *ontrollerState_ptr = &controllerState;
 
        vr::HmdVector3_t position;
        vr::HmdQuaternion_t quaternion;
 
        bool bPoseValid = trackedDevicePose.bPoseIsValid;
        vr::HmdVector3_t vVel;
        vr::HmdVector3_t vAngVel;
        vr::ETrackingResult eTrackingResult;
 
        vr::ETrackedDeviceClass trackedDeviceClass = vr::VRSystem()->GetTrackedDeviceClass(unDevice);
        switch (trackedDeviceClass) {
            case vr::ETrackedDeviceClass::TrackedDeviceClass_HMD:
                //don't care about hmd for now
                break;
            case vr::ETrackedDeviceClass::TrackedDeviceClass_Controller:
                // Simliar to the HMD case block above, please adapt as you like
                // to get away with code duplication and general confusion
 
                vr::VRSystem()->GetControllerStateWithPose(vr::TrackingUniverseStanding, unDevice, &controllerState,
                                                           sizeof(controllerState), &trackedDevicePose);
 
                position = GetPosition(devicePose->mDeviceToAbsoluteTracking);
                quaternion = GetRotation(devicePose->mDeviceToAbsoluteTracking);
 
 
                vVel = trackedDevicePose.vVelocity;
                vAngVel = trackedDevicePose.vAngularVelocity;
                eTrackingResult = trackedDevicePose.eTrackingResult;
                bPoseValid = trackedDevicePose.bPoseIsValid;
 
                switch (vr::VRSystem()->GetControllerRoleForTrackedDeviceIndex(unDevice)) {
                    case vr::TrackedControllerRole_Invalid:
                        // invalid hand...
                        break;
 
                    case vr::TrackedControllerRole_LeftHand:
 
                        if (m_pHMD->GetControllerState(unDevice, &controllerState, sizeof(controllerState))) {
                            m_rbShowTrackedDevice[unDevice] = controllerState.ulButtonPressed == 0;
                            if (controllerState.ulButtonPressed & vr::ButtonMaskFromId(vr::k_EButton_ApplicationMenu)) {
                                //printf("l_Application Menu\n");
                                if (dirty == 1) {
                                    dirty = 0;
                                    printf("UNDIRTY\n");
                                    lb_x = 0;
                                    lb_y = 0;
                                    lb_z = 0;
                                    rclcpp::sleep_for(100ms);
 
 
                                } else if (dirty == 0) {
                                    dirty = 1;
                                    printf("DIRTY\n");
                                    rclcpp::sleep_for(100ms);
 
                                }
                            }
                            if (controllerState.ulButtonPressed & vr::ButtonMaskFromId(vr::k_EButton_Grip)) {
                                printf("l-Grip\n");
                            }
                            if (controllerState.ulButtonPressed & vr::ButtonMaskFromId(vr::k_EButton_Axis0)) {
                                //printf("l-Axis 0, (%f,%f)\n", controllerState.rAxis[0].x,controllerState.rAxis[0].y);
                                double l_axis_y = controllerState.rAxis[0].y;
                                double l_axis_x = controllerState.rAxis[0].x;
                                if (l_axis_y > 0.4 && abs(l_axis_x) < 0.4) {
                                    printf("forward\n");
                                    lb_x = 1;
                                    lb_y = 0;
                                }
                                if (l_axis_y < 0.4 && abs(l_axis_x) < 0.4) {
                                    printf("backward\n");
                                    lb_x = -1;
                                    lb_y = 0;
                                }
                                if (l_axis_x > 0.4 && abs(l_axis_y) < 0.4) {
                                    printf("right\n");
                                    lb_x = 0;
                                    lb_y = 1;
                                }
                                if (l_axis_x < 0.4 && abs(l_axis_y) < 0.4) {
                                    printf("left\n");
                                    lb_x = 0;
                                    lb_y = -1;
                                }
                                if (l_axis_y > 0.4 && l_axis_x > 0.4) {
                                    printf("forward - right \n");
                                    lb_x = 1;
                                    lb_y = 1;
                                }
                                if (l_axis_y < -0.4 && l_axis_x > 0.4) {
                                    printf("backward - right \n");
                                    lb_x = -1;
                                    lb_y = 1;
                                }
                                if (l_axis_y > 0.4 && l_axis_x < -0.4) {
                                    printf("forward - left \n");
                                    lb_x = 1;
                                    lb_y = -1;
                                }
                                if (l_axis_y < -0.4 && l_axis_x < -0.4) {
                                    printf("backward - left \n");
                                    lb_x = -1;
                                    lb_y = -1;
                                }
                                if (abs(l_axis_x) < 0.3 && abs(l_axis_y) < 0.3) {
                                    printf("Zero\n");
                                    lb_x = 0;
                                    lb_y = 0;
                                }
                            }
 
                            l_new_pos_z = position.v[1];
 
 
                            if (abs(l_old_pos_z - l_new_pos_z) > 0.00075) {
                                if (l_old_pos_z > l_new_pos_z) {
                                    l_delta_z = -1;
                                    lb_z = -1;
                                }
                                if (l_old_pos_z < l_new_pos_z) {
                                    l_delta_z = 1;
                                    lb_z = 1;
                                }
                                l_old_pos_z = l_new_pos_z;
                            } else {
                                l_delta_z = 0;
                                lb_z = 0;
                            }
 
                        }
                        break;
                    case vr::TrackedControllerRole_RightHand:
                        if (m_pHMD->GetControllerState(unDevice, &controllerState, sizeof(controllerState))) {
                            m_rbShowTrackedDevice[unDevice] = controllerState.ulButtonPressed == 0;
                            if (controllerState.ulButtonPressed & vr::ButtonMaskFromId(vr::k_EButton_ApplicationMenu)) {
                                //printf("l_Application Menu\n");
                                if (dirty == 1) {
                                    dirty = 0;
                                    printf("UNDIRTY\n");
                                    rclcpp::sleep_for(100ms);
                                    rb_x = 0;
                                    rb_y = 0;
                                    rb_z = 0;
 
 
                                } else if (dirty == 0) {
                                    dirty = 1;
                                    printf("DIRTY\n");
                                    rclcpp::sleep_for(100ms);
 
                                }
                            }
                            if (controllerState.ulButtonPressed & vr::ButtonMaskFromId(vr::k_EButton_Grip)) {
                                printf("r-Grip\n");
                            }
                            if (controllerState.ulButtonPressed & vr::ButtonMaskFromId(vr::k_EButton_Axis0)) {
                                double r_axis_y = controllerState.rAxis[0].y;
                                double r_axis_x = controllerState.rAxis[0].x;
                                if (r_axis_y > 0.4 && abs(r_axis_x) < 0.4) {
                                    printf("forward\n");
                                    rb_x = 1;
                                    rb_y = 0;
                                }
                                if (r_axis_y < 0.4 && abs(r_axis_x) < 0.4) {
                                    printf("backward\n");
                                    rb_x = -1;
                                    rb_y = 0;
                                }
                                if (r_axis_x > 0.4 && abs(r_axis_y) < 0.4) {
                                    printf("right\n");
                                    rb_x = 0;
                                    rb_y = 1;
                                }
                                if (r_axis_x < 0.4 && abs(r_axis_y) < 0.4) {
                                    printf("left\n");
                                    rb_x = 0;
                                    rb_y = -1;
                                }
                                if (r_axis_y > 0.4 && r_axis_x > 0.4) {
                                    printf("forward - right \n");
                                    rb_x = 1;
                                    rb_y = 1;
                                }
                                if (r_axis_y < -0.4 && r_axis_x > 0.4) {
                                    printf("backward - right \n");
                                    rb_x = -1;
                                    rb_y = 1;
                                }
                                if (r_axis_y > 0.4 && r_axis_x < -0.4) {
                                    printf("forward - left \n");
                                    rb_x = 1;
                                    rb_y = -1;
                                }
                                if (r_axis_y < -0.4 && r_axis_x < -0.4) {
                                    printf("backward - left \n");
                                    rb_x = -1;
                                    rb_y = -1;
                                }
                                if (abs(r_axis_x) < 0.4 && abs(r_axis_y) < 0.4) {
                                    printf("Right Zero\n");
                                    rb_x = 0;
                                    rb_y = 0;
                                }
                            }
                            r_new_pos_z = position.v[1];
                            if (abs(r_old_pos_z - r_new_pos_z) > 0.00075) {
                                if (r_old_pos_z > r_new_pos_z) {
                                    r_delta_z = -1;
                                    rb_z = -1;
                                }
                                if (r_old_pos_z < r_new_pos_z) {
                                    r_delta_z = 1;
                                    rb_z = 1;
                                }
                                r_old_pos_z = r_new_pos_z;
                            } else {
                                r_delta_z = 0;
                                rb_z = 0;
                            }
                        }
                        break;
                }
                break;
        }



Then add the following code to create the node, publisher, and message to the void CMainApplication::RunMainLoop() function.

auto node = rclcpp::Node::make_shared("vive_test");
auto publisher_joy = node->create_publisher<sensor_msgs::msg::Joy>("hubo/joy");
auto message_joy = std::make_shared<sensor_msgs::msg::Joy>();
message_joy->header.stamp.sec = 0;
message_joy->header.stamp.nanosec = 0;
message_joy->header.frame_id = "joy";
message_joy->axes.resize(2);
message_joy->axes[0] = message_joy->axes[1] = 0;



Then finally add this code into the while loop within the same function

if(dirty == 1)
{
   message_joy->buttons.resize(6);
   message_joy->buttons[0] = lb_x;
   message_joy->buttons[1] = lb_y;
   message_joy->buttons[2] = lb_z;
   message_joy->buttons[3] = rb_x;
   message_joy->buttons[4] = rb_y;
   message_joy->buttons[5] = rb_z;
 
   publisher_joy->publish(message_joy);
   rclcpp::spin_some(node);
   rclcpp::sleep_for(10ms);
}



We are now done with modifying the main.cpp file!
4. Create the CMakeLists.txt file
In this section we will make the CMakeLists.txt. This file will tell the compiler where to find the various API and libraries for the code. Make a new text file in the src workspace and call it CMakeLists.txt. Then add the following code into it:

cmake_minimum_required(VERSION 3.5)
project(vivetest)
 
if(NOT WIN32)
    set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Wextra -Wpedantic")
endif()
 
# -----------------------------------------------------------------------------
## SYSTEM PROPERTIES ##
if(NOT PLATFORM)
  if(CMAKE_SIZEOF_VOID_P MATCHES 8)
    set(PLATFORM 64)
  else()
    set(PLATFORM 32)
  endif()
endif()
message(STATUS "Compilation set for ${PLATFORM}bits architectures.")
set(SDL_REQUIRED_LIBRARIES SDL2)
 set(SDL_REQUIRED_LIBRARIES ${SDL_REQUIRED_LIBRARIES} SDL2main)
 add_definitions(-D_WIN32)
 set(ARCH_TARGET win${PLATFORM})
 # Binaries path for thirdparties are not generics so we try to guess their suffixes.
 set(WINDOWS_PATH_SUFFIXES win${PLATFORM} Win${PLATFORM} x${PLATFORM})
 if(${PLATFORM} MATCHES 64)
   message(WARNING "SDL x64 runtime binaries not provided on Windows.")
 endif()
 # -----------------------------------------------------------------------------
 ## PATHS ##
 set(THIRDPARTY_DIR C:/openvr-master/samples/thirdparty)
 set(SHARED_SRC_DIR C:/openvr-master/samples/shared)
 if(CMAKE_HOST_UNIX)
   find_file(OPENVRPATHS openvrpaths.vrpath PATHS $ENV{HOME}/.config/openvr "$ENV{HOME}/Library/Application Support/OpenVR/.openvr")
   if(${OPENVRPATHS} MATCHES OPENVRPATHS-NOTFOUND)
     message(FATAL_ERROR "${OPENVRPATHS} Please install SteamVR SDK to continue..")
   endif()
 endif()
 # -----------------------------------------------------------------------------
 ## COMPILER DETECTION ##
 if(   (${CMAKE_CXX_COMPILER_ID} MATCHES "GNU")
    OR (${CMAKE_CXX_COMPILER_ID} MATCHES "Clang"))
   # Better to use the prebuilt GNU preprocessor define __GNUC__,
   # kept for legacy reason with the sample code.
   add_definitions(-DGNUC)
 
   set(CMAKE_CXX_FLAGS         "${CMAKE_CXX_FLAGS} -std=c++11 -include ${SHARED_SRC_DIR}/compat.h")
   set(CMAKE_CXX_FLAGS_DEBUG   "${CMAKE_CXX_FLAGS_DEBUG} -Wall -Wextra -pedantic -g")
   set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O2")
 
   # Handles x86 compilation support on x64 arch.
   if(${PLATFORM} MATCHES 32)
     set(CMAKE_CXX_FLAGS        "${CMAKE_CXX_FLAGS} -m32")
     set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -m32")
   endif()
 elseif(CMAKE_CXX_COMPILER_ID MATCHES "MSVC")
   set(CMAKE_CXX_FLAGS_DEBUG   "${CMAKE_CXX_FLAGS_DEBUG} /W2 /DEBUG")
   set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} /MP /INCREMENTAL:NO")
 else()
   message(FATAL_ERROR "Unsupported compiler '${CMAKE_CXX_COMPILER_ID}'")
 endif()
# -----------------------------------------------------------------------------
## LIBRARIES ##
## OpenGL / GLU
find_package(OpenGL REQUIRED)
 
## GLEW 1.11
if(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
  # On GNU/Linux, glew can be found on the package manager.
  find_package(GLEW 1.11 REQUIRED)
else()
  # Otherwise, use the shipped binaries.
  find_library(GLEW_LIBRARIES
    NAMES
      GLEW
      glew32
    PATHS
      ${THIRDPARTY_DIR}/glew/glew-1.11.0/lib/Release
    PATH_SUFFIXES
      osx32
      ${WINDOWS_PATH_SUFFIXES}
  )
  set(GLEW_INCLUDE_DIR ${THIRDPARTY_DIR}/glew/glew-1.11.0/include)
endif()
 
## SDL 2
## osx32 and linux32 cmake can spot each others' .so and .a files, so keep them apart
if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
  foreach(lib ${SDL_REQUIRED_LIBRARIES})
    find_library(${lib}_LIBRARY
      NAMES
        ${lib}
      PATHS
        ${THIRDPARTY_DIR}/sdl2-2.0.3/bin
      PATH_SUFFIXES
        osx32
    )
    list(APPEND SDL2_LIBRARIES ${${lib}_LIBRARY})
  endforeach()
else()
  foreach(lib ${SDL_REQUIRED_LIBRARIES})
    find_library(${lib}_LIBRARY
      NAMES
        ${lib}
      PATHS
        ${THIRDPARTY_DIR}/sdl2-2.0.3/bin
      PATH_SUFFIXES
        linux${PLATFORM}
        ${WINDOWS_PATH_SUFFIXES}
    )
    list(APPEND SDL2_LIBRARIES ${${lib}_LIBRARY})
  endforeach()
endif()
set(SDL2_INCLUDE_DIR ${THIRDPARTY_DIR}/sdl2-2.0.3/include)
 
## Vulkan
if(NOT (${CMAKE_SYSTEM_NAME} MATCHES "Darwin"))
  find_library(VULKAN_LIBRARY
      NAMES
        vulkan-1
        vulkan
      PATHS
        ${THIRDPARTY_DIR}/vulkan-1.0.49.0/lib
      PATH_SUFFIXES
        linux${PLATFORM}
        ${WINDOWS_PATH_SUFFIXES}
      NO_DEFAULT_PATH
  )
  set(VULKAN_INCLUDE_DIR ${THIRDPARTY_DIR}/vulkan-1.0.49.0/include)
endif()
## OpenVR API path
find_library(OPENVR_LIBRARIES
  NAMES
    openvr_api
  PATHS
    C:/openvr-master/bin
    C:/openvr-master/lib
  PATH_SUFFIXES
    osx32
    linux64
    ${WINDOWS_PATH_SUFFIXES}
  NO_DEFAULT_PATH
  NO_CMAKE_FIND_ROOT_PATH
)
set(OPENVR_INCLUDE_DIR C:/openvr-master/headers)
# -----------------------------------------------------------------------------
## SHARED SOURCES ##
file(GLOB SHARED_SRC_FILES
  ${SHARED_SRC_DIR}/*.cpp
  ${SHARED_SRC_DIR}/*.h
)
 
 
 
if(NOT (${CMAKE_SYSTEM_NAME} MATCHES "Darwin"))
  include_directories(${VULKAN_INCLUDE_DIR})
endif()
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()
if(NOT PLATFORM)
  if(CMAKE_SIZEOF_VOID_P MATCHES 8)
    set(PLATFORM 64)
  else()
    set(PLATFORM 32)
  endif()
endif()
message(STATUS "Compilation set for ${PLATFORM}bits architectures.")
 
set(SDL_REQUIRED_LIBRARIES SDL2)
 
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()
 
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
 
include_directories(
        .
        ${OPENGL_INCLUDE_DIR}
        ${GLEW_INCLUDE_DIR}
        ${SDL2_INCLUDE_DIR}
        ${QT_INCLUDE_DIRS}
        ${OPENVR_INCLUDE_DIR}
        ${geometry_msgs_INCLUDE_DIRS}
        ${rclcpp_INCLUDE_DIRS}
	${sensor_msgs_INCLUDE_DIRS}
)
add_executable(vive
        ${SHARED_SRC_FILES}
        main.cpp
        )
target_link_libraries(vive
        ${OPENGL_LIBRARIES}
        ${GLEW_LIBRARIES}
        ${SDL2_LIBRARIES}
        ${OPENVR_LIBRARIES}
        ${CMAKE_DL_LIBS}
        ${EXTRA_LIBS}
        ${rclcpp_LIBRARIES}
        ${rmw_implementation_LIBRARIES}
        ${geometry_msgs_LIBRARIES}
	${sensor_msgs_LIBRARIES}
        )
ament_target_dependencies(vive rclcpp std_msgs geometry_msgs sensor_msgs)
 
install(TARGETS
  vive
  DESTINATION lib/${PROJECT_NAME}
)
 
ament_package()


You can make a new text file by right clicking in the directory, going to new, then clicking on Text Document.
5. Make the Package.xml file
In this section we will make the Package.xml file which will be used to tell the ros the properties of the package as a whole. Make a txt file and rename it to Package.xml and put in the following code into it.

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
    <name>vivetest</name>
    <version>0.0.3</version>
    <description>vive code test</description>
    <maintainer email="[email protected]">Morgan Quigley</maintainer>
    <license>Apache License 2.0</license>
 
    <buildtool_depend>ament_cmake</buildtool_depend>
 
    <build_depend>rclcpp</build_depend>
    <build_depend>std_msgs</build_depend>
    <build_depend>geometry_msgs</build_depend>
    <build_depend>sensor_msgs</build_depend>
 
    <exec_depend>rclcpp</exec_depend>
    <exec_depend>std_msgs</exec_depend>
    <exec_depend>geometry_msgs</exec_depend>
    <exec_depend>sensor_msgs</exec_depend>
    <export>
        <build_type>ament_cmake</build_type>
    </export>
</package>

Building the OpenVR ROS 2 Package

This section will walk the student through how to build the package using ament build.
Open a visual studio command prompt (apps: vs2015 x64 native tools command prompt) and enter the following commands:


cd C:\dev\ros2


then:


call install\setup.bat


Finally run the build command:


python src\ament\ament_tools\scripts\ament.py build - -only-packages vivetest


Running OpenVR ROS 2 Node

We will be checking that the code is running the way we expect. This can be confirmed by checking what is being published to ROS 2.
1. Open another command prompt and source ROS 2 as shown in the previous section.
2. Run the code using the ROS 2 run command
Go back to the command prompt used in the previous section and run the node.


ros2 run vivetest vive



3. Run the ROS topic command to see check what is being published


call install/setup.bat



ros2 topic echo /hubo/joy



3. Run the code using the ROS 2 run command
Go back to the command prompt used in the previous section and run the node.


ros2 run vivetest vive



4. Check that it is working properly To send commands you need to click on the trackpad in the direction you want to move in for the x and y-direction. Then you can raise or lower the whole controller to give input in the z-direction.
The first three values in the joy button are the x, y, and z input for the left hand, while the next three are for the x, y, and z for the right hand. If there is an input the value should turn to 1 or -1 depending on direction, if no input the value is 0.