Skip to content
This repository was archived by the owner on Feb 8, 2023. It is now read-only.
Open
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
100 changes: 32 additions & 68 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,73 +1,37 @@
cmake_minimum_required(VERSION 2.8.3)
project(imu_vn_100)

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall")

find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
diagnostic_updater
)
find_package(Boost REQUIRED)
Comment thread
versatran01 marked this conversation as resolved.

catkin_package(
INCLUDE_DIRS include vncpplib/include
LIBRARIES imu_vn_100
CATKIN_DEPENDS diagnostic_updater roscpp sensor_msgs
DEPENDS Boost
)

include_directories(
include
vncpplib/include
${catkin_INCLUDE_DIRS}
)

add_library(imu_vn_100
vncpplib/src/arch/linux/vncp_services.c
vncpplib/src/vndevice.c
vncpplib/src/vn100.c
src/imu_vn_100.cpp
)
target_link_libraries(imu_vn_100
${catkin_LIBRARIES}
)
add_dependencies(imu_vn_100
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)

add_executable(imu_vn_100_node
src/imu_vn_100_node.cpp)
target_link_libraries(imu_vn_100_node
${catkin_LIBRARIES}
imu_vn_100
)
add_dependencies(imu_vn_100_node
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)

install(TARGETS imu_vn_100 imu_vn_100_node
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h**"
)
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 11)
endif()

find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs diagnostic_updater)

catkin_package(CATKIN_DEPENDS
diagnostic_updater
roscpp
sensor_msgs)

add_executable(${PROJECT_NAME}_node
src/imu_vn_100.cpp
vncpplib/src/arch/linux/vncp_services.c
vncpplib/src/vn100.c
vncpplib/src/vndevice.c)
target_include_directories(${PROJECT_NAME}_node
PUBLIC src vncpplib/include ${catkin_INCLUDE_DIRS})
Comment thread
versatran01 marked this conversation as resolved.
target_link_libraries(${PROJECT_NAME}_node PUBLIC ${catkin_LIBRARIES})

install(TARGETS ${PROJECT_NAME}_node
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})

install(FILES vncpplib/include/vn100.h
vncpplib/include/vncp_services.h
vncpplib/include/vndevice.h
vncpplib/include/vn_errorCodes.h
vncpplib/include/vn_kinematics.h
vncpplib/include/vn_linearAlgebra.h
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)

install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
vncpplib/include/vncp_services.h
vncpplib/include/vndevice.h
vncpplib/include/vn_errorCodes.h
vncpplib/include/vn_kinematics.h
vncpplib/include/vn_linearAlgebra.h
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})

install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
25 changes: 11 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,13 +45,10 @@ The baud rate of the serial port. The available baud rates can be checked on the
The rate of the IMU data.

```
enable_magn (bool, default: true)
enable_press (bool, default: true)
enable_temp (bool, default: true)
enable_rpy (bool, default: false)
enable_mag_pres (bool, default: true)
Comment thread
versatran01 marked this conversation as resolved.
```

Enable other possible messages that the driver is available to send. Note that the frequency of the data for each of these messages will be the same with the IMU data, if the topic is enabled.
Calibrated magnetic (compensated), temperature, and pressure measurements.

`sync_rate` (`int`, `20`)

Expand All @@ -68,9 +65,13 @@ Set serial port for binary messages to one of:
* `1` - Serial port 1
* `2` - Serial port 2

`imu_compensated` (`boolean`, `default: true`)
`compensated` (`boolean`, `default: true`)

Use *compensated* IMU measurements (i.e. angular velocity, linear acceleration, magnetic field).
Use *compensated* IMU measurements (i.e. angular velocity, linear acceleration).

`time_alpha` (`double`, `default: 0`)

