Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GX5-10 compatibility #5

Open
ryanmeasel opened this issue Jan 7, 2018 · 8 comments
Open

GX5-10 compatibility #5

ryanmeasel opened this issue Jan 7, 2018 · 8 comments

Comments

@ryanmeasel
Copy link

ryanmeasel commented Jan 7, 2018

I'm building compatibility for the GX5-10 into the driver. My progress thus far:

The GX5-10 is connected through an RS232-to-USB connector on /dev/ttyUSB0. It was necessary to add the Linux user to the dialout group so that the driver could connect over that port.

The GX5-10 does not have AHRS or filtering features, so for starters, I commented out the portions of publish_imu code that configured the AHRS as well as all the filter related functionality.

Using microstrain_25.launch, the driver progresses to spinning up the IMU. This is confirmed by log output from the driver as well as the indicator lights on the IMU. Unfortunately, no messages are published over /imu/data.

Any thoughts? Is there a separate data stream that needs be started since there is no AHRS data stream?

Thanks for your help!

Driver version: b57c78a (latest)
ROS distro: kinetic
ROS version: 1.12.12
OS: Ubuntu 16.04

@bsb808
Copy link
Collaborator

bsb808 commented Jan 7, 2018

Ryan,

Have you tried running the driver (without commenting out any code) using the microstrain_25.launch file? In the launch file you can set the ROSCONSOLE_CONFIG_FILE variable so that the debug ROS log information is set to the screen - that might help.

If you can send me the log file from that test I may be able to tell what is going on.

The -10 sensor will need to have the publish_imu code, that is the only part of the code that will apply to the -10. With the publish_imu parameter set to true, the driver will read the following messages...

  • MIP_AHRS_DATA_ACCEL_SCALED
  • MIP_AHRS_DATA_GYRO_SCALED;
  • MIP_AHRS_DATA_QUATERNION

which are used to populate the /imu/data topic.

The datasheet for the -10 suggests the it doesn't report the quaternion data, only the accelerometer and gyro data. This will likely cause the driver to hang, but it is a good first step.

I can make a quick modification to try and support the -10 if you are will to test with the hardware and send logs.

Thank you!
Brian

@ryanmeasel
Copy link
Author

ryanmeasel commented Jan 7, 2018

Sure thing. I've enclosed the output running the driver as is with the microstrain_25.launch and the logging level set to DEBUG.

It hangs at "Setting the AHRS message format" which I suspect is line 252 where the message format is being set with 3 entries including Quaternions.

Happy to try any modifications! I'll be working on this all day.

ryan@snorlax:~/catkin_ws_microstrain$ roslaunch microstrain_3dm_gx5_45 microstrain_25.launch                                                                           
... logging to /home/ryan/.ros/log/c2676482-f3e9-11e7-ba50-408d5c0720fc/roslaunch-snorlax-21539.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://snorlax:38135/

SUMMARY
========

PARAMETERS
 * /microstrain_3dm_gx5_25_node/auto_init: True
 * /microstrain_3dm_gx5_25_node/baudrate: 115200
 * /microstrain_3dm_gx5_25_node/declination: 0.23
 * /microstrain_3dm_gx5_25_node/declination_source: 2
 * /microstrain_3dm_gx5_25_node/device_setup: True
 * /microstrain_3dm_gx5_25_node/dynamics_mode: 1
 * /microstrain_3dm_gx5_25_node/gps_frame_id: navsat_link
 * /microstrain_3dm_gx5_25_node/gps_rate: 4
 * /microstrain_3dm_gx5_25_node/imu_frame_id: imu_link
 * /microstrain_3dm_gx5_25_node/imu_rate: 100
 * /microstrain_3dm_gx5_25_node/nav_rate: 10
 * /microstrain_3dm_gx5_25_node/odom_child_frame_id: base_link
 * /microstrain_3dm_gx5_25_node/odom_frame_id: wgs84_odom_link
 * /microstrain_3dm_gx5_25_node/port: /dev/ttyUSB0
 * /microstrain_3dm_gx5_25_node/publish_gps: False
 * /microstrain_3dm_gx5_25_node/publish_imu: True
 * /microstrain_3dm_gx5_25_node/publish_odom: False
 * /microstrain_3dm_gx5_25_node/readback_settings: True
 * /microstrain_3dm_gx5_25_node/save_settings: True
 * /rosdistro: kinetic
 * /rosversion: 1.12.12

NODES
  /
    microstrain_3dm_gx5_25_node (microstrain_3dm_gx5_45/microstrain_3dm_gx5_45_node)

auto-starting new master
process[master]: started with pid [21550]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to c2676482-f3e9-11e7-ba50-408d5c0720fc
process[rosout-1]: started with pid [21563]
started core service [/rosout]
process[microstrain_3dm_gx5_25_node-2]: started with pid [21580]
[DEBUG] [1515357097.612854648]: remap: __name => microstrain_3dm_gx5_25_node
[DEBUG] [1515357097.612883964]: remap: __log => /home/ryan/.ros/log/c2676482-f3e9-11e7-ba50-408d5c0720fc/microstrain_3dm_gx5_25_node-2.log
[DEBUG] [1515357097.613744592]: Adding tcp socket [6] to pollset
[DEBUG] [1515357097.613824434]: UDPROS server listening on port [38576]
[DEBUG] [1515357097.615742408]: Started node [/microstrain_3dm_gx5_25_node], pid [21580], bound on [snorlax], xmlrpc port [39511], tcpros port [49381], using [real] time
[ INFO] [1515357097.628631176]: Attempting to open serial port </dev/ttyUSB0> at <115200> 

