forked from ros-drivers/microstrain_mips
-
Notifications
You must be signed in to change notification settings - Fork 78
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
ROS Adds example of providing NMEA over CV7-INS aux port (#351)
* Adds ROS CV7-INS NMEA aux port example * Adds example files to README
- Loading branch information
1 parent
48b4747
commit f0a6659
Showing
4 changed files
with
338 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
61 changes: 61 additions & 0 deletions
61
microstrain_inertial_examples/config/cv7_ins_nmea_aux/cv7_ins.yml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,61 @@ | ||
# You should change this section of config to match your setup | ||
port : '/dev/microstrain_main' | ||
baudrate : 115200 | ||
set_baud : True | ||
|
||
# This will cause the node to convert any NED measurements to ENU | ||
# This will also cause the node to convert any vehicle frame measurements to the ROS definition of a vehicle frame | ||
use_enu_frame : True | ||
|
||
# Configure some frame IDs | ||
frame_id : 'cv7_ins_link' # Frame ID of all of the filter messages. Represents the location of the CV7-INS in the tf tree | ||
map_frame_id : "map" # Frame ID of the local tangent plane. | ||
earth_frame_id : "earth" # Frame ID of the global frame | ||
target_frame_id : "base_link" # Frame ID that we will publish a transform to. | ||
|
||
# Disable the transform from the mount to frame id transform as it will be handled in the launch file | ||
publish_mount_to_frame_id_transform : False | ||
|
||
# We will use relative transform mode, meaning that we will publish the following transforms from this node | ||
# earth_frame_id -> map_frame_id | ||
# map_frame_id -> target_frame_id | ||
# This helps ROS standard tools consume and display position information produced by the device | ||
tf_mode: 2 | ||
|
||
# We will use auto relative position configuration for this example. This configuration does a couple things: | ||
# We will setup a local tangent plane at the first location we receive after the device enters full navigation mode | ||
# We will publish this location as the transform from the earth_frame_id to map_frame_id frame | ||
filter_relative_position_config : True | ||
filter_relative_position_source : 2 | ||
|
||
# Set the antenna offset. | ||
# Note: This should be changed for you setup, otherwise you will experience poor filter performance | ||
gnss1_antenna_offset : [0.0, -0.7, -1.0] | ||
|
||
# This will set the initial heading alignment to use GNSS Kinematic Alignment | ||
# Note that if you have any form of external heading, it is probably better to set this to 8 in order to use that | ||
filter_auto_heading_alignment_selector : 2 | ||
|
||
# Setup some aiding options. | ||
filter_enable_gnss_pos_vel_aiding : True | ||
filter_enable_gnss_heading_aiding : False | ||
|
||
# This example uses the PPS from the F9P connected to this device via GPIO | ||
filter_pps_source : 3 | ||
|
||
# Change this baudrate to whatever baudrate the F9P is configured to communicate at | ||
aux_baudrate : 115200 | ||
|
||
# Configure the GPIO pins | ||
gpio_config : True | ||
|
||
# GPIO 1 (pin 7) will be the pin where we receive NMEA | ||
gpio1_feature : 5 # UART feature | ||
gpio1_behavior : 0x22 # UART Port 2 RX behavior | ||
|
||
# GPIO 3 (pin 6) will be the pin where we receive PPS | ||
gpio3_feature : 2 # PPS feature | ||
gpio3_behavior : 1 # Input behavior (PPS is being input to the device) | ||
|
||
# Disable the filter declination source. This is required to get the node to start, and isn't doing anything special | ||
filter_declination_source : 1 |
222 changes: 222 additions & 0 deletions
222
microstrain_inertial_examples/config/cv7_ins_nmea_aux/display.rviz
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,222 @@ | ||
Panels: | ||
- Class: rviz/Displays | ||
Help Height: 78 | ||
Name: Displays | ||
Property Tree Widget: | ||
Expanded: | ||
- /Global Options1 | ||
- /Status1 | ||
Splitter Ratio: 0.5 | ||
Tree Height: 555 | ||
- Class: rviz/Selection | ||
Name: Selection | ||
- Class: rviz/Tool Properties | ||
Expanded: | ||
- /2D Pose Estimate1 | ||
- /2D Nav Goal1 | ||
- /Publish Point1 | ||
Name: Tool Properties | ||
Splitter Ratio: 0.5886790156364441 | ||
- Class: rviz/Views | ||
Expanded: | ||
- /Current View1 | ||
Name: Views | ||
Splitter Ratio: 0.5 | ||
- Class: rviz/Time | ||
Name: Time | ||
SyncMode: 0 | ||
SyncSource: "" | ||
Preferences: | ||
PromptSaveOnExit: true | ||
Toolbars: | ||
toolButtonStyle: 2 | ||
Visualization Manager: | ||
Class: "" | ||
Displays: | ||
- Alpha: 0.5 | ||
Cell Size: 1 | ||
Class: rviz/Grid | ||
Color: 160; 160; 164 | ||
Enabled: true | ||
Line Style: | ||
Line Width: 0.029999999329447746 | ||
Value: Lines | ||
Name: Grid | ||
Normal Cell Count: 0 | ||
Offset: | ||
X: 0 | ||
Y: 0 | ||
Z: 0 | ||
Plane: XY | ||
Plane Cell Count: 10 | ||
Reference Frame: <Fixed Frame> | ||
Value: true | ||
- Angle Tolerance: 0.10000000149011612 | ||
Class: rviz/Odometry | ||
Covariance: | ||
Orientation: | ||
Alpha: 0.5 | ||
Color: 255; 255; 127 | ||
Color Style: Unique | ||
Frame: Local | ||
Offset: 1 | ||
Scale: 1 | ||
Value: true | ||
Position: | ||
Alpha: 0.30000001192092896 | ||
Color: 204; 51; 204 | ||
Scale: 1 | ||
Value: true | ||
Value: true | ||
Enabled: true | ||
Keep: 1 | ||
Name: Odometry | ||
Position Tolerance: 0.10000000149011612 | ||
Queue Size: 10 | ||
Shape: | ||
Alpha: 1 | ||
Axes Length: 1 | ||
Axes Radius: 0.10000000149011612 | ||
Color: 255; 25; 0 | ||
Head Length: 0.30000001192092896 | ||
Head Radius: 0.10000000149011612 | ||
Shaft Length: 1 | ||
Shaft Radius: 0.05000000074505806 | ||
Value: Arrow | ||
Topic: /ekf/odometry_map | ||
Unreliable: false | ||
Value: true | ||
- Angle Tolerance: 0.10000000149011612 | ||
Class: rviz/Odometry | ||
Covariance: | ||
Orientation: | ||
Alpha: 0.5 | ||
Color: 255; 255; 127 | ||
Color Style: Unique | ||
Frame: Local | ||
Offset: 1 | ||
Scale: 1 | ||
Value: true | ||
Position: | ||
Alpha: 0.30000001192092896 | ||
Color: 204; 51; 204 | ||
Scale: 1 | ||
Value: true | ||
Value: true | ||
Enabled: true | ||
Keep: 1 | ||
Name: Odometry | ||
Position Tolerance: 0.10000000149011612 | ||
Queue Size: 10 | ||
Shape: | ||
Alpha: 1 | ||
Axes Length: 1 | ||
Axes Radius: 0.10000000149011612 | ||
Color: 255; 25; 0 | ||
Head Length: 0.30000001192092896 | ||
Head Radius: 0.10000000149011612 | ||
Shaft Length: 1 | ||
Shaft Radius: 0.05000000074505806 | ||
Value: Arrow | ||
Topic: /ekf/odometry_earth | ||
Unreliable: false | ||
Value: true | ||
- Class: rviz/TF | ||
Enabled: true | ||
Filter (blacklist): "" | ||
Filter (whitelist): "" | ||
Frame Timeout: 15 | ||
Frames: | ||
All Enabled: true | ||
base_link: | ||
Value: true | ||
cv7_ins_link: | ||
Value: true | ||
earth: | ||
Value: true | ||
fake_sensor: | ||
Value: true | ||
map: | ||
Value: true | ||
Marker Alpha: 1 | ||
Marker Scale: 1 | ||
Name: TF | ||
Show Arrows: true | ||
Show Axes: true | ||
Show Names: true | ||
Tree: | ||
earth: | ||
map: | ||
base_link: | ||
cv7_ins_link: | ||
{} | ||
fake_sensor: | ||
{} | ||
Update Interval: 0 | ||
Value: true | ||
Enabled: true | ||
Global Options: | ||
Background Color: 48; 48; 48 | ||
Default Light: true | ||
Fixed Frame: map | ||
Frame Rate: 30 | ||
Name: root | ||
Tools: | ||
- Class: rviz/Interact | ||
Hide Inactive Objects: true | ||
- Class: rviz/MoveCamera | ||
- Class: rviz/Select | ||
- Class: rviz/FocusCamera | ||
- Class: rviz/Measure | ||
- Class: rviz/SetInitialPose | ||
Theta std deviation: 0.2617993950843811 | ||
Topic: /initialpose | ||
X std deviation: 0.5 | ||
Y std deviation: 0.5 | ||
- Class: rviz/SetGoal | ||
Topic: /move_base_simple/goal | ||
- Class: rviz/PublishPoint | ||
Single click: true | ||
Topic: /clicked_point | ||
Value: true | ||
Views: | ||
Current: | ||
Class: rviz/Orbit | ||
Distance: 20.5603084564209 | ||
Enable Stereo Rendering: | ||
Stereo Eye Separation: 0.05999999865889549 | ||
Stereo Focal Distance: 1 | ||
Swap Stereo Eyes: false | ||
Value: false | ||
Field of View: 0.7853981852531433 | ||
Focal Point: | ||
X: 0 | ||
Y: 0 | ||
Z: 0 | ||
Focal Shape Fixed Size: false | ||
Focal Shape Size: 0.05000000074505806 | ||
Invert Z Axis: false | ||
Name: Current View | ||
Near Clip Distance: 0.009999999776482582 | ||
Pitch: 0.6753978729248047 | ||
Target Frame: base_link | ||
Yaw: 0.5703979134559631 | ||
Saved: ~ | ||
Window Geometry: | ||
Displays: | ||
collapsed: false | ||
Height: 846 | ||
Hide Left Dock: false | ||
Hide Right Dock: false | ||
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002b4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000030700fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | ||
Selection: | ||
collapsed: false | ||
Time: | ||
collapsed: false | ||
Tool Properties: | ||
collapsed: false | ||
Views: | ||
collapsed: false | ||
Width: 1200 | ||
X: 60 | ||
Y: 363 |
25 changes: 25 additions & 0 deletions
25
microstrain_inertial_examples/launch/cv7_ins_nmea_aux.launch
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,25 @@ | ||
<?xml version="1.1"?> | ||
|
||
<!-- Standalone example launch file to launch a node that interfaces with a CV7-INS --> | ||
<launch> | ||
|
||
<!-- Specify our custom params file to the microstrin launch file --> | ||
<include file="$(find microstrain_inertial_driver)/launch/microstrain.launch"> | ||
<arg name="namespace" value="/" /> | ||
<arg name="params_file" value="$(find microstrain_inertial_examples)/config/cv7_ins_nmea_aux/cv7_ins.yml" /> | ||
</include> | ||
|
||
<!-- Publish a static transform for where the CV7-INS is mounted on base_link. --> | ||
<!-- Unless the CV7-INS is mounted exactly at base_link, you should change this to be accurate to your setup --> | ||
<node | ||
pkg="tf" | ||
type="static_transform_publisher" | ||
name="base_link_cv7_ins_link_static_transform" | ||
output="screen" | ||
args=" | ||
0 0 0 0 0 0 base_link cv7_ins_link 1000 | ||
" /> | ||
|
||
<!-- Start RViz --> | ||
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find microstrain_inertial_examples)/config/cv7_ins_nmea_aux/display.rviz" /> | ||
</launch> |