All you need to do is define the frame of the IMU relative to the base_link with the correct rotation and orientation.
If the IMU would already be using the REP-103 coordinate system the very basic urdf would look something like this:
<?xml version='1.0'?>
<robot name="basic" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="base_link">
<pose>0 0 0 0 0 0</pose>
</link>
<link name="imu"/>
<joint name="imu_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.3"/>
<parent link="base_link" />
<child link="imu"/>
</joint>
</robot>
Would produce the output as (red=x, green=y, blue=z):
In the linked repository the orientation of the IMU is depicted as Z down and Y to the "right". You need to take that orientation into account in the definition of your frames. To do that you need to rotate it around the X axis.
The rotation is in radians so rotate it by PI for 180 degrees. <origin rpy="3.1416 0 0" xyz="0 0 0.3"/>
The basic robot would look like this:
<?xml version='1.0'?>
<robot name="basic" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="base_link">
<pose>0 0 0 0 0 0</pose>
</link>
<link name="imu"/>
<joint name="imu_joint" type="fixed">
<origin rpy="3.1416 0 0" xyz="0 0 0.3"/>
<parent link="base_link" />
<child link="imu"/>
</joint>
</robot>
Output and the image in the linked git repo:
To easily inspect your urdf you might want to install the package urdf_tutorial.
replace <ros_distro>
with your distribution
sudo apt install ros-<ros_distro>-urdf-tutorial
for kinetic:
sudo apt install ros-kinetic-urdf-tutorial
Then assuming you saved the above robot description as basic.xacro
you could just run:
cd /path/to/saved/xacro
roslaunch urdf_tutorial display.launch model:=basic.xacro
To verify that everything seems to be working normally you could install some plugins to visualize the IMU output in rviz. One example would be rviz_imu_plugin. Have not used that plugin in a long time, you would probably need to have your URDF "running" and change the fixed_frame to base_link in Rviz to get sensible output.