Skip to content

Commit cf0236d

Browse files
author
plnegre
committed
tf_filter added
1 parent 9e5d8fc commit cf0236d

File tree

2 files changed

+230
-0
lines changed

2 files changed

+230
-0
lines changed

tf_tools/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@ catkin_package()
1010
include_directories(${catkin_INCLUDE_DIRS})
1111

1212
add_executable(tf_logger src/tf_logger.cpp)
13+
add_executable(tf_filter src/tf_filter.cpp)
1314

1415
target_link_libraries(tf_logger ${catkin_LIBRARIES})
16+
target_link_libraries(tf_filter ${catkin_LIBRARIES})
1517

tf_tools/src/tf_filter.cpp

Lines changed: 228 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,228 @@
1+
/// Copyright (c) 2012,
2+
/// Systems, Robotics and Vision Group
3+
/// University of the Balearican Islands
4+
/// All rights reserved.
5+
///
6+
/// Redistribution and use in source and binary forms, with or without
7+
/// modification, are permitted provided that the following conditions are met:
8+
/// * Redistributions of source code must retain the above copyright
9+
/// notice, this list of conditions and the following disclaimer.
10+
/// * Redistributions in binary form must reproduce the above copyright
11+
/// notice, this list of conditions and the following disclaimer in the
12+
/// documentation and/or other materials provided with the distribution.
13+
/// * Neither the name of Systems, Robotics and Vision Group, University of
14+
/// the Balearican Islands nor the names of its contributors may be used
15+
/// to endorse or promote products derived from this software without
16+
/// specific prior written permission.
17+
///
18+
/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
/// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
/// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
/// ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
22+
/// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
23+
/// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24+
/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
25+
/// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
26+
/// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
27+
/// THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28+
29+
#include <ros/ros.h>
30+
#include <tf/transform_listener.h>
31+
#include <tf/transform_broadcaster.h>
32+
#include <string>
33+
#include <iostream>
34+
35+
std::ostream& operator<<(std::ostream& os, const tf::Transform& transform)
36+
{
37+
using std::setw;
38+
tf::Vector3 origin = transform.getOrigin();
39+
tf::Quaternion quat = transform.getRotation();
40+
os << setw(10) << origin.x() << " " << setw(10) << origin.y() << " " << setw(10) << origin.z() << " ";
41+
os << setw(10) << quat.x() << " " << setw(10) << quat.y() << " " << setw(10) << quat.z() << " " << setw(10) << quat.w();
42+
return os;
43+
}
44+
45+
void printHeader(std::ostream& os, const std::string& frame_id)
46+
{
47+
os << frame_id << ".x " << frame_id << ".y " << frame_id << ".z "
48+
<< frame_id << ".qx " << frame_id << ".qy " << frame_id << ".qz " << frame_id << ".qw ";
49+
}
50+
51+
int main(int argc, char** argv)
52+
{
53+
ros::init(argc, argv, "tf_filter");
54+
55+
ros::NodeHandle nh;
56+
ros::NodeHandle nhp("~");
57+
58+
std::string reference_frame_id;
59+
std::string child_frame_id;
60+
double frequency, ramp_wwf;
61+
int num_samples_wwf, wwf_index;
62+
bool full_arrays = false;
63+
64+
nhp.param("reference_frame_id", reference_frame_id, std::string("/base_link"));
65+
nhp.param("child_frame_id", child_frame_id, std::string("/camera"));
66+
nhp.param("frequency", frequency, 100.0);
67+
68+
// Use Weighted Window Filter
69+
nhp.param("ramp_wwf", ramp_wwf, 0.5);
70+
nhp.param("num_samples_wwf", num_samples_wwf, 10);
71+
72+
ROS_INFO("TF Filter initiated.\n\tPARAMETERS: \
73+
\n\t * Reference frame ID: %s \
74+
\n\t * Child frame ID: %s \
75+
\n\t * Frequency: %f \
76+
\n\t * Ramp WWF: %f \
77+
\n\t * Num samples WWF: %d",
78+
reference_frame_id.c_str(),
79+
child_frame_id.c_str(),
80+
frequency,
81+
ramp_wwf,
82+
num_samples_wwf);
83+
84+
double * x_array, * y_array, * z_array;
85+
double * sR_array, * cR_array, * sP_array, * cP_array, * sY_array, * cY_array;
86+
double * t_array, * w_array;
87+
88+
//fill circular arrays with zeros
89+
wwf_index = 0;
90+
x_array = new double[num_samples_wwf];
91+
y_array = new double[num_samples_wwf];
92+
z_array = new double[num_samples_wwf];
93+
sR_array = new double[num_samples_wwf]; // sin(roll) array
94+
cR_array = new double[num_samples_wwf]; // cos(roll) array
95+
sP_array = new double[num_samples_wwf]; // sin(pitch) array
96+
cP_array = new double[num_samples_wwf]; // cos(pitch) array
97+
sY_array = new double[num_samples_wwf]; // sin(yaw) array
98+
cY_array = new double[num_samples_wwf]; // cos(yaw) array
99+
t_array = new double[num_samples_wwf]; //times used for the ramp
100+
w_array = new double[num_samples_wwf]; //weights
101+
for(int i = 0; i< num_samples_wwf; i++){
102+
x_array[i] = 0.0;
103+
y_array[i] = 0.0;
104+
z_array[i] = 0.0;
105+
sR_array[i] = 0.0;
106+
cR_array[i] = 0.0;
107+
sP_array[i] = 0.0;
108+
cP_array[i] = 0.0;
109+
sY_array[i] = 0.0;
110+
cY_array[i] = 0.0;
111+
t_array[i] = 0.0;
112+
w_array[i] = 0.0;
113+
}
114+
115+
tf::TransformListener listener;
116+
tf::TransformBroadcaster broadcaster;
117+
118+
ros::Rate rate(frequency);
119+
while (ros::ok())
120+
{
121+
rate.sleep(); //TODO: here or at the end?
122+
123+
// Wait for clock
124+
if (!ros::Time::isValid()) continue;
125+
ros::Time requested_time = ros::Time(0); //(ros::Time::now() - ros::Duration(2 / frequency));
126+
tf::StampedTransform transform;
127+
try
128+
{
129+
// first look up transform, this could throw exceptions
130+
ros::Duration timeout(2 / frequency);
131+
ros::Duration polling_sleep_duration(0.5 / frequency);
132+
listener.waitForTransform(
133+
reference_frame_id,
134+
child_frame_id,
135+
requested_time,
136+
timeout,
137+
polling_sleep_duration);
138+
listener.lookupTransform(
139+
reference_frame_id,
140+
child_frame_id,
141+
requested_time,
142+
transform);
143+
144+
ROS_DEBUG_STREAM("Received transform: " << transform);
145+
ROS_DEBUG_STREAM("With frame_id: " << transform.frame_id_ << " and child_id " << transform.child_frame_id_);
146+
147+
// get position and orientation
148+
double roll, pitch, yaw;
149+
tf::Matrix3x3 rotm(transform.getRotation());
150+
rotm.getRPY(roll, pitch, yaw);
151+
152+
x_array[wwf_index] = transform.getOrigin().x();
153+
y_array[wwf_index] = transform.getOrigin().y();
154+
z_array[wwf_index] = transform.getOrigin().z();
155+
sR_array[wwf_index] = sin(roll);
156+
cR_array[wwf_index] = cos(roll);
157+
sP_array[wwf_index] = sin(pitch);
158+
cP_array[wwf_index] = cos(pitch);
159+
sY_array[wwf_index] = sin(yaw);
160+
cY_array[wwf_index] = cos(yaw);
161+
162+
// save ros time into circular array
163+
ros::Time now = transform.stamp_;
164+
t_array[wwf_index] = now.toSec();
165+
166+
// compute weights for every element of the arrays
167+
// and leave weights of empty cells to zero
168+
int num_elem = num_samples_wwf;
169+
if(!full_arrays){
170+
num_elem = wwf_index + 1;
171+
}
172+
double w_total = 0.0;
173+
for(int i = 0; i < num_elem; i++){
174+
double t_aux = t_array[i] - t_array[wwf_index]; //<=0
175+
w_array[i] = std::max(0.0,ramp_wwf*t_aux + 1);
176+
w_total += w_array[i];
177+
}
178+
179+
180+
double w_aux;
181+
double x, y, z, sinR, cosR, sinP, cosP, sinY, cosY;
182+
x = y = z = sinR = cosR = sinP = cosP = sinY = cosY = 0.0;
183+
184+
// Compute final tf
185+
for(int i = 0; i < num_elem; i++){
186+
w_aux = w_array[i]/w_total;
187+
x += w_aux * x_array[i];
188+
y += w_aux * y_array[i];
189+
z += w_aux * z_array[i];
190+
sinR += w_aux * sR_array[i];
191+
cosR += w_aux * cR_array[i];
192+
sinP += w_aux * sP_array[i];
193+
cosP += w_aux * cP_array[i];
194+
sinY += w_aux * sY_array[i];
195+
cosY += w_aux * cY_array[i];
196+
}
197+
198+
tf::Vector3 orig(x,y,z);
199+
200+
roll = atan2(sinR, cosR);
201+
pitch = atan2(sinP, cosP);
202+
yaw = atan2(sinY, cosY);
203+
204+
tf::Quaternion quat;
205+
quat.setRPY(roll, pitch, yaw);
206+
207+
transform.setOrigin(orig);
208+
transform.setRotation(quat);
209+
210+
// Set the output stamped transform and send it
211+
transform.child_frame_id_ = transform.child_frame_id_ + "_filtered";
212+
broadcaster.sendTransform(transform);
213+
214+
// Increment the counter
215+
wwf_index++;
216+
if (wwf_index==num_samples_wwf){
217+
full_arrays = true;
218+
wwf_index = 0;
219+
}
220+
}
221+
catch (const tf::TransformException& e)
222+
{
223+
std::cerr << "TransformException caught: " << e.what() << std::endl;
224+
}
225+
}
226+
return 0;
227+
}
228+

0 commit comments

Comments
 (0)