ros2를 활용해 플레이스테이션 컨트롤러의 입력을 조종할 수 있도록 하는 프로젝트.

README.md

원본으로부터 특기할만한 변경점#

p9n_example 에서의 변경점#

기존에는 단순히 플레이스테이션 컨트롤러의 입력을 받아 출력하는 역할만 있었으나, 이를 publish 할 수 있는 능력 부여

또한, 동시 키 입력 지원 (기존 코드는 모든 인풋에 대하여 if else 로 switch 하는 방식이었으나 수정된 코드는 이를 개별로 처리하고 publish)

이 외에도 CmakeList.txt, package.xml 파일의 스크립트간 의존관계 변경에 따른 수정

또한 이를 통하여 python 상에서 플레이스테이션 컨트롤러의 입력을 처리 할 수 있도록 joy_feed_back_receiver.py 예제 추가

p9n_example 폴더내부의 cpp 코드, include hpp 코드, 모두 수정되었음.

수정 커밋 참고, @1f6b880

PlayStation-JoyInterface-ROS2#

PlayStation Joy Controller Interface Package for ROS2.

Supported controllers#

StatusHardware Name
:heavy_check_mark:DualShock3
:heavy_check_mark:DualShock4
:heavy_check_mark:DualSense

Repository Status#

ROS2 DistroBranchBuild status
galacticgalacticGalactic CI
humblehumbleHumble CI

How to use the interface library#

  1. Initialize controller interface with the specific hardware type.

    // Initialize Interface
    const std::string hw_name = "DualSense";
    const auto hw_type = p9n_interface::getHwType(hw_name);
    ps_interface =
    std::make_unique<p9n_interface::PlayStationInterface>(hw_type);
  2. Set sensor_msg::msg::joy to interface. Then you can access any button state via the interface.

    void Example::onJoyCallback(sensor_msgs::msg::Joy::ConstSharedPtr joy_msg) {
    ps_interface->setJoyMsg(joy_msg);  // set joy message to interface
    
    // When Circle Button Pressed..
    if(ps_interface->pressedCircle()) {
     // You can hook action here
    ...

Buttons and Interface functions.#

TargetTypeFunction NameDescription
AnyboolpressedAny();Return true when pressed
boolpressedSquare();
boolpressedCircle();
boolpressedTriangle();
boolpressedCross();
L1boolpressedL1();
R1boolpressedR1();
R2boolpressedR2();pressedR2Analog() also returns the button status with float
L2boolpressedL2();pressedL2Analog() also returns the button status with float
SelectboolpressedSelect();
StartboolpressedStart();
PSboolpressedPS();
DPad ↑boolpressedDPadUp();pressedDPadY() also returns the button status with float
DPad ↓boolpressedDPadDown();pressedDPadY() also returns the button status with float
DPad ←boolpressedDPadLeft();pressedDPadX() also returns the button status with float
DPad →boolpressedDPadRight();pressedDPadX() also returns the button status with float
DPad ← →floatpressedDPadX();-1.0 : Right, 1.0 : Left
DPad ↑ ↓floatpressedDPadY();-1.0 : Down, 1.0 : Up
Left Stick ← →floattiltedStickLX();-1.0 : Right, 1.0 : Left
Left Stick ↑ ↓floattiltedStickLY();-1.0 : Down, 1.0 : Up
Left StickboolisTiltedL();Return true when L stick is tilted
Right Stick ← →floattiltedStickRX();-1.0 : Right, 1.0 : Left
Right Stick ↑ ↓floattiltedStickRY();-1.0 : Down, 1.0 : Up
Right StickbooltiltedStickRY();Return true when R stick is tiled
R2floatpressedR2Analog();-1.0 : Pressed, 1.0 : Not pressed
L2floatpressedL2Analog();-1.0 : Pressed, 1.0 : Not pressed

Convert from Left Joy Stick to cmd_vel#

teleop_twist_joy_node has cmd_vel publisher.
Velocity is decided as below.
Image

Acknowledgements#

We acknowledge attribute and gratitude to the following resources in creating this package.