Skip to main content
Version: ROS 2 Jazzy

Inertial Navigation Systems

Inertial Navigation Systems (INS) compute and provide position, orientation and velocity data. They can be augmented with GNSS and/or visual data for more precise outputs.

INS may publish a variety of data, including sensor_msgs/msg/Imu, sensor_msgs/msg/NavSatFix, and nav_msgs/msg/Odometry types.

Fixposition Vision-RTK 2

ins:
- model: fixposition
urdf_enabled: true
launch_enabled: true
parent: default_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ip: 192.168.131.35
port: "21001"
antennas:
- type: spherical
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
- type: spherical
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
fixposition_driver:
fp_output:
formats:
- ODOMETRY
- LLH
- RAWIMU
- CORRIMU
rate: 200
type: tcp
reconnect: 5
customer_input:
speed_topic: "xvn/speed"
rtcm_topic: "xvn/rtcm"

Package and Setup

The Fixposition Vision-RTK2 (formerly Fixposition XVN) uses the fixposition_driver_ros2 ROS 2 driver, maintained by Fixposition. The driver is open-source and hosted on GitHub.

The ROS 2 driver must be built from source, following these instructions.

For specifics on the way Clearpath's configuration system launches the fixposition_driver_ros2, see the Fixposition launch file and the default parameter file in clearpath_sensors.

Antenna configuration

The Fixposition Vision-RTK2 requires two GNSS antennas. The position and type of each antenna is defined in the antennas array. Each antenna instance may contain the following attributes:

  • type: the shape of the antenna: spherical (default), helical, or patch
  • parent: the parent link of the antenna in the URDF. default_mount if unspecified
  • xyz: the XYZ offset from the parent link to the antenna's mounting point
  • rpy: the RPY offset relative to the parent link