Multi-robot Playground
AverageVelocityEstimatorNode.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, Alysson Ribeiro da Silva
3  * All rights reserved.
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  *
8  * 1. Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. All advertising materials mentioning features or use of this software must
16  * display the following acknowledgement:
17  * This product includes software developed by Alysson Ribeiro da Silva.
18  *
19  * 4. Neither the name of the copyright holder nor the names of its
20  * contributors may be used to endorse or promote products derived from
21  * this software without specific prior written permission.
22  *
23  * 5. The source and the binary form, and any modifications made to them
24  * may not be used for the purpose of training or improving machine learning
25  * algorithms, including but not limited to artificial intelligence, natural
26  * language processing, or data mining. This condition applies to any derivatives,
27  * modifications, or updates based on the Software code. Any usage of the source
28  * or the binary form in an AI-training dataset is considered a breach of
29  * this License.
30  *
31  * THIS SOFTWARE IS PROVIDED BY COPYRIGHT HOLDER "AS IS" AND ANY EXPRESS OR
32  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
33  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
34  * EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
35  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
36  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
37  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
38  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
39  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
40  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
41 */
42 
43 /*
44  * Ros and system
45  */
46 #include <deque>
47 #include <string.h>
48 #include "ros/ros.h"
49 #include "tf/tf.h"
50 
51 /*
52  * Messages
53  */
54 #include "std_msgs/Float32.h"
55 #include "geometry_msgs/Pose.h"
56 #include "multirobotsimulations/CustomPose.h"
57 
58 /*
59  * Helpers
60  */
61 #include "Common.h"
62 
63 /*
64  * AverageVelocityEstimatorNode class
65  */
67  public:
70 
71  private:
72  double ComputeAverageVelocity(std::deque<double>& speedArray);
73  void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg);
74  void Update();
75 
76  /*
77  * Control variables
78  */
79  int aId;
81  int aCount;
83  double aRate;
84  std::string aNamespace;
85  tf::Vector3 aLastWorldPos;
86  tf::Vector3 aWorldPos;
87 
88  /*
89  * Routines
90  */
91  std::vector<ros::Timer> aTimers;
92 
93  /*
94  * Subscribers
95  */
96  std::vector<ros::Subscriber> aSubscribers;
97 
98  /*
99  * Advertisers
100  */
102 
103  /*
104  * Messages
105  */
106  std_msgs::Float32 aAverageVelocityMsg;
107 
108  /*
109  * Helpers
110  */
111  std::deque<double> aVelocityArray;
112 };
AverageVelocityEstimatorNode::~AverageVelocityEstimatorNode
~AverageVelocityEstimatorNode()
AverageVelocityEstimatorNode::aAverageVelocityPublisher
ros::Publisher aAverageVelocityPublisher
Definition: AverageVelocityEstimatorNode.h:101
AverageVelocityEstimatorNode::ComputeAverageVelocity
double ComputeAverageVelocity(std::deque< double > &speedArray)
AverageVelocityEstimatorNode::aRate
double aRate
Definition: AverageVelocityEstimatorNode.h:83
AverageVelocityEstimatorNode::aSubscribers
std::vector< ros::Subscriber > aSubscribers
Definition: AverageVelocityEstimatorNode.h:96
AverageVelocityEstimatorNode::aTimers
std::vector< ros::Timer > aTimers
Definition: AverageVelocityEstimatorNode.h:91
AverageVelocityEstimatorNode
Definition: AverageVelocityEstimatorNode.h:66
AverageVelocityEstimatorNode::aReceivedPosition
bool aReceivedPosition
Definition: AverageVelocityEstimatorNode.h:82
AverageVelocityEstimatorNode::aId
int aId
Definition: AverageVelocityEstimatorNode.h:79
AverageVelocityEstimatorNode::aQueueSize
int aQueueSize
Definition: AverageVelocityEstimatorNode.h:80
AverageVelocityEstimatorNode::Update
void Update()
AverageVelocityEstimatorNode::WorldPoseCallback
void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg)
AverageVelocityEstimatorNode::aAverageVelocityMsg
std_msgs::Float32 aAverageVelocityMsg
Definition: AverageVelocityEstimatorNode.h:106
AverageVelocityEstimatorNode::aLastWorldPos
tf::Vector3 aLastWorldPos
Definition: AverageVelocityEstimatorNode.h:85
AverageVelocityEstimatorNode::aNamespace
std::string aNamespace
Definition: AverageVelocityEstimatorNode.h:84
Common.h
AverageVelocityEstimatorNode::aVelocityArray
std::deque< double > aVelocityArray
Definition: AverageVelocityEstimatorNode.h:111
AverageVelocityEstimatorNode::aWorldPos
tf::Vector3 aWorldPos
Definition: AverageVelocityEstimatorNode.h:86
AverageVelocityEstimatorNode::aCount
int aCount
Definition: AverageVelocityEstimatorNode.h:81
AverageVelocityEstimatorNode::AverageVelocityEstimatorNode
AverageVelocityEstimatorNode()