Used when computing time stamp. `t1 = a * dt_ros + (1 - a) * dt_dev + t0

`vpe_enable` (`boolean`, `default: true`)

Expand Down Expand Up @@ -102,11 +103,11 @@ Set VPE tuning mode to one of:

`imu/imu` (`sensor_msgs/Imu`)

If `imu_compensated` is `false`, the default, then the message contains the *uncompensated* (for the definition of UNCOMPENSATED, please refer to the [user manual](http://www.vectornav.com/docs/default-source/documentation/vn-100-documentation/UM001.pdf?sfvrsn=10)) angular velocity and linear acceleration. Otherwise both are *compensated*.
If `compensated` is `false`, the default, then the message contains the *uncompensated* (for the definition of UNCOMPENSATED, please refer to the [user manual](http://www.vectornav.com/docs/default-source/documentation/vn-100-documentation/UM001.pdf?sfvrsn=10)) angular velocity and linear acceleration. Otherwise both are *compensated*.

`imu/magnetic_field` (`sensor_msgs/MagneticField`)

Magnetic field. If `imu_compensated` is `false` then it is *uncompensated* otherwise it is *compensated*.
Magnetic field. Always *compensated*.

`imu/pressure` (`sensor_msgs/FluidPressure`)

Expand All @@ -116,16 +117,12 @@ Pressure.

Temperature in degree Celsius

`imu/rpy` (`geometry_msgs/Vector3Stamped`)

Estimated roll (`x`), pitch (`y`) and yaw (`z`) angles in radians given as a 3,2,1 Euler angle rotation sequence describing the orientation of the sensor with respect to the inertial North East Down (NED) frame.

**Node**

With the provided launch file, do

```
roslaunch imu_vn_100 vn_100_cont.launch
roslaunch imu_vn_100 imu.launch
```

## FAQ
Expand Down
20 changes: 10 additions & 10 deletions launch/vn_100_cont.launch → launch/imu.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,15 @@

<!-- Sync out settings -->
<!-- to disable this just set it to < 0 -->
<arg name="sync_rate" default="20"/>
<arg name="sync_rate" default="0"/>
<arg name="sync_pulse_width_us" default="1000"/>

<!-- Binary settings -->
<arg name="binary_output" default="true"/>
<arg name="binary_async_mode" default="2"/>

<arg name="imu_compensated" default="false"/>
<arg name="compensated" default="false"/>
<arg name="time_alpha" default="0.0"/>

<!-- VPE settings -->
<arg name="vpe_enable" default="true"/>
Expand All @@ -26,9 +27,7 @@

<!-- Ros Topic settings -->
<arg name="enable_mag" default="true"/>
<arg name="enable_pres" default="true"/>
<arg name="enable_temp" default="true"/>
<arg name="enable_rpy" default="false"/>
<arg name="enable_mag_pres" default="$(arg enable_mag)"/>

<node pkg="imu_vn_100" name="$(arg imu)" type="imu_vn_100_node" output="$(arg output)">
<param name="port" type="string" value="$(arg port)"/>
Expand All @@ -37,13 +36,14 @@
<param name="imu_rate" type="int" value="$(arg imu_rate)"/>
<param name="binary_output" type="bool" value="$(arg binary_output)"/>
<param name="binary_async_mode" type="int" value="$(arg binary_async_mode)"/>
<param name="imu_compensated" type="bool" value="$(arg imu_compensated)"/>
<param name="enable_mag" type="bool" value="$(arg enable_mag)"/>
<param name="enable_pres" type="bool" value="$(arg enable_pres)"/>
<param name="enable_temp" type="bool" value="$(arg enable_temp)"/>
<param name="enable_rpy" type="bool" value="$(arg enable_rpy)"/>
<param name="compensated" type="bool" value="$(arg compensated)"/>
<param name="time_alpha" type="double" value="$(arg time_alpha)"/>

<param name="enable_mag_pres" type="bool" value="$(arg enable_mag_pres)"/>

<param name="sync_rate" type="int" value="$(arg sync_rate)"/>
<param name="sync_pulse_width_us" type="int" value="$(arg sync_pulse_width_us)"/>

<param name="vpe/enable" type="bool" value="$(arg vpe_enable)"/>
<param name="vpe/heading_mode" type="int" value="$(arg vpe_heading_mode)"/>
<param name="vpe/filtering_mode" type="int" value="$(arg vpe_filtering_mode)"/>
Expand Down
4 changes: 1 addition & 3 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
<description>The imu_vn_100 package</description>

<maintainer email="sunke.polyu@gmail.com">Ke Sun</maintainer>
<maintainer email="quchao@seas.upenn.edu">Chao Qu</maintainer>
<license>Apache 2.0</license>
<!-- <url type="website">http://wiki.ros.org/imu_vn_100</url> -->
<author email="sunke.polyu@gmail.com">Ke Sun</author>
Expand All @@ -15,9 +16,6 @@
<depend>roscpp</depend>
<depend>sensor_msgs</depend>


<export>
<!-- Other tools can request additional information be placed here -->

</export>
</package>
Loading