Software Guide
Galaxea B1 Software Guide
Software Dependency
- Ubuntu 20.04 LTS
- ROS Noetic
Installation
The SDK does not require recompilation. Please refer to the contents below.
CAN Connection Tutorial
Important: To ensure the USB-to-CAN Adapter works properly on Linux, please install the driver file that matches your system’s kernel version; otherwise, it may cause errors.
1. Launch the Driver
Use the following command to check the current kernel version:
name -r
The driver file name usually includes the version information. If you need drivers for other kernel versions, please contact us for assistance.
Driver File |
---|
5.15.0-67-generic: 5.15.0_67.ko |
5.15.0-101-generic: 5.15.0_101.ko |
5.15.0-102-generic: 5.15.0_102.ko |
Use the following command to load the kernel module:
sudo insmod /usr/lib/modules/$(uname -r)/kernel/drivers/net/can/dev/can-dev.ko
sudo insmod 5.15.0_101.ko
2. Set 1M Baud Rate
Use the following command to set the CAN interface baud rate to 1 Mbps:
sudo ip link set can0 type can bitrate 1000000
3. Open the CAN Interface
Use the following command to bring up the CAN interface:
sudo ip link set up can0
If no errors occurred in the previous steps, use the following commands to check the CAN interface's configuration and status:
sudo apt-get install net-tools
ifconfig can0
4. Install Driver Dependencies
Use the following command to install the necessary dependencies for the driver:
sudo apt-get install ros-noetic-socketcan-interface ros-noetic-can-msgs
5. Install and Use can_utils
Use the following commands to install the tool and monitor data from Galaxea B1 in real-time, provided that:
- B1 is already running, and
- The CAN-to-USB Adapter is properly connected.
- Make sure to switch the joystick controller SWB to the bottom and SWC to the middle. Otherwise,
candump can0
cwill be unable to access the CAN data, and the upper computer will not be able to control the chassis.
sudo apt-get install can_utils
candump can0
First Move
Launch the Chassis Node
source install/setup.bash
roslaunch signal_chassis r1.launch
Control the Chassis
rostopic pub /control_command signal_chassis/ControlCommand "header:
seq: 0
stamp: {secs: 0, nsecs: 0}
frame_id: ''
motion_mode: 0
x: 0.5
y: 0.0
w: 0.0"
Software Interface
Driver Interface
This interface is used for the chassis status feedback ROS package. The package defines multiple topics for posting the status of multiple motors in the chassis. The following are detailed descriptions of each topic and its related message types:
Topic Name | Description | Message Type |
---|---|---|
/hdas/motor_state | Chassis motion state feedback | chassis_msg/DrivetrainStamped |
Topic Name | Field | Description |
---|---|---|
/hdas/motor_state | .steering_angle_fl | Front-wheel left-wheel steering angle degrees |
.steering_angle_fr | Front-wheel right-wheel steering angle degrees | |
.steering_angle_rl | Rear-wheel left-wheel steering angle degrees | |
.steering_angle_rr | Rear-wheel right-wheel steering angle degrees | |
.drive_speed_fl | Front-wheel left-wheel linear speed m/s | |
.drive_speed_fr | Front-wheel right-wheel linear speed m/s | |
.drive_speed_rl | Rear-wheel left-wheel linear speed m/s | |
.drive_speed_rr | Rear-wheel right-wheel linear speed m/s | |
.drive_angular_speed_fl | Front-wheel left-wheel angular speed rad/s | |
.drive_angular_speed_fr | Front-wheel right-wheel angular speed rad/s | |
.drive_angular_speed_rl | Rear-wheel left-wheel angular speed rad/s | |
.drive_angular_speed_rr | Rear-wheel right-wheel angular speed rad/s | |
.motion_mode | 0: Dual Ackerman Mode 1: Parallel Mode : Spinning Mode |
Control Interface
The chassis control interface can be used to command the chassis to move at the target speed, which includes the combination of X, Y, and Yaw Rate:
Topic Name | Description | Message Type |
---|---|---|
/control_command | Issuing the chassis control signal | signal_chassis/ControlCommand.msg |
Topic Name | Field | Description |
---|---|---|
/control_command | header | Standard ROS header |
.motion_mode | 0: Dual Ackerman Mode 1: Transition Mode 2: Spinning Mode 3: Vector Control Mode 4: Breaking Mode |
|
.x | Not used for Mode 2 & Mode 4; Mode 0: Linear speed of x in the range of (-1, 1) m/s Mode 1: Linear speed of x-direction in the range of (-1, 1) m/s Mode 3: Linear speed of x-direction in the range of (-1, 1) m/s |
|
.y | Not used for Mode 0 & Mode 2 & Mode 4 Mode 1: Linear speed of y-direction in the range of (-1, 1) m/s Mode 3: Linear speed of y-direction in the range of (-1, 1) m/s |
|
.w | Not used for Mode 1 & Mode 4; Motion Mode 0: (-45°, 45°) Motion Mode 2: angular speed in the range of (-3.7, 3.7) rad/s Motion Mode 3: angular speed in the range of (-3.7, 3.7) rad/s |