Contents
Package Summary
Maintainer status: maintained
Maintainer: Rocwang <825213566@qq.com>
Download: https://github.com/yowlings/wit_node.git
Author: Rocwang
License: BSD
This is the ROS nodelet package for wit motion company imu and gps sensor. Providing driver, ros driver and nodelet intergrating program.The wit motion 9-axies IMU and GPS module provides abundant types of data for user, including nine axises data, atmosphere pressure, temperature, latitude,longitude, altitude, satellites number .etc
Usage
Launch the only ROS launch file:
roslaunch wit_node wit.launch
Dependencies and Install
1. ROS
2. ros-<distro>-ecl
Install ecl by
sudo apt install ros-<distro>-ecl
Nodes
wit
The wit ros node for getting IMU&GPS module data and publishing related topics.Subscribed Topics
~<name>/reset_offset (std_msgs/Empty)- Reset the offset yaw angle to current yaw, so the zero direction is turned to current direction.
Published Topics
~<name>/raw_data (wit_node/ImuGpsRaw)- All raw data provided by the wit device, including nine axises data, atmosphere pressure, temperature, latitude,longitude, altitude, satellites number .etc
- The standard ROS imu sensor msg which include orientation by filtered RPY.
- The standard ROS gps or navigation satellites msg.
- The offseted imu yaw data, which means the zero direction is start direction.
Parameters
~port (string, default: /dev/ttyUSB0)- the device port name.