# D455 and IMU configuration
## GNSS Configuration
**Selecting ucenter_config_f9p_gvins.txt, download and import to GNSS.**



**Make sure you can output message from UBX-RXM-RAWX,UBX-RXM-SFRBX, UBX-NAV-PVT**


**Dont forget to save config**

**Config output frequence and baudrate finally.**

**I setup with freq: 60ms, baudrate: 921600**
## GVINS Configuration
you can create new instance(.yaml) and put below content in here:
```bash!
[ROS_WS]/src/GVINS/config/[YOUR_CONFIG].yaml
```
```yaml!
%YAML:1.0
#common parameters
imu_topic: "/camera/imu"
image_topic: "/camera/color/image_raw"
output_dir: "/home/ubuntu/output/"
#camera calibration
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
# mirror_parameters:
# xi: 1.8476540167437447
distortion_parameters:
k1: -5.58381e-02
k2: 6.70407e-02
p1: -2.42111e-04
p2: -2.12417e-02
projection_parameters:
fx: 3.7958282470703125e+02
fy: 3.793941955566406e+02
cx: 3.1927392578125e+02
cy: 2.471514129638672e+02
# gamma1: 385.5973815917969
# gamma2: 385.11065673828125
# u0: 324.7513122558594
# v0: 240.29359436035156
gnss_enable: 1
gnss_meas_topic: "/ublox_driver/range_meas" # GNSS raw measurement topic
gnss_ephem_topic: "/ublox_driver/ephem" # GPS, Galileo, BeiDou ephemeris
gnss_glo_ephem_topic: "/ublox_driver/glo_ephem" # GLONASS ephemeris
gnss_iono_params_topic: "/ublox_driver/iono_params" # GNSS broadcast ionospheric parameters
gnss_tp_info_topic: "/ublox_driver/time_pulse_info" # PPS time info
gnss_elevation_thres: 30 # satellite elevation threshold (degree)
gnss_psr_std_thres: 2.0 # pseudo-range std threshold
gnss_dopp_std_thres: 2.0 # doppler std threshold
gnss_track_num_thres: 15 # number of satellite tracking epochs before entering estimator
gnss_ddt_sigma: 0.1
gnss_local_online_sync: 0 # if perform online synchronization betwen GNSS and local time
local_trigger_info_topic: "/external_trigger" # external trigger info of the local sensor, if `gnss_local_online_sync` is 1
gnss_local_time_diff: 17.9 # difference between GNSS and local time (s), if `gnss_local_online_sync` is 0
gnss_iono_default_parameters: !!opencv-matrix
rows: 1
cols: 8
dt: d
data: [0.1118E-07, 0.2235E-07, -0.4172E-06, 0.6557E-06,
0.1249E+06, -0.4424E+06, 0.1507E+07, -0.2621E+06]
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999998, 0.000727753, -0.0018542,
-0.000731598, 0.999998, -0.00207414,
0.00185269, 0.00207549, 0.999996]
#Translation from camera frame to imu frame, imu^T_cam
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [-0.0591689, -6.45117e-05, 0.000440176]
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 25 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 0 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 1.3070468303711670e-02 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 1.8698887111278477e-03 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 3.6264256290488833e-04 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 3.3803458569191471e-05 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.794 # gravity magnitude
#unsynchronization parameters
estimate_td: 1 # online estimate time offset between camera and imu
td: 0.00732677665793 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
```
## Executing command
Open 4 terminal and type:
* start gvins
```bash
roslaunch gvins [YOUR_LAUNCHER].launch
```
* ros launch cmd of camera and imu
```bash
roslaunch realsense2_camera rs_camera.launch enable_gyro:=true enable_accel:=true unite_imu_method:=linear_interpolation enable_sync:=true color_width:=640 color_height:=480 enable_depth:=false enable_color:=true color_fps:=60
```
* ros launch cmd of ZED-F9P
```bash
roslaunch ublox_driver ublox_driver.launch
```
* Run rviz
```bash
rviz -d ~/catkin_ws/src/GVINS/config/gvins_rviz_config.rviz
```