Commit 0cbd0f8c authored by Dave Niewinski's avatar Dave Niewinski Committed by Tony Baltovski
Browse files

Properly support GX5 (#77)

* Updated udev rule to differentiate between the GX3 (legacy) and the GX5 (current) and install a different launch file

* Removed unnecessary launch lines

* Updated dependencies and gx5 launch for new mips package

* Fixed package typo
parent 09ecd055
......@@ -3,7 +3,7 @@
<!-- imu -->
<node pkg="microstrain_3dmgx2_imu" type="imu_node" name="microstrain_imu">
<param name="time_offset" value="-0.040" />
<param name="port" value="/dev/microstrain" />
<param name="port" value="/dev/microstrain_gx3" />
<param name="frame_id" type="string" value="imu_link" />
<param name="autocalibrate" value="true" />
<param name="angular_velocity_stdev" value="0.00017" />
......
<?xml version="1.0"?>
<launch>
<!-- Standalone example launch file for 3DM-GX5-25 -->
<!-- Declare arguments with default values -->
<arg name="port" default="/dev/microstrain_gx5" />
<arg name="baudrate" default="115200" />
<arg name="imu_rate" default="100" />
<arg name="imu_frame_id" default="imu_link" />
<arg name="debug" default="false" />
<arg name="diagnostics" default="false" />
<!-- For setting debug level to debug -->
<group if="$(arg debug)">
<env name="ROSCONSOLE_CONFIG_FILE"
value="$(find microstrain_mips)/config/custom_rosconsole.conf"/>
</group>
<!-- Microstrain sensor node -->
<node name="microstrain_mips_node"
pkg="microstrain_mips"
type="microstrain_mips_node" output="screen" ns="gx5">
<param name="port" value="$(arg port)" type="str" />
<param name="baudrate" value="$(arg baudrate)" type="int" />
<param name="device_setup" value="true" type="bool" />
<!-- General Settings -->
<param name="readback_settings" value="true" type="bool" />
<param name="save_settings" value="true" type="bool" />
<param name="auto_init" value="true" type="bool" />
<!-- The GX5-25 is AHRS only, so need to turn off the other messages -->
<!-- AHRS Settings -->
<param name="publish_imu" value="true" type="bool" />
<param name="imu_rate" value="$(arg imu_rate)" type="int" />
<param name="imu_frame_id" value="$(arg imu_frame_id)" type="str" />
<!-- Declination source 1=None, 2=magnetic, 3=manual -->
<param name="declination_source" value="2" type="int" />
<param name="declination" value="0.23" type="double" />
<!-- GPS Settings -45 and -35 Only -->
<param name="gps_rate" value="4" type="int" />
<param name="gps_frame_id" value="navsat_link" type="str" />
<!-- Filter Settings - GXx-45 Only -->
<param name="nav_rate" value="10" type="int" />
<param name="dynamics_mode" value="1" type="int" />
<param name="odom_frame_id" value="wgs84_odom_link" type="str" />
<param name="odom_child_frame_id" value="base_link" type="str" />
</node>
<!-- Diagnostics -->
<group if="$(arg diagnostics)">
<!--<node pkg="rqt_topic" type="rqt_topic" name="rqt_topic"/>-->
<!--<node pkg="rqt_plot" type="rqt_plot" name="pid_setpoints"
args="/yaw_pid_debug/Setpoint /vel_pid_debug/Setpoint"/>-->
<!-- Diagnostic Aggregator for robot monitor usage -->
<node pkg="diagnostic_aggregator" type="aggregator_node" name="imu_diagnostic_aggregator">
<rosparam command="load" file="$(find microstrain_mips)/config/diagnostic_analyzers.yaml" />
</node>
</group>
</launch>
......@@ -28,6 +28,7 @@
<run_depend>imu_transformer</run_depend>
<run_depend>lms1xx</run_depend>
<run_depend>microstrain_3dmgx2_imu</run_depend>
<run_depend>microstrain_mips</run_depend>
<run_depend>nmea_comms</run_depend>
<run_depend>nmea_navsat_driver</run_depend>
<run_depend>python-scipy</run_depend>
......
......@@ -14,8 +14,11 @@ if os.path.exists('/dev/clearpath/imu') or os.path.exists('/dev/clearpath/um6'):
if os.path.exists('/dev/clearpath/um7'):
j.add(package="husky_bringup", glob="launch/um7_config/*")
if os.path.exists('/dev/microstrain'):
j.add(package="husky_bringup", glob="launch/microstrain_config/*")
if os.path.exists('/dev/microstrain_gx3'):
j.add(package="husky_bringup", glob="launch/microstrain_gx3_config/*")
if os.path.exists('/dev/microstrain_gx5'):
j.add(package="husky_bringup", glob="launch/microstrain_gx5_config/*")
if os.path.exists('/dev/clearpath/gps'):
j.add(package="husky_bringup", glob="launch/navsat_config/*")
......
SUBSYSTEM=="tty", ATTRS{idVendor}=="199b", ATTRS{idProduct}=="3065", SYMLINK="microstrain", MODE="0666"
SUBSYSTEM=="tty", ATTRS{idVendor}=="199b", ATTRS{idProduct}=="3065", SYMLINK="microstrain_gx3", MODE="0666"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", SYMLINK="microstrain_gx5", MODE="0666"
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment