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_ros1_driver.git
- For Ubuntu 20.04 / Python 3, switch to the appropriate branch:
cd im1r_ros1_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
.bashrcfile: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:
- Verify the serial port used by IM1R, e.g.
/dev/ttyUSB0 - Verify the baud rate used by IM1R, e.g.
115200
rosrun im1r_ros_driver daisch_im1r_node.py /dev/ttyUSB0 115200
- Verify the serial port used by IM1R, e.g.
-
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) |
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.pySolution: Grant executable permissions to the script:
chmod +x /home/daisch/catkin_ws/src/im1r_ros_driver/scripts/subscriber_example.pyIf you have any other questions or need further assistance, feel free to ask.
