Only released in EOL distros:
Package Summary
Released
Documented
Rover Robotics: ROS package for connecting to SwiftNav Piksi
- Maintainer status: developed
- Maintainer: Nick Fragale <nick AT roverrobotics DOT com>
- Author:
- License: BSD
- Source: git https://github.com/roverrobotics/rr_swiftnav_piksi.git (branch: master)
Contents
Installation
This package requires SwiftNav's libsbp python library. Install before installing this package.
Option 1 (Recommended) Install binaries via aptitude package manager
sudo apt install ros-kinetic-rr-swiftnav-piksi
Option 2 Install source from github (only use if you want to make custom changes to the source code)
cd ~/catkin_ws/src/ git clone https://github.com/RoverRobotics/rr_swiftnav_piksi.git cd ~/catkin_ws/ catkin_make source devel/setup.bash
Nodes
swiftnav_piksi_tcp.py
The swiftnav_piksi_tcp_node provides a ROS driver for SwiftNav Piksi's that are connected via ethernet cable. This node will calculate the heading of a robot when moving. In order to get the orientation correct well travelling in reverse, the cmd_vel/managed topic from the rr_control_input_manager node is needed.Subscribed Topics
/swift_nav/enable_comms (std_msgs/Bool)- When set to true the node will start an NCAT processs that will forward IP traffic from base station to the Piksi. Setting this false when idle is a good idea to reduce network traffic.
- Used to calculate heading correctly while moving
Published Topics
/swift_gps/llh/position (sensor_msgs/NavSatFix)- Outputs the current Latitude and Longitude
- Outputs an integer that corresponds to the current fix mode 0: Invalid 1: Single Point Position (SSP) 2: Differential GNSS (DGNSS) 3: Float RTK 4: Fixed RTK 5: Dead Reckoning 6: Satellite-Base Augmentation System(SBAS)
- Outputs the number of satellites currently being used.
- Outputs x, y distance in meters away from the basestation. This is a cm level accurate measurement when fix mode is 'rtk_fix' and should be used as input into a kalman filter (robot_localization is a good package for this). This topic also includes heading information calculated from the last two RTK positions. Heading will only be updated if distance traveled is greater than 4cm in 0.1 seconds, which corresponds with going 0.4m/s.
- Raw IMU values.
Parameters
~piksi_ip_address (string, default: 1.2.3.10)- IP Address of the SwiftNav Piksi
- TCP port of the SwiftNav Piksi
- IP Address or URL of the Base Station
- TCP port of the Base Station
- IP Address of the computer connected to the Piksi
Running
Example using rosrun
rosrun rr_swiftnav_piksi swiftnav_piksi_tcp.py