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

Updates and publish rate #70

Merged
merged 3 commits into from
Jul 14, 2021
Merged
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
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,11 @@ catkin_package(
###########

#include(vnproglib-1.1/cpp/CMakeLists.txt)
add_subdirectory(vnproglib-1.1.5.0/cpp)
add_subdirectory(vnproglib-1.2.0.0/cpp)

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(vnproglib-1.1.5.0/cpp/include ${catkin_INCLUDE_DIRS})
include_directories(vnproglib-1.2.0.0/cpp/include ${catkin_INCLUDE_DIRS})

## Declare a cpp library
## Declare a cpp executable
Expand Down
30 changes: 30 additions & 0 deletions Dockerfile
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
FROM ros:noetic-ros-core

# change shell to bash
SHELL ["/bin/bash","-c"]

# install build packages
RUN apt-get update && \
apt-get install -y --no-install-recommends \
make g++ cmake ros-noetic-tf2 ros-noetic-tf2-geometry-msgs && \
rm -rf /var/lib/apt/lists/*

# copy vectornav repo to workspace
COPY . /catkin_ws/src/vectornav

# change to workspace
WORKDIR /catkin_ws

# build workspace
RUN source /opt/ros/noetic/setup.bash && \
catkin_make

# create entrypoint script
RUN printf '#!/bin/bash\nsource /catkin_ws/devel/setup.bash\nexec "$@"' > /entrypoint.bash && \
chmod 777 /entrypoint.bash

# define entrypoint
ENTRYPOINT ["/entrypoint.bash"]

# define startup default command
CMD ["roslaunch", "vectornav", "vectornav.launch"]
8 changes: 4 additions & 4 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,13 +223,14 @@ int main(int argc, char *argv[])
uint32_t sn = vs.readSerialNumber();
ROS_INFO("Model Number: %s, Firmware Version: %s", mn.c_str(), fv.c_str());
ROS_INFO("Hardware Revision : %d, Serial Number : %d", hv, sn);
ROS_INFO("Publish Rate: %d Hz", async_output_rate);

// Set the device info for passing to the packet callback function
UserData user_data;
user_data.device_family = vs.determineDeviceFamily();

// Set Data output Freq [Hz]
vs.writeAsyncDataOutputFrequency(async_output_rate);
// Make sure no generic async output is registered
vs.writeAsyncDataOutputType(VNOFF);

// Configure binary output message
BinaryOutputRegister bor(
Expand Down Expand Up @@ -260,8 +261,7 @@ int main(int argc, char *argv[])

vs.writeBinaryOutput1(bor);

// Set Data output Freq [Hz]
vs.writeAsyncDataOutputFrequency(async_output_rate);
// Register async callback function
vs.registerAsyncPacketReceivedHandler(&user_data, BinaryAsyncMessageReceived);

// You spin me right round, baby
Expand Down
51 changes: 51 additions & 0 deletions vnproglib-1.2.0.0/CHANGELOG.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
Changelog for VectorNav Programming Library

2021-06-08 v1.2.0.0
- Added support and examples for embedded firmware updates (C,C++,.NET)
- Added support and example for passing through RTCM corrections to Tactical products (C++)
- Added Heave Configuration Register & binary output parsing (C++)
- Added examples supporting Visual Studio 2019 (C,C++,.NET)
- Updated Python help files for installation troubleshooting
- Fixed bug (C++) Delta Theta/Velocity Configuration Register, bad enumeration for
Accelerometer Compensation, added EarthRateCorrection enumeration
* NOT BACKWARDS COMPATIBLE *
- Updated GPS Basic Configuration register (C++) for setting antenna power
- Fixed bug (C++) in dcm2quat() function
- Fixed bug (C++) to add support for CompositeData::positionGpsEcef()
- Fixed bug (C++) for timing on Mac systems
- Fixed bug (C++) for using SYNCINMODE_ASYNC3
- Added support for connecting to multiple sensors simultaneously (C++)
- Fixed bug (C++) for parsing Binary Group GPS-2 data
- Cleaned up ASCII response packet parsing, including InsStatus field (C++)
- Fixed bug (C++) in packet handler when not waiting for response
- Fixed bug (C++) in parsing GpsTow from VNGPS & VNGPE messages
- Cleaned up packetfinder (C++), including putting checks on packet lengths to prevent
ouf-of-memory issues and increasing buffer sizes to handle larger binary messages

2019-06-10 v1.1.5.0
- Added a license file to the distribution (which includes the version number)
- Updated the C++ library to support GPS-2
- Added .NET-library getting_started example project for Visual Studio 2017 and x64 builds
(which also supports Matlab and Labview)
- Fixed bug (C) that prevented writing to the User Tag register
- Fixed bug (C++) in serial parser that could lead to program hanging due to never unlocking
a CriticalSection
- Added support in C++ for SYNCINMODE_ASYNC3
- Updated C-library to be able to be compiled as C++ code (restoring past functionality)

2018-06-13 v1.1.4.0
- Fixed bug (C,C++,.NET) that could cause process to hang when both ASCII and binary data
present on port
- Fixed bug (C,C++) that can cause process to crash or consume 100% CPU on Linux machines
- Re-compiled the .NET DLLs so Labview examples work properly
- Added support for UTC time outputs in both C & C++
- Added Binary Group 7 (GPS2) outputs to C-library (not available in any other language)
- Added support to C-library for binary outputs SyncOutCnt, TimeStatus, TimeInfo, GpsDOP
(now available across C, C++, .NET)
- Fixed bug (C) that output garbage when parsing hex printed values in ASCII outputs: VNERR
message, INS Status, Binary Output Configuration Registers
- Fixed bug (C++) in example Makefiles causing linking error

2018-03-05 v1.1.2.0
- Added support in C++ & .NET for binary outputs: SyncInCnt, TimeStatus, TimeInfo, GpsDOP

22 changes: 22 additions & 0 deletions vnproglib-1.2.0.0/LICENSE.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
The MIT License (MIT)

VectorNav Programming Library (v1.2.0.0)
Copyright (c) 2015 VectorNav Technologies, LLC

Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ set(SOURCE
src/packetfinder.cpp
src/port.cpp
src/position.cpp
src/rtcmlistener.cpp
src/rtcmmessage.cpp
src/searcher.cpp
src/sensors.cpp
src/serialport.cpp
Expand All @@ -44,6 +46,8 @@ set(SOURCE
include/vn/error_detection.h
include/vn/position.h
include/vn/registers.h
include/vn/rtcmlistener.h
include/vn/rtcmmessage.h
include/vn/utilities.h
include/vn/memoryport.h
include/vn/nocopy.h
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ SOURCES = \
src/packetfinder.cpp \
src/port.cpp \
src/position.cpp \
src/rtcmlistener.cpp \
src/rtcmmessage.cpp \
src/searcher.cpp \
src/sensors.cpp \
src/serialport.cpp \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#define _VN_EXCEPTIONS_H_

#include <stdexcept>
#include <string>

namespace vn {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,13 @@ struct vn_proglib_DLLEXPORT Packet
/// otherwise <c>false</c>.
bool isAsciiAsync();

/// \brief Indicates if the packet is a Bootloader message.
///
/// \return <c>true</c> if the packet is a Bootloader message;
/// otherwise <c>false</c>.
bool isBootloader();


/// \brief Determines the type of ASCII asynchronous message this packet
/// is.
///
Expand Down Expand Up @@ -373,6 +380,14 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genReset(ErrorDetectionMode errorDetectionMode, char *buffer, size_t size);

/// \brief Generates a command to put the sensor in firmware update mode.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
/// \param[in] size Number of bytes available in the provided buffer.
/// \return The total number bytes in the generated command.
static size_t genFirmwareUpdate(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size);

/// \brief Generates a command to read the Serial Baud Rate register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
Expand Down Expand Up @@ -430,6 +445,15 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genWriteAsyncDataOutputFrequency(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, uint32_t adof, uint8_t port);

/// \brief Generates a command to write to a firmware update record on a VectorNav sensor to the bootloader.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
/// \param[in] size Number of bytes available in the provided buffer.
/// \param[in] record The record to write to the bootloader for a specific processor on the sensor.
/// \return The total number bytes in the generated command.
static size_t genWriteFirmwareUpdateRecord(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, std::string record);

/// \brief Generates a command to read the User Tag register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
Expand Down Expand Up @@ -791,6 +815,36 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genWriteFilterBasicControl(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, uint8_t magMode, uint8_t extMagMode, uint8_t extAccMode, uint8_t extGyroMode, vn::math::vec3f gyroLimit);

/// \brief Generates a command to read the Heave Configuration register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
/// \param[in] size Number of bytes available in the provided buffer.
/// \return The total number bytes in the generated command.
static size_t genReadHeaveConfiguration(ErrorDetectionMode errorDetectionMode, char *buffer, size_t size);

/// \brief Generates a command to write to the VPE Basic Control register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
/// \param[in] size Number of bytes available in the provided buffer.
/// \param[in] initialWavePeriod Value for the initialWavePeriod field.
/// \param[in] initialWaveAmplitude Value for the initialWaveAmplitude field.
/// \param[in] maxWavePeriod Value for the maxWavePeriod field.
/// \param[in] minWaveAmplitude Value for the minWaveAmplitude field.
/// \param[in] delayedHeaveCutoffFreq Value for the delayedHeaveCutoffFreq field.
/// \param[in] heaveCutoffFreq Value for the heaveCutoffFreq field.
/// \param[in] heaveRateCutoffFreq Value for the heaveRateCutoffFreq field.
/// \return The total number bytes in the generated command.
static size_t genWriteHeaveConfiguration(ErrorDetectionMode errorDetectionMode,char *buffer, size_t size,
float initialWavePeriod,
float initialWaveAmplitude,
float maxWavePeriod,
float minWaveAmplitude,
float delayedHeaveCutoffFreq,
float heaveCutoffFreq,
float heaveRateCutoffFreq);

/// \brief Generates a command to read the VPE Basic Control register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
Expand Down Expand Up @@ -1031,7 +1085,7 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genReadGpsConfiguration(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size);

/// \brief Generates a command to write to the GPS Configuration register on a VectorNav sensor.
/// \brief Generates a command to write to the GPS Configuration register on a VectorNav sensor (deprecated).
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
Expand All @@ -1041,6 +1095,18 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genWriteGpsConfiguration(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, uint8_t mode, uint8_t ppsSource);

/// \brief Generates a command to write to the GPS Configuration register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
/// \param[in] size Number of bytes available in the provided buffer.
/// \param[in] mode The register's Mode field.
/// \param[in] ppsSource The register's PpsSource field.
/// \param[in] rate The register's Rate field.
/// \param[in] antPow The register's AntPower field.
/// \return The total number bytes in the generated command.
static size_t genWriteGpsConfiguration(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, uint8_t mode, uint8_t ppsSource, uint8_t rate, uint8_t antPow);

/// \brief Generates a command to read the GPS Antenna Offset register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
Expand Down Expand Up @@ -1191,7 +1257,7 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genReadDeltaThetaAndDeltaVelocityConfiguration(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size);

/// \brief Generates a command to write to the Delta Theta and Delta Velocity Configuration register on a VectorNav sensor.
/// \brief Generates a command to write to the Delta Theta and Delta Velocity Configuration register on a VectorNav sensor (deprecated).
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
Expand All @@ -1202,6 +1268,18 @@ struct vn_proglib_DLLEXPORT Packet
/// \return The total number bytes in the generated command.
static size_t genWriteDeltaThetaAndDeltaVelocityConfiguration(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, uint8_t integrationFrame, uint8_t gyroCompensation, uint8_t accelCompensation);

/// \brief Generates a command to write to the Delta Theta and Delta Velocity Configuration register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
/// \param[in] buffer Caller provided buffer to place the generated command.
/// \param[in] size Number of bytes available in the provided buffer.
/// \param[in] integrationFrame The register's IntegrationFrame field.
/// \param[in] gyroCompensation The register's GyroCompensation field.
/// \param[in] accelCompensation The register's AccelCompensation field.
/// \param[in] earthRateCorrection The register's EarthRateCorrection field.
/// \return The total number bytes in the generated command.
static size_t genWriteDeltaThetaAndDeltaVelocityConfiguration(ErrorDetectionMode errorDetectionMode, char* buffer, size_t size, uint8_t integrationFrame, uint8_t gyroCompensation, uint8_t accelCompensation, uint8_t earthRateCorrection);

/// \brief Generates a command to read the Reference Vector Configuration register on a VectorNav sensor.
///
/// \param[in] errorDetectionMode The type of error-detection to use in generating the command.
Expand Down Expand Up @@ -1794,6 +1872,15 @@ struct vn_proglib_DLLEXPORT Packet
/// \param[out] gyroLimit The register's GyroLimit field.
void parseFilterBasicControl(uint8_t* magMode, uint8_t* extMagMode, uint8_t* extAccMode, uint8_t* extGyroMode, vn::math::vec3f* gyroLimit);

// Added by jesperh 2021-02-09
void parseHeaveConfiguration(
float* initialWavePeriod,
float* initialWaveAmplitude,
float* maxWavePeriod,
float* minWaveAmplitude,
float* delayedHeaveCutoffFreq,
float* heaveCutoffFreq,
float* heaveRateCutoffFreq);
/// \brief Parses a response from reading the VPE Basic Control register.
///
/// \param[out] enable The register's Enable field.
Expand Down Expand Up @@ -1893,12 +1980,20 @@ struct vn_proglib_DLLEXPORT Packet
/// \param[out] pressure The register's Pressure field.
void parseImuMeasurements(vn::math::vec3f* mag, vn::math::vec3f* accel, vn::math::vec3f* gyro, float* temp, float* pressure);

/// \brief Parses a response from reading the GPS Configuration register.
/// \brief Parses a response from reading the GPS Configuration register (deprecated).
///
/// \param[out] mode The register's Mode field.
/// \param[out] ppsSource The register's PpsSource field.
void parseGpsConfiguration(uint8_t* mode, uint8_t* ppsSource);

/// \brief Parses a response from reading the GPS Configuration register.
///
/// \param[out] mode The register's Mode field.
/// \param[out] ppsSource The register's PpsSource field.
/// \param[out] rate The register's Rate field.
/// \param[out] antPow The register's AntPower field.
void parseGpsConfiguration(uint8_t* mode, uint8_t* ppsSource, uint8_t* rate, uint8_t* antPow);

/// \brief Parses a response from reading the GPS Antenna Offset register.
///
/// \param[out] position The register's Position field.
Expand Down Expand Up @@ -2020,13 +2115,21 @@ struct vn_proglib_DLLEXPORT Packet
/// \param[out] deltaVelocity The register's DeltaVelocity field.
void parseDeltaThetaAndDeltaVelocity(float* deltaTime, vn::math::vec3f* deltaTheta, vn::math::vec3f* deltaVelocity);

/// \brief Parses a response from reading the Delta Theta and Delta Velocity Configuration register.
/// \brief Parses a response from reading the Delta Theta and Delta Velocity Configuration register (deprecated).
///
/// \param[out] integrationFrame The register's IntegrationFrame field.
/// \param[out] gyroCompensation The register's GyroCompensation field.
/// \param[out] accelCompensation The register's AccelCompensation field.
void parseDeltaThetaAndDeltaVelocityConfiguration(uint8_t* integrationFrame, uint8_t* gyroCompensation, uint8_t* accelCompensation);

/// \brief Parses a response from reading the Delta Theta and Delta Velocity Configuration register.
///
/// \param[out] integrationFrame The register's IntegrationFrame field.
/// \param[out] gyroCompensation The register's GyroCompensation field.
/// \param[out] accelCompensation The register's AccelCompensation field.
/// \param[out] earthRateCorrection The register's EarthRateCorrection field.
void parseDeltaThetaAndDeltaVelocityConfiguration(uint8_t* integrationFrame, uint8_t* gyroCompensation, uint8_t* accelCompensation, uint8_t* earthRateCorrection);

/// \brief Parses a response from reading the Reference Vector Configuration register.
///
/// \param[out] useMagModel The register's UseMagModel field.
Expand Down
Loading