[ INFO] [1515357097.629224902]: Putting device communications into 'standard mode'
[ INFO] [1515357097.634967590]: Verify comm's mode
[ INFO] [1515357097.637049130]: Sleep for a second...
[DEBUG] [1515357097.866681458]: Accepted connection on socket [6], new socket [11]
[DEBUG] [1515357097.866981109]: Adding tcp socket [11] to pollset
[DEBUG] [1515357097.867047889]: TCPROS received a connection from [127.0.0.1:51124]
[DEBUG] [1515357097.868009100]: Connection: Creating TransportSubscriberLink for topic [/rosout] connected to [callerid=[/rosout] address=[TCPROS connection on port 49381 to [127.0.0.1:51124 on socket 11]]]
[ INFO] [1515357098.137285572]: Right mode?
[ INFO] [1515357098.137378550]: Idling Device: Stopping data streams and/or waking from sleep
[ INFO] [1515357098.644347953]: AHRS Base Rate => 1000 Hz
[ INFO] [1515357099.144537882]: AHRS decimation set to 0X0A
[ INFO] [1515357099.144588019]: Setting the AHRS message format

@ryanmeasel
Copy link
Author

ryanmeasel commented Jan 7, 2018

Changing the line 251 to 2 entries allows the message format and poll data calls to function.

Line 251

data_stream_format_num_entries = 2;
process[microstrain_3dm_gx5_25_node-2]: started with pid [24120]
[DEBUG] [1515358891.633064172]: remap: __name => microstrain_3dm_gx5_25_node
[DEBUG] [1515358891.633103233]: remap: __log => /home/ryan/.ros/log/efb9ec1c-f3ed-11e7-ba50-408d5c0720fc/microstrain_3dm_gx5_25_node-2.log
[DEBUG] [1515358891.633813436]: Adding tcp socket [6] to pollset
[DEBUG] [1515358891.633891573]: UDPROS server listening on port [60447]
[DEBUG] [1515358891.635771863]: Started node [/microstrain_3dm_gx5_25_node], pid [24120], bound on [snorlax], xmlrpc port [42853], tcpros port [52965], using [real] time
[ INFO] [1515358891.648730627]: Attempting to open serial port </dev/ttyUSB0> at <115200> 

[ INFO] [1515358891.649090571]: Putting device communications into 'standard mode'
[ INFO] [1515358891.654711818]: Verify comm's mode
[ INFO] [1515358891.656794405]: Sleep for a second...
[DEBUG] [1515358891.891373612]: Accepted connection on socket [6], new socket [11]
[DEBUG] [1515358891.891667857]: Adding tcp socket [11] to pollset
[DEBUG] [1515358891.891805381]: TCPROS received a connection from [127.0.0.1:42530]
[DEBUG] [1515358891.899942705]: Connection: Creating TransportSubscriberLink for topic [/rosout] connected to [callerid=[/rosout] address=[TCPROS connection on port 52965 to [127.0.0.1:42530 on socket 11]]]
[ INFO] [1515358892.156984437]: Right mode?
[ INFO] [1515358892.157035335]: Idling Device: Stopping data streams and/or waking from sleep
[ INFO] [1515358892.672206101]: AHRS Base Rate => 1000 Hz
[ INFO] [1515358893.172474548]: AHRS decimation set to 0X0A
[ INFO] [1515358893.172566163]: Setting the AHRS message format
[ INFO] [1515358893.678890930]: Poll AHRS data to verify
[DEBUG] [1515358893.686957097]: 0 FILTER (0 errors)    1 AHRS (0 errors)    0 GPS (0 errors) Packets
[ INFO] [1515358894.187941963]: Saving AHRS data settings
[ INFO] [1515358897.696876899]: Setting declination source to 0X02

@ryanmeasel
Copy link
Author

After commenting the declination and filter code, it works!

Specifically, lines:
268 -- 291
425 -- 456
487 -- 489

@bsb808
Copy link
Collaborator

bsb808 commented Jan 7, 2018

Ryan,

That is great. I added a few more parameters so that the driver can support the -10 (in addition to the -25, -35 and -45). I also added a new -10 specific launch file for you to try.

These changes are in the "10-dev" branch. Could you give it a try? Would be nice if we can merge your changes back into the master.

Nice job!
Brian

@ryanmeasel
Copy link
Author

ryanmeasel commented Jan 8, 2018

There are few issues that persist.

  • data_stream_format_num_entries needs to be set to 2 (Line 258).
  • It hangs on lines 446 and 460.

Adding more one-off settings seems inefficient. I'm not too familiar with ROS node architecture, but can the functionality be modularized into different types within the same package? It'd further be nice to not obscure the compatibility range under the "gx5-45" package name. I'd be happy to contribute if you wanted to push down a path like that.

@bsb808
Copy link
Collaborator

bsb808 commented Jan 8, 2018 via email

@ryanmeasel
Copy link
Author

Awesome, I'll work on the pull. May take a few weeks (work on this is mostly reserved to the weekends).

Thanks for your informative and speedy replies! Really appreciate the help!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants