include
joint_states_settler
joint_states_settler.h
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2009, Willow Garage, Inc.
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the Willow Garage nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
36
37
#ifndef JOINT_STATES_SETTLER_JOINT_STATES_SETTLER_H_
38
#define JOINT_STATES_SETTLER_JOINT_STATES_SETTLER_H_
39
40
#include <boost/shared_ptr.hpp>
41
42
#include <calibration_msgs/Interval.h>
43
#include <sensor_msgs/JointState.h>
44
45
#include <
settlerlib/sorted_deque.h
>
46
47
#include <joint_states_settler/ConfigGoal.h>
48
49
#include "
joint_states_deflater.h
"
50
#include "
deflated_joint_states.h
"
51
52
namespace
joint_states_settler
53
{
54
55
class
JointStatesSettler
56
{
57
public
:
58
JointStatesSettler
();
59
60
bool
configure
(
const
joint_states_settler::ConfigGoal& goal);
61
62
calibration_msgs::Interval
add
(
const
sensor_msgs::JointStateConstPtr msg);
63
sensor_msgs::JointState
pruneJointState
(
const
sensor_msgs::JointStateConstPtr msg);
64
65
private
:
66
bool
configured_
;
67
JointStatesDeflater
deflater_
;
68
std::vector<double>
tol_
;
69
ros::Duration
max_step_
;
70
71
typedef
settlerlib::SortedDeque< boost::shared_ptr<const DeflatedJointStates>
>
DeflatedMsgCache
;
72
typedef
settlerlib::SortedDeque<settlerlib::DeflatedConstPtr>
DeflatedCache
;
73
DeflatedMsgCache
cache_
;
74
75
};
76
77
}
78
79
#endif
joint_states_deflater.h
joint_states_settler::JointStatesSettler::deflater_
JointStatesDeflater deflater_
Definition:
joint_states_settler.h:131
settlerlib::SortedDeque
deflated_joint_states.h
joint_states_settler::JointStatesSettler::configured_
bool configured_
Definition:
joint_states_settler.h:130
joint_states_settler::JointStatesSettler::DeflatedMsgCache
settlerlib::SortedDeque< boost::shared_ptr< const DeflatedJointStates > > DeflatedMsgCache
Definition:
joint_states_settler.h:135
sorted_deque.h
joint_states_settler::JointStatesSettler::JointStatesSettler
JointStatesSettler()
Definition:
joint_states_settler.cpp:44
joint_states_settler::JointStatesSettler::cache_
DeflatedMsgCache cache_
Definition:
joint_states_settler.h:137
joint_states_settler::JointStatesSettler::configure
bool configure(const joint_states_settler::ConfigGoal &goal)
Definition:
joint_states_settler.cpp:49
joint_states_settler::JointStatesSettler::DeflatedCache
settlerlib::SortedDeque< settlerlib::DeflatedConstPtr > DeflatedCache
Definition:
joint_states_settler.h:136
joint_states_settler::JointStatesSettler::add
calibration_msgs::Interval add(const sensor_msgs::JointStateConstPtr msg)
Definition:
joint_states_settler.cpp:76
joint_states_settler::JointStatesSettler::tol_
std::vector< double > tol_
Definition:
joint_states_settler.h:132
joint_states_settler::JointStatesSettler::max_step_
ros::Duration max_step_
Definition:
joint_states_settler.h:133
ros::Duration
joint_states_settler::JointStatesSettler::pruneJointState
sensor_msgs::JointState pruneJointState(const sensor_msgs::JointStateConstPtr msg)
Definition:
joint_states_settler.cpp:95
joint_states_settler
Definition:
deflated_joint_states.h:41
joint_states_settler
Author(s): Vijay Pradeep, Eitan Marder-Eppstein
autogenerated on Tue Mar 1 2022 23:58:53