-
Notifications
You must be signed in to change notification settings - Fork 77
3DM‐CV7‐INS or 3DM‐GV7‐INS with Ublox F9P
This tutorial shows how to set up a 3DM-CV7-INS or 3DM-Gv7-INS to provide a global odometry solution in ROS 2. In this example, we will provide the sensor with GPS data from a SparkFun ZED-F9P.
Tip
The code for this example can be found in the microstrain_ros_examples
package
The 3DM-CV7-INS (or CV7-INS) is an embeddaable tactical grade inertial navigation system with external position and velocity inputs. The sensor hosts an advanced Extended Kalman Filter that can fuse internal sensor data with external aiding data to provide a robust navigation solution.
The 3DM-GV7-INS (or GV7-INS) is a ruggedized version of the CV7-INS containing the exact same sensor fusion capabilities in an IP68 package.
In this example, the CV7-INS will take on the role of providing a global
odometry solution, as well as populating several transforms. This can be
thought of as a replacement to the Integrating GPS
Data
guide provided by robot_localization
.
It is assumed ROS2 and dependent packages are installed or built
locally. Additionally you will have to install the
microstrain_ros_examples
package:
source /opt/ros/<ros2-distro>/setup.bash sudo apt install ros-$ROS_DISTRO-microstrain-ros-examples
The Ublox F9P that we will be using to provide GPS data relies on GNSS for navigation. In order for the system to initialize and successfully navigate, it needs to operate outside with a clear view of the sky.
If you want RTK level precision, you will need to either have a 3DM-RTK, or internet access from your robot and a subscription to an NTRIP network.
For the purposes of this example, we need to define several frames. Many of these are defined in REP 105.
frame_id | description |
---|---|
earth | ECEF frame |
map | Coordinate frame representing a global tangent plane with it's origin at the first valid fix received by the CV7-INS/GV7-INS. |
base_link | Coordinate frame representing the vehicle used for testing |
cv7_ins_link | Coordinate frame representing the CV7-INS/GV7-INS |
ublox_f9p_antenna_link | Coordinate frame representing the center of the antenna connected to the SparkFun F9P |
In this example, we will use the microstrain_inertial_driver
and
robot_description
to create the following transform tree where
<sensor_frame>
is cv7_ins_link
In order for the CV7-INS/GV7-INS to use data provided by the F9P, it needs to know the location of the antenna relative to itself. The easiest and most accurate way to accomplish this is to add the CV7-INS/GV7-INS and the F9P antenna to a robot description file.
For the purposes of this tutorial, we have created a simple "robot" in cv7_ins_ublox_f9p.urdf.xacro which can be seen below
The antenna in this example is mounted 20 centimeters directly to the right of the CV7-INS. If your devices are not mounted like that, you should copy cv7_ins_ublox_f9p.urdf.xacro to a new file called my_robot.urdf.xacro
and make any modifications needed. We will discuss how to use this file in future steps.
The parameters for this demo can be found in cv7_ins_ublox_f9p.yml. Most of the parameters can probably be left alone, but users may want to tweak some. In order to do this, copy the previously mentioned file to a new file called my_params.yml
and make any modifications needed. We will disuss how to use this file in future steps.
Note
The following subsections are entirely optional. If you just want to get things up and running, skip to step 2
The default behavior of the example is to place the origin of the global tangent plane at the location where the CV7-INS/GV7-INS enters full navigation mode.
This may not be desirable for all users. For example, if you wanted to provide waypoints in the global tangent plane and have them be repeatable between runs, you should instead have a constant location for it. To do this, you should modify this section to look something like this:
filter_relative_position_config : True # Tell the driver to setup the local tangent plane
filter_relative_position_source : 1 # The global tangent plane will be placed in a constant location dictated by the parameters below.
filter_relative_position_frame : 2 # This will determine the frame that filter_relative_position_ref is in. (1 - WGS84 ECEF, 2 - WGS84 LLH)
filter_relative_position_ref : [44.4356530949166, -73.10754131943577, 0.01] # This will determine the origin of the global tangent plane. Since filter_relative_position_frame is set to 2, this should be in LLH
The default behavior of this example is to use GNSS kinematic alignment to initialize heading. If you are using a ground vehicle and you can accomplish this, GNSS kinematic alignment is a reliable option for good heading. However, the CV7-INS also supports initializing heading using the magnetometer. To use the magnetometer, you should modify this section to look something like this:
Important
Magnetometer heading can be heavily affected by motors, and large metal parts on vehicles. If you want to use this option, you need to take care when mounting and calibrating the sensor
filter_auto_heading_alignment_selector : 4 # This will configure the device to use magnetometer to initialize heading
With the CV7-INS/GV7-INS and F9P plugged into your computer, change ublox_f9p_port
to the port that the F9P is connected on, and run the following command to start the example.
ros2 launch microstrain_ros_examples cv7_ins_ublox_f9p_launch.py ublox_f9p_port:=/dev/ttyACM1
Once the example is up and running, you will notice that rviz still displays an error assuming that you haven't changed any parameters. This is because the heading has not yet initialized.
In order to initialize heading, drive your vehicle straight forward, and after some time, you should see the following logs
[microstrain_inertial_driver]: Full nav achieved. Relative position will be reported relative to the following position
[microstrain_inertial_driver]: LLH: [44.437295, -73.105477, 131.566168]
[microstrain_inertial_driver]: XYZW: [0.383015, 0.056882, 0.135439, 0.911987]
Once you see those logs, rviz should no longer display an error, and the system should be fully operational
If in step 0, you modified the robot description, add the following parameter to the end of the launch statement
robot_urdf_file:=/path/to/my_robot.urdf.xacro
If in step 1, you modified the parameter file, add the following parameter to the end of the launch statement
params_file:=/path/to/my_params.yml
If you want to provide RTK corrections to the ublox F9P, you have internet access on the robot, and a subscription to a corrections service, you can add the following parameters to the launch command to receive RTK corrections over NTRIP.
ntrip:=true ntrip_host:=my.ntrip.host ntrip_port:=2101 ntrip_mountpoint:=VRS_RTCM3 ntrip_username:=myuser ntrip_password:=mypass