chengkaiqiang 6213262140 v-0.1.1-1:20240806 | 3 ヶ月 前 | |
---|---|---|
.. | ||
docs | 3 ヶ月 前 | |
include | 3 ヶ月 前 | |
launch | 3 ヶ月 前 | |
lib | 3 ヶ月 前 | |
node | 3 ヶ月 前 | |
CMakeLists.txt | 3 ヶ月 前 | |
README.md | 3 ヶ月 前 | |
g30esli_interface.sh | 3 ヶ月 前 |
The controller package for vehicles manufactured by Yamaha Motor Co., Ltd.
Yamaha Golfcar Academic Pack version of G30Es-Li has the By-wire ECU based on CAN communication.
CAN message format is private, so we provide CAN communication and parsing functions as a binary g30esli.a
in ymc package.
This node has two modes and some condition of transition as in this figure. If you press throttle or brake pedal, By-wire mode is forced to transition to Manual Mode (override function).
/vehicle_cmd
topic./ds4
topic.Confirm safety around your vehicle.
Launch Autoware nodes and check to correctly provide /vehicle_cmd
topic.
Connect and setup CAN interface. (NOTE: We generally use PEAK System PCAN-USB)
$ rosrun ymc canset up canX
4-1. Launch g30esli_interface
node.
$ roslaunch ymc g30esli_interface.launch device:=canX
And then your car should move by vehicle_cmd
topic.
4-2. If you want to use DS4 joystick, launch with use_ds4
option and connect your joystick controller.
$ roslaunch ymc g30esli_interface.launch device:=canX use_ds4:=true ds4_wired:=true ## USB
or
$ roslaunch ymc g30esli_interface.launch device:=canX use_ds4:=true ds4_wired:=false ## Bluetooth
And then, your car should move by joystick controller. For controlling by vehicle_cmd
, press PS button.
Button | Description |
---|---|
CROSS | Send speed ( 3 <= v <= 19 [km/h] ), change to JOYSTICK mode |
SQUARE | Smooth brake, change to JOYSTICK mode |
CIRCLE | Semi-emergency brake |
TRIANGLE | Emergency brake |
R1 | Reverse shift |
L1 | Neutral shift |
R2 | Change speed linearly ( v = 16 * R2 + 3 [km/h] ) |
L2 | Change max steering linearly ( theta = (17 * L2 + 20) * ANALOG_L [deg] ) |
ANALOG_L | Steering angle ( -37 <= theta <= +37 [deg] ) |
DIGITAL_UP / LEFT / RIGHT / DOWN | Blinker clear / left / right / hazard |
SHARE | Engage vehicle |
OPTION | Disengage vehicle |
PS | change to AUTO mode |
Please see ds4 package to know installation and details.
Parameter | Type | Description | Default |
---|---|---|---|
engaged |
Bool | Enable Auto Mode at startup | true |
device |
String | CAN interface name | can0 |
steering_offset_deg |
Double | Steering offset [deg] | 0.0 |
command_timeout |
Int | vehicle_cmd timeout [ms] |
1000 |
use_ds4 |
Bool | Enable DS4 joystick and start in joystick mode | false |
ds4_wired |
Bool | Select DS4 connection (true = USB, false = Bluetooth) | false |
ds4_timeout |
Int | Bluetooth timeout in ds4_driver [ms] |
1000 |
Node [/g30esli_interface]
Publications:
* /vehicle/battery [std_msgs/Float32]
* /vehicle/twist [geometry_msgs/TwistStamped]
* /vehicle_status [autoware_msgs/VehicleStatus]
Subscriptions:
* /vehicle/engage [std_msgs/Bool]
* /vehicle_cmd [autoware_msgs/VehicleCmd]