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

add support of noetic #122

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions AUTHORS
Original file line number Diff line number Diff line change
Expand Up @@ -11,3 +11,6 @@ João Sousa <[email protected]>
Vincent Rousseau <[email protected]>
Martin Pecka <[email protected]>
Konstantinos Chatzilygeroudis <[email protected]>
Jean Laneurit <[email protected]>
Roland Lenain <[email protected]>
Cyrille Pierre <[email protected]>
6 changes: 6 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package xsens_driver
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.2.3 (2022-10-27)
------------------
* add support of noetic
* fix quaternion computation from rotation matrix data provided by IMU
* Contributors: Roland Lenain, Cyrille Pierre

2.2.2 (2018-08-02)
------------------
* fix exception while closing node
Expand Down
26 changes: 13 additions & 13 deletions launch/xsens_driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!-- parameters -->
<arg name="device" default="auto" doc="device file of the IMU"/>
<arg name="baudrate" default="0" doc="baudrate of the IMU"/>
<arg name="timeout" default="0.002" doc="timeout for the IMU communication"/>
<arg name="timeout" default="0.1" doc="timeout for the IMU communication"/>
<arg name="initial_wait" default="0.1" doc="initial wait to allow device to come up"/>
<arg name="frame_id" default="/imu" doc="frame id of the IMU"/>
<arg name="frame_local" default="ENU" doc="desired frame orientation (ENU, NED or NWU)"/>
Expand All @@ -12,16 +12,16 @@
<arg name="orientation_covariance_diagonal" default="[0.01745, 0.01745, 0.15708]" doc="Diagonal elements of the orientation covariance matrix"/>

<!-- node -->
<node pkg="xsens_driver" type="mtnode.py" name="xsens_driver" output="screen" >
<param name="device" value="$(arg device)"/>
<param name="baudrate" value="$(arg baudrate)"/>
<param name="timeout" value="$(arg timeout)"/>
<param name="initial_wait" value="$(arg initial_wait)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="frame_local" value="$(arg frame_local)"/>
<param name="no_rotation_duration" value="$(arg no_rotation_duration)"/>
<rosparam param="angular_velocity_covariance_diagonal" subst_value="True">$(arg angular_velocity_covariance_diagonal)</rosparam>
<rosparam param="linear_acceleration_covariance_diagonal" subst_value="True">$(arg linear_acceleration_covariance_diagonal)</rosparam>
<rosparam param="orientation_covariance_diagonal" subst_value="True">$(arg orientation_covariance_diagonal)</rosparam>
</node>
<node pkg="xsens_driver" type="mtnode.py" name="xsens_driver" output="screen" >
<param name="device" value="$(arg device)"/>
<param name="baudrate" value="$(arg baudrate)"/>
<param name="timeout" value="$(arg timeout)"/>
<param name="initial_wait" value="$(arg initial_wait)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="frame_local" value="$(arg frame_local)"/>
<param name="no_rotation_duration" value="$(arg no_rotation_duration)"/>
<rosparam param="angular_velocity_covariance_diagonal" subst_value="True">$(arg angular_velocity_covariance_diagonal)</rosparam>
<rosparam param="linear_acceleration_covariance_diagonal" subst_value="True">$(arg linear_acceleration_covariance_diagonal)</rosparam>
<rosparam param="orientation_covariance_diagonal" subst_value="True">$(arg orientation_covariance_diagonal)</rosparam>
</node>
</launch>
5 changes: 3 additions & 2 deletions nodes/mtdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class DeprecatedMID:
def getName(cls, value):
'''Return the name of the first found member of class cls with given
value.'''
for k, v in cls.__dict__.iteritems():
for k, v in iter(cls.__dict__.items()):
if v == value:
return k
return ''
Expand Down Expand Up @@ -232,9 +232,10 @@ class OutputMode:
Position = 0x0010
Velocity = 0x0020
Status = 0x0800

RAWGPS = 0x1000 # supposed to be incompatible with previous
RAW = 0x4000 # incompatible with all except RAWGPS

# RAW = 0x0006

class OutputSettings:
"""Values for the output settings."""
Expand Down
Loading