include
imu_sensor_controller
imu_sensor_controller.h
Go to the documentation of this file.
1
// Copyright (C) 2012, hiDOF INC.
3
// Copyright (C) 2013, PAL Robotics S.L.
4
//
5
// Redistribution and use in source and binary forms, with or without
6
// modification, are permitted provided that the following conditions are met:
7
// * Redistributions of source code must retain the above copyright notice,
8
// this list of conditions and the following disclaimer.
9
// * Redistributions in binary form must reproduce the above copyright
10
// notice, this list of conditions and the following disclaimer in the
11
// documentation and/or other materials provided with the distribution.
12
// * Neither the name of PAL Robotics S.L. nor the names of its
13
// contributors may be used to endorse or promote products derived from
14
// this software without specific prior written permission.
15
//
16
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26
// POSSIBILITY OF SUCH DAMAGE.
28
30
31
#pragma once
32
33
34
#include <
controller_interface/controller.h
>
35
#include <
hardware_interface/imu_sensor_interface.h
>
36
#include <
pluginlib/class_list_macros.hpp
>
37
#include <sensor_msgs/Imu.h>
38
#include <
realtime_tools/realtime_publisher.h
>
39
40
namespace
imu_sensor_controller
41
{
42
43
// this controller gets access to the ImuSensorInterface
44
class
ImuSensorController
:
public
controller_interface::Controller
<hardware_interface::ImuSensorInterface>
45
{
46
public
:
47
ImuSensorController
(){}
48
49
virtual
bool
init
(
hardware_interface::ImuSensorInterface
* hw,
ros::NodeHandle
&root_nh,
ros::NodeHandle
& controller_nh);
50
virtual
void
starting
(
const
ros::Time
& time);
51
virtual
void
update
(
const
ros::Time
& time,
const
ros::Duration
&
/*period*/
);
52
virtual
void
stopping
(
const
ros::Time
&
/*time*/
);
53
54
private
:
55
std::vector<hardware_interface::ImuSensorHandle>
sensors_
;
56
typedef
std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::Imu> >
RtPublisherPtr
;
57
std::vector<RtPublisherPtr>
realtime_pubs_
;
58
std::vector<ros::Time>
last_publish_times_
;
59
double
publish_rate_
;
60
};
61
62
}
imu_sensor_controller::ImuSensorController::realtime_pubs_
std::vector< RtPublisherPtr > realtime_pubs_
Definition:
imu_sensor_controller.h:57
realtime_publisher.h
imu_sensor_controller::ImuSensorController::ImuSensorController
ImuSensorController()
Definition:
imu_sensor_controller.h:47
imu_sensor_controller::ImuSensorController::sensors_
std::vector< hardware_interface::ImuSensorHandle > sensors_
Definition:
imu_sensor_controller.h:55
controller_interface::Controller
imu_sensor_interface.h
imu_sensor_controller::ImuSensorController::last_publish_times_
std::vector< ros::Time > last_publish_times_
Definition:
imu_sensor_controller.h:58
controller.h
imu_sensor_controller::ImuSensorController::publish_rate_
double publish_rate_
Definition:
imu_sensor_controller.h:59
hardware_interface::ImuSensorInterface
imu_sensor_controller
Definition:
imu_sensor_controller.h:40
ros::Time
imu_sensor_controller::ImuSensorController::update
virtual void update(const ros::Time &time, const ros::Duration &)
Definition:
imu_sensor_controller.cpp:74
imu_sensor_controller::ImuSensorController
Definition:
imu_sensor_controller.h:44
class_list_macros.hpp
imu_sensor_controller::ImuSensorController::RtPublisherPtr
std::shared_ptr< realtime_tools::RealtimePublisher< sensor_msgs::Imu > > RtPublisherPtr
Definition:
imu_sensor_controller.h:56
ros::Duration
imu_sensor_controller::ImuSensorController::init
virtual bool init(hardware_interface::ImuSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition:
imu_sensor_controller.cpp:39
imu_sensor_controller::ImuSensorController::stopping
virtual void stopping(const ros::Time &)
Definition:
imu_sensor_controller.cpp:190
ros::NodeHandle
imu_sensor_controller::ImuSensorController::starting
virtual void starting(const ros::Time &time)
Definition:
imu_sensor_controller.cpp:66
imu_sensor_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri May 24 2024 02:41:19