Main Page
Classes
Class List
Class Members
All
Functions
Variables
Files
File List
File Members
All
Functions
Macros
src
flat_world_imu_node.cpp
Go to the documentation of this file.
1
/*
2
* Copyright 2016 The Cartographer Authors
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
*
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
#include <
turtlebot3_slam/flat_world_imu_node.h
>
18
19
FlatWorldImuNode::FlatWorldImuNode
()
20
{
21
bool
init_result =
init
();
22
ROS_ASSERT
(init_result);
23
}
24
25
FlatWorldImuNode::~FlatWorldImuNode
()
26
{
27
}
28
29
bool
FlatWorldImuNode::init
()
30
{
31
publisher_
=
nh_
.
advertise
<sensor_msgs::Imu>(
"imu_out"
, 10);
32
subscriber_
=
nh_
.
subscribe
(
"imu_in"
, 150, &
FlatWorldImuNode::msgCallback
,
this
);
33
34
return
true
;
35
}
36
37
void
FlatWorldImuNode::msgCallback
(
const
sensor_msgs::ImuConstPtr imu_in)
38
{
39
if
(
last_published_time_
.
isZero
() || imu_in->header.stamp >
last_published_time_
)
40
{
41
last_published_time_
= imu_in->header.stamp;
42
sensor_msgs::Imu imu_out = *imu_in;
43
imu_out.linear_acceleration.x = 0.0;
44
imu_out.linear_acceleration.y = 0.0;
45
imu_out.linear_acceleration.z =
GRAVITY
;
46
publisher_
.
publish
(imu_out);
47
}
48
}
49
50
int
main
(
int
argc,
char
* argv[])
51
{
52
ros::init
(argc,
argv
,
"flat_world_imu_node"
);
53
54
FlatWorldImuNode
flat_world_imu_node;
55
56
ros::spin
();
57
58
return
0;
59
}
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
FlatWorldImuNode::init
bool init()
Definition:
flat_world_imu_node.cpp:29
FlatWorldImuNode::FlatWorldImuNode
FlatWorldImuNode()
Definition:
flat_world_imu_node.cpp:19
FlatWorldImuNode
Definition:
flat_world_imu_node.h:25
FlatWorldImuNode::msgCallback
void msgCallback(const sensor_msgs::ImuConstPtr imu_in)
Definition:
flat_world_imu_node.cpp:37
FlatWorldImuNode::nh_
ros::NodeHandle nh_
Definition:
flat_world_imu_node.h:33
FlatWorldImuNode::publisher_
ros::Publisher publisher_
Definition:
flat_world_imu_node.h:35
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
flat_world_imu_node.h
main
int main(int argc, char *argv[])
Definition:
flat_world_imu_node.cpp:50
argv
argv
FlatWorldImuNode::subscriber_
ros::Subscriber subscriber_
Definition:
flat_world_imu_node.h:36
TimeBase< Time, Duration >::isZero
bool isZero() const
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
FlatWorldImuNode::last_published_time_
ros::Time last_published_time_
Definition:
flat_world_imu_node.h:34
ros::spin
ROSCPP_DECL void spin()
FlatWorldImuNode::~FlatWorldImuNode
~FlatWorldImuNode()
Definition:
flat_world_imu_node.cpp:25
ROS_ASSERT
#define ROS_ASSERT(cond)
GRAVITY
#define GRAVITY
Definition:
flat_world_imu_node.h:23
turtlebot3_slam
Author(s): Pyo
, Darby Lim
, Gilbert
, Leon Jung
autogenerated on Wed Mar 2 2022 01:08:44