src
align_handler.cpp
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
26
#include <
novatel_oem7_driver/oem7_message_handler_if.hpp
>
27
28
29
#include <
ros/ros.h
>
30
31
#include <
novatel_oem7_driver/oem7_ros_messages.hpp
>
32
#include <novatel_oem7_msgs/HEADING2.h>
33
34
#include <
oem7_ros_publisher.hpp
>
35
36
37
namespace
novatel_oem7_driver
38
{
39
40
/***
41
* Handler of ALIGH-related messages
42
*/
43
class
ALIGNHandler
:
public
Oem7MessageHandlerIf
44
{
45
Oem7RosPublisher
HEADING2_pub_
;
46
47
void
publishHEADING2
(
48
Oem7RawMessageIf::ConstPtr msg)
49
{
50
boost::shared_ptr<novatel_oem7_msgs::HEADING2>
heading2;
51
MakeROSMessage
(msg, heading2);
52
HEADING2_pub_
.
publish
(heading2);
53
}
54
55
public
:
56
ALIGNHandler
()
57
{
58
}
59
60
~ALIGNHandler
()
61
{
62
}
63
64
void
initialize
(
ros::NodeHandle
& nh)
65
{
66
HEADING2_pub_
.
setup
<novatel_oem7_msgs::HEADING2>(
"HEADING2"
, nh);
67
}
68
69
const
std::vector<int>&
getMessageIds
()
70
{
71
static
const
std::vector<int> MSG_IDS({
HEADING2_OEM7_MSGID
});
72
return
MSG_IDS;
73
}
74
75
void
handleMsg
(Oem7RawMessageIf::ConstPtr msg)
76
{
77
ROS_DEBUG_STREAM
(
"ALIGN < [id= "
<< msg->getMessageId() <<
"]"
);
78
79
publishHEADING2
(msg);
80
}
81
};
82
}
83
84
#include <
pluginlib/class_list_macros.h
>
85
PLUGINLIB_EXPORT_CLASS
(
novatel_oem7_driver::ALIGNHandler
,
novatel_oem7_driver::Oem7MessageHandlerIf
)
novatel_oem7_driver::Oem7RosPublisher::setup
void setup(const std::string &name, ros::NodeHandle &nh)
Definition:
oem7_ros_publisher.hpp:47
novatel_oem7_driver::ALIGNHandler::HEADING2_pub_
Oem7RosPublisher HEADING2_pub_
Definition:
align_handler.cpp:47
boost::shared_ptr
ros.h
oem7_ros_messages.hpp
novatel_oem7_driver::ALIGNHandler
Definition:
align_handler.cpp:43
novatel_oem7_driver::ALIGNHandler::getMessageIds
const std::vector< int > & getMessageIds()
Definition:
align_handler.cpp:71
novatel_oem7_driver::ALIGNHandler::ALIGNHandler
ALIGNHandler()
Definition:
align_handler.cpp:58
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
novatel_oem7_driver::HEADING2_OEM7_MSGID
const int HEADING2_OEM7_MSGID
Definition:
oem7_message_ids.h:43
class_list_macros.h
novatel_oem7_driver::ALIGNHandler::~ALIGNHandler
~ALIGNHandler()
Definition:
align_handler.cpp:62
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
novatel_oem7_driver::Oem7RosPublisher::publish
void publish(boost::shared_ptr< M > &msg)
Definition:
oem7_ros_publisher.hpp:92
oem7_message_handler_if.hpp
novatel_oem7_driver::ALIGNHandler::publishHEADING2
void publishHEADING2(Oem7RawMessageIf::ConstPtr msg)
Definition:
align_handler.cpp:49
novatel_oem7_driver::ALIGNHandler::handleMsg
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
Definition:
align_handler.cpp:77
novatel_oem7_driver::MakeROSMessage
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
novatel_oem7_driver::Oem7RosPublisher
Definition:
oem7_ros_publisher.hpp:38
novatel_oem7_driver::ALIGNHandler::initialize
void initialize(ros::NodeHandle &nh)
Definition:
align_handler.cpp:66
novatel_oem7_driver::Oem7MessageHandlerIf
Definition:
oem7_message_handler_if.hpp:41
novatel_oem7_driver
Definition:
oem7_imu.hpp:25
ros::NodeHandle
oem7_ros_publisher.hpp
novatel_oem7_driver
Author(s):
autogenerated on Sat Feb 3 2024 03:51:34