- IM1R_ROS_Driver
The project aims to develop and maintain ROS drivers suitable for IM1R-FB-U, a compact 6-axis inertial measurement module designed by DAISCH.
- Ubuntu 18.04 / ROS Melodic
- Ubuntu 20.04 / ROS Noetic
-
Install ROS: Please refer to the ROS installation guide for detailed instructions.
-
Install Dependencies:
Run the following commands to install dependencies based on your system's Python version:
-
For Ubuntu 18.04 / Python 2:
sudo apt update sudo apt install python-pip pip install pyserial
-
For Ubuntu 20.04 / Python 3:
sudo apt update sudo apt install python3-pip pip3 install pyserial
-
-
Create catkin workspace:
mkdir -p ~/catkin_ws/src
-
Clone the project repository to the src directory of your catkin workspace:
cd ~/catkin_ws/src git clone https://github.com/DAISCHSensor/IM1R_ROS_Driver.git
- For Ubuntu 20.04 / Python 3, switch to the appropriate branch:
cd IM1R_ROS_Driver git checkout ubuntu20.04-support
- For Ubuntu 20.04 / Python 3, switch to the appropriate branch:
-
Build the driver:
cd ~/catkin_ws/ catkin_make
-
Update the
.bashrc
file:echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc source ~/.bashrc
-
Connect IM1R via UART1 data cable.
-
Start the ROS master:
roscore
-
Identify the serial port for the IM1R device:
dmesg | grep tty
-
Set the serial port permissions: Assuming the IM1R device is connected to /dev/ttyUSB0:
sudo chmod 666 /dev/ttyUSB0
-
Launch the driver node:
rosrun im1r_ros_driver daisch_im1r_node.py /dev/ttyUSB0 115200
/dev/ttyUSB0
is the serial port.115200
is the baud rate used by IM1R, adjust it as needed.
-
List all the topic:
rostopic list
-
echo the specific topic:
rostopic echo imu/data
-
(Example Program) Subscribe to a topic:
rosrun im1r_ros_driver subscriber_example.py
imu/data
(sensor_msgs/Imu) quaternion, angular velocity and linear accelerationtemperature
(sensor_msgs/Temperature) temperature from deviceim1r/extra
(DAISCH Custom Topic) extra params from IM1R
Variable | Supported |
---|---|
time header.stamp |
✔️ |
string header.frame_id |
✔️ |
float64 orientation.x |
✔️ |
float64 orientation.y |
✔️ |
float64 orientation.z |
✔️ |
float64 orientation.w |
✔️ |
float64[9] orientation_covariance |
✘ |
float64 angular_velocity.x |
✔️ |
float64 angular_velocity.y |
✔️ |
float64 angular_velocity.z |
✔️ |
float64[9] angular_velocity_covariance |
✘ |
float64 linear_acceleration.x |
✔️ |
float64 linear_acceleration.y |
✔️ |
float64 linear_acceleration.z |
✔️ |
float64[9] linear_acceleration_covariance |
✘ |
Variable | Supported |
---|---|
time header.stamp |
✔️ |
string header.frame_id |
✔️ |
float64 temperature |
✔️ |
float64 variance |
✘ |
Variable | Type | Definition | Unit | Remarks |
---|---|---|---|---|
count |
uint8 | Message counter | - | 0~255 cyclic increment |
timestamp |
uint64 | Timestamp of the measurement | microseconds (µs) | UNIX time |
pitch |
float64 | Pitch angle | degrees (°) | |
roll |
float64 | Roll angle | degrees (°) | |
yaw |
float64 | Yaw angle | degrees (°) | |
imu_status |
uint8 | IMU status indicator | - | Bit 0: Acceleration valid (0) / invalid (1) Bit 2: Angular velocity valid (0) / invalid (1) Higher bits are not defined |
gyro_bias_x |
float64 | Gyroscope bias along the X axis | radians/second (rad/s) | |
gyro_bias_y |
float64 | Gyroscope bias along the Y axis | radians/second (rad/s) | |
gyro_bias_z |
float64 | Gyroscope bias along the Z axis | radians/second (rad/s) | |
gyro_static_bias_x |
float64 | Static gyroscope bias along the X axis | radians/second (rad/s) | |
gyro_static_bias_y |
float64 | Static gyroscope bias along the Y axis | radians/second (rad/s) | |
gyro_static_bias_z |
float64 | Static gyroscope bias along the Z axis | radians/second (rad/s) |
-
Connect IM1R via UART2 debug cable.
-
Start the ROS core service:
roscore
-
Identify the serial port of the IM1R device:
dmesg | grep tty
-
Set serial port permissions: Assuming the IM1R device is connected to /dev/ttyUSB0:
sudo chmod 666 /dev/ttyUSB0
-
Start the configuration tool:
rosrun im1r_ros_driver daisch_im1r_config.py /dev/ttyUSB0
- Ensure the serial port connected to IM1R is set to port 2, with a fixed baud rate of 115200.
-
After a successful start, the main interface will display the following content:
-
If the serial port connection fails, you will see the information in the image below. Please check if the device is correctly connected and reconfigure the serial port permissions.
Here are the steps to change the output frequency as an example:
-
Enter
2
in the main interface and press Enter to enter the submenu: -
Select the desired output frequency from the submenu. After the configuration is successful, the tool will automatically return to the main menu. For example, after setting the output frequency to 50Hz, you can see the setting has been successfully changed in the main menu:
-
The output frequency should match the baud rate. Mismatched baud rates and output frequencies can result in erroneous messages being received.
Baud Rate Maximum Output Frequency 115200 100Hz 230400 250Hz 460800 500Hz 921600 1000Hz
Symptom: Running rosrun im1r_ros_driver subscriber_example.py
results in the following error:
[rosrun] Couldn't find executable named subscriber_example.py below /home/daisch/catkin_ws/src/im1r_ros_driver
[rosrun] Found the following, but they're either not files,
[rosrun] or not executable:
[rosrun] /home/daisch/catkin_ws/src/im1r_ros_driver/scripts/subscriber_example.py
Solution: Grant executable permissions to the script:
chmod +x /home/daisch/catkin_ws/src/im1r_ros_driver/scripts/subscriber_example.py
If you have any other questions or need further assistance, feel free to ask.