A ROS wrapper for the InertialSense uINS3 RTK-GPS-INS and Dual GPS (GPS Compassing) sensor.
To use this node, you will need to update firmware on your uINS to v1.7.3 release page. Download the appropriate .hex
file and use the firmware_update
ROS service to update the firmware
rosservice call /firmware_update /home/superjax/Download/IS_uINS-3_v1.7.3<...>.hex
This is a ROS package, with the InertialSenseSDK as a submodule, so just create a catkin workspace, clone this into the src
folder, pull down the submodule and build
mkdir -p catkin_ws/src
cd catkin_ws/src
catkin_init_workspace
git clone https://inertialsense/inertial_sense_ros
cd inertial_sense
git submodule update --init --recursive
cd ../..
catkin_make
rosrun inertial_sense inertial_sense_node
Make sure that you are a member of the dailout
group, or you won't have access to the serial port.
For changing parameter values and topic remapping from the command line using rosrun
refer to the Remapping Arguments page. For setting vector parameters, use the following syntax:
rosparam set /inertial_sense_node/GPS_ref_lla "[40.25, -111.67, 1556.59]"
rosrun inertial_sense inertial_sense_node
For setting parameters and topic remappings from a launch file, refer to the Roslaunch for Larger Projects page, or the sample launch/test.launch
file in this repository.
RTK (Realtime Kinematic) GPS requires two gps receivers, a base and a rover. The GPS observations from the base GPS are sent to the rover and the rover is able to calculate a much more accurate (+/- 3cm) relative position to the base. This requires a surveyed base position and a relatively high-bandwidth connection to the rover. If using a uINS with two GPS receviers, GPS 1 is used for base corrections. The RTK functionality in this node is performed by setting parameters shown below.
It is important that the base position be accurate. There are two primary methods for getting a surveyed base position.
Once the base position has been identified, set the refLLA
of the base uINS to your surveyed position to indicate a surveyed base position.
GPS Compassing is supported on units with two GPS receivers. It also requires a very precise measurement of the locations of both GPS antennas relative to the uINS (+/- 1cm). If you want to use the Dual GNSS mode, you must set the dual_GNSS
parameter, and specify both the GPS_ant1_xyz
and GPS_ant2_xyz
vector parameters.
Dual GNSS uses the onboard RTK engine, so it is currently impossible for a uINS to be configured as both an RTK rover and for dual GNSS compassing simultaneously. It is possible to provide base corrections while also acting in dual GNSS mode.
If GPS is available, all header timestamps are calculated with respect to the GPS clock but are translated into UNIX time to be consistent with the other topics in a ROS network. If GPS is unvailable, then a constant offset between uINS time and system time is estimated during operation and is applied to IMU and INS message timestamps as they arrive. There is often a small drift in these timestamps (on the order of a microsecond per second), due to variance in measurement streams and difference between uINS and system clocks, however this is more accurate than stamping the measurements with ROS time as they arrive.
In an ideal setting, there should be no jump in timestamps when GPS is first acquired, because the timestamps should be identical, however, due to inaccuracies in system time, there will likely be a small jump in message timestamps after the first GPS fix.
Topics are enabled and disabled using parameters. By default, only the ins
topic is published to save processor time in serializing unecessary messages.
ins
(nav_msgs/Odometry)
imu
(sensor_msgs/Imu)
gps
(inertial_sense/GPS)
gps/info
(inertial_sense/GPSInfo)
mag
(sensor_msgs/MagneticField)
baro
(sensor_msgs/FluidPressure)
preint_imu
(inertial_sense/DThetaVel)
RTK/info
(inertial_sense/RTKInfo)
RTK/rel
(inertial_sense/RTKRel)
gps/obs
(inertial_sense/GNSSObservation)
gps/eph
(inertial_sense/GNSSEphemeris)
gps/geph
~port
(string, default: "/dev/ttyUSB0")
~baudrate
(int, default: 921600)
~frame_id
(string, default "body")
Topic Configuration
~navigation_dt_ms
(int, default: Value retrieved from device flash configuration)
~stream_INS
(bool, default: true)
~stream_IMU
(bool, default: false)
~stream_baro
(bool, default: false)
~stream_mag
(bool, default: false)
~stream_preint_IMU
(bool, default: false)
~stream_GPS
(bool, default: false)
~stream_GPS_info
(bool, default: false)
stream_GPS_raw
(bool, default: false)
RTK Configuration
~RTK_rover
(bool, default: false)
~RTK_base
(bool, default: false)
~dual_GNSS
(bool, default: false)
~RTK_server_IP
(string, default: 127.0.0.1)
~RTK_server_port
(int, default: 7777)
~RTK_correction_type
(string, default: UBLOX)
Sensor Configuration
~INS_rpy
(vector(3), default: {0, 0, 0})
~INS_xyz
(vector(3), default: {0, 0, 0})
~GPS_ant1_xyz
(vector(3), default: {0, 0, 0})
~GPS_ant2_xyz
(vector(3), default: {0, 0, 0})
~GPS_ref_lla
(vector(3), default: {0, 0, 0})
set_refLLA
service to update this automatically)~inclination
(float, default: 1.14878541071)
~declination
(float, default: 0.20007290992)
~dynamic_model
(int, default: 8)
ASCII Output Configuration
~ser1_baud_rate
(int, default: 921600)
~NMEA_rate
(int, default: 0)
~NMEA_configuration
(int, default: 0x00)
~NMEA_ports
(int, default: 0x00)
single_axis_mag_cal
(std_srvs/Trigger)
multi_axis_mag_cal
(std_srvs/Trigger)
firmware_update
(inertial_sense/FirmwareUpdate)
.hex
file supplied (use absolute filenames)set_refLLA_current
(std_srvs/Trigger)
refLLA
. Use this to set a base position after a survey, or to zero out the ins
topic.1set_refLLA_value
(std_srvs/Trigger)
refLLA
to the values passed as service arguments of type float64[3]. Use this to set refLLA to a known value.