
ros2를 활용해 플레이스테이션 컨트롤러의 입력을 조종할 수 있도록 하는 프로젝트.
원본으로부터 특기할만한 변경점#
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#
Status | Hardware Name |
---|---|
:heavy_check_mark: | DualShock3 |
:heavy_check_mark: | DualShock4 |
:heavy_check_mark: | DualSense |
Repository Status#
ROS2 Distro | Branch | Build status |
---|---|---|
galactic | galactic | |
humble | humble |
How to use the interface library#
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);
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.#
Target | Type | Function Name | Description |
---|---|---|---|
Any | bool | pressedAny(); | Return true when pressed |
□ | bool | pressedSquare(); | |
○ | bool | pressedCircle(); | |
□ | bool | pressedTriangle(); | |
☓ | bool | pressedCross(); | |
L1 | bool | pressedL1(); | |
R1 | bool | pressedR1(); | |
R2 | bool | pressedR2(); | pressedR2Analog() also returns the button status with float |
L2 | bool | pressedL2(); | pressedL2Analog() also returns the button status with float |
Select | bool | pressedSelect(); | |
Start | bool | pressedStart(); | |
PS | bool | pressedPS(); | |
DPad ↑ | bool | pressedDPadUp(); | pressedDPadY() also returns the button status with float |
DPad ↓ | bool | pressedDPadDown(); | pressedDPadY() also returns the button status with float |
DPad ← | bool | pressedDPadLeft(); | pressedDPadX() also returns the button status with float |
DPad → | bool | pressedDPadRight(); | pressedDPadX() also returns the button status with float |
DPad ← → | float | pressedDPadX(); | -1.0 : Right, 1.0 : Left |
DPad ↑ ↓ | float | pressedDPadY(); | -1.0 : Down, 1.0 : Up |
Left Stick ← → | float | tiltedStickLX(); | -1.0 : Right, 1.0 : Left |
Left Stick ↑ ↓ | float | tiltedStickLY(); | -1.0 : Down, 1.0 : Up |
Left Stick | bool | isTiltedL(); | Return true when L stick is tilted |
Right Stick ← → | float | tiltedStickRX(); | -1.0 : Right, 1.0 : Left |
Right Stick ↑ ↓ | float | tiltedStickRY(); | -1.0 : Down, 1.0 : Up |
Right Stick | bool | tiltedStickRY(); | Return true when R stick is tiled |
R2 | float | pressedR2Analog(); | -1.0 : Pressed, 1.0 : Not pressed |
L2 | float | pressedL2Analog(); | -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.
Acknowledgements#
We acknowledge attribute and gratitude to the following resources in creating this package.
- ps_ros2_common by @Ar-Ray-code