src
oem7_raw_message_if.hpp
Go to the documentation of this file.
1
//
3
// Copyright (c) 2020 NovAtel Inc.
4
//
5
// Permission is hereby granted, free of charge, to any person obtaining a copy
6
// of this software and associated documentation files (the "Software"), to deal
7
// in the Software without restriction, including without limitation the rights
8
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9
// copies of the Software, and to permit persons to whom the Software is
10
// furnished to do so, subject to the following conditions:
11
//
12
// The above copyright notice and this permission notice shall be included in all
13
// copies or substantial portions of the Software.
14
//
15
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21
// SOFTWARE.
22
//
24
25
#ifndef __OEM7_RAW_MESSAGE_IF_
26
#define __OEM7_RAW_MESSAGE_IF_
27
28
#include <stdint.h>
29
#include <stddef.h>
30
31
#include <boost/shared_ptr.hpp>
32
33
namespace
novatel_oem7
34
{
35
class
Oem7RawMessageIf
36
{
37
public
:
38
39
typedef
boost::shared_ptr<const Oem7RawMessageIf>
ConstPtr
;
40
41
enum
Oem7MessageType
42
{
43
OEM7MSGTYPE_UNKNOWN
,
44
OEM7MSGTYPE_LOG
,
45
OEM7MSGTYPE_RSP
,
46
OOEM7MSGTYPE_CMD
47
};
48
49
enum
Oem7MessageFormat
50
{
51
OEM7MSGFMT_UNKNOWN
,
52
OEM7MSGFMT_BINARY
,
53
OEM7MSGFMT_SHORTBINARY
,
54
OEM7MSGFMT_ASCII
,
55
OEM7MSGFMT_ABASCII
56
};
57
58
virtual
~Oem7RawMessageIf
(){}
59
60
virtual
Oem7MessageType
getMessageType
()
const
= 0;
61
virtual
Oem7MessageFormat
getMessageFormat
()
const
= 0;
62
virtual
int
getMessageId
()
const
= 0;
63
virtual
const
uint8_t*
getMessageData
(
size_t
offset)
const
= 0;
64
virtual
size_t
getMessageDataLength
()
const
= 0;
65
};
66
}
67
68
#endif
novatel_oem7::Oem7RawMessageIf::OEM7MSGFMT_ABASCII
@ OEM7MSGFMT_ABASCII
Definition:
oem7_raw_message_if.hpp:55
novatel_oem7::Oem7RawMessageIf::getMessageId
virtual int getMessageId() const =0
novatel_oem7::Oem7RawMessageIf::ConstPtr
boost::shared_ptr< const Oem7RawMessageIf > ConstPtr
Definition:
oem7_raw_message_if.hpp:39
novatel_oem7::Oem7RawMessageIf::~Oem7RawMessageIf
virtual ~Oem7RawMessageIf()
Definition:
oem7_raw_message_if.hpp:58
novatel_oem7::Oem7RawMessageIf::OEM7MSGFMT_BINARY
@ OEM7MSGFMT_BINARY
Definition:
oem7_raw_message_if.hpp:52
boost::shared_ptr
novatel_oem7::Oem7RawMessageIf::OOEM7MSGTYPE_CMD
@ OOEM7MSGTYPE_CMD
Definition:
oem7_raw_message_if.hpp:46
novatel_oem7::Oem7RawMessageIf::OEM7MSGTYPE_RSP
@ OEM7MSGTYPE_RSP
Definition:
oem7_raw_message_if.hpp:45
novatel_oem7::Oem7RawMessageIf::Oem7MessageFormat
Oem7MessageFormat
Definition:
oem7_raw_message_if.hpp:49
novatel_oem7::Oem7RawMessageIf::Oem7MessageType
Oem7MessageType
Definition:
oem7_raw_message_if.hpp:41
novatel_oem7::Oem7RawMessageIf::getMessageFormat
virtual Oem7MessageFormat getMessageFormat() const =0
novatel_oem7::Oem7RawMessageIf::OEM7MSGFMT_UNKNOWN
@ OEM7MSGFMT_UNKNOWN
Definition:
oem7_raw_message_if.hpp:51
novatel_oem7::Oem7RawMessageIf::OEM7MSGTYPE_LOG
@ OEM7MSGTYPE_LOG
Definition:
oem7_raw_message_if.hpp:44
novatel_oem7::Oem7RawMessageIf::OEM7MSGTYPE_UNKNOWN
@ OEM7MSGTYPE_UNKNOWN
Definition:
oem7_raw_message_if.hpp:43
novatel_oem7::Oem7RawMessageIf::getMessageDataLength
virtual size_t getMessageDataLength() const =0
novatel_oem7::Oem7RawMessageIf::getMessageType
virtual Oem7MessageType getMessageType() const =0
novatel_oem7::Oem7RawMessageIf::OEM7MSGFMT_SHORTBINARY
@ OEM7MSGFMT_SHORTBINARY
Definition:
oem7_raw_message_if.hpp:53
novatel_oem7::Oem7RawMessageIf
Definition:
oem7_raw_message_if.hpp:35
novatel_oem7
Definition:
oem7_message_decoder_lib.cpp:47
novatel_oem7::Oem7RawMessageIf::getMessageData
virtual const uint8_t * getMessageData(size_t offset) const =0
novatel_oem7::Oem7RawMessageIf::OEM7MSGFMT_ASCII
@ OEM7MSGFMT_ASCII
Definition:
oem7_raw_message_if.hpp:54
novatel_oem7_driver
Author(s):
autogenerated on Sat Feb 3 2024 03:51:34