Skip to content

Commit 290e8f9

Browse files
author
Enrique Fernández Perdomo
committed
Merge pull request #32 from clearpathrobotics/compute_twist_on_publish
Compute twist on publish
2 parents 38c99db + 088839f commit 290e8f9

File tree

9 files changed

+1152
-122
lines changed

9 files changed

+1152
-122
lines changed

diff_drive_controller/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,9 @@ if (CATKIN_ENABLE_TESTING)
8383
${catkin_INCLUDE_DIRS}
8484
${EIGEN_INCLUDE_DIRS})
8585

86+
catkin_add_gtest(odometry_test test/odometry_test.cpp)
87+
target_link_libraries(odometry_test ${PROJECT_NAME})
88+
8689
add_executable(diffbot test/diffbot.cpp)
8790
target_link_libraries(diffbot ${catkin_LIBRARIES})
8891

diff_drive_controller/include/diff_drive_controller/odometry.h

Lines changed: 32 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,18 @@ namespace diff_drive_controller
134134
bool updateOpenLoop(const double linear, const double angular,
135135
const ros::Time &time);
136136

137+
/**
138+
* \brief Update the odometry twist with the (internal) incremental pose,
139+
* since the last update/call to this method; this resets the (internal)
140+
* incremental pose
141+
* \param[in] time Current time, used to compute the time step/increment,
142+
* which is used to divide the (internal) incremental pose
143+
* by dt and obtain the twist
144+
* \return true if twist is actually updated; it won't be updated if the
145+
* time step/increment is very small, to avoid division by zero
146+
*/
147+
bool updateTwist(const ros::Time& time);
148+
137149
/**
138150
* \brief Heading getter
139151
* \return Heading [rad]
@@ -276,17 +288,12 @@ namespace diff_drive_controller
276288
const double v_l, const double v_r, const ros::Time& time);
277289

278290
/**
279-
* \brief Update the odometry twist with the previous and current odometry
280-
* pose
281-
* \param[in] p0 Previous odometry pose
282-
* \param[in] p1 Current odometry pose
283-
* \param[in] v_l Left wheel velocity [rad/s]
284-
* \param[in] v_r Right wheel velocity [rad/s]
285-
* \param[in] time Current time
286-
* \return true if the odometry twist is actually updated
291+
* \brief Updates the (internal) incremental odometry with latest left and
292+
* right wheel position increments
293+
* \param[in] dp_l Left wheel position increment [rad]
294+
* \param[in] dp_r Right wheel position increment [rad]
287295
*/
288-
bool updateTwist(const SE2& p0, const SE2& p1,
289-
const double v_l, const double v_r, const ros::Time& time);
296+
void updateIncrementalPose(const double dp_l, const double dp_r);
290297

291298
/**
292299
* \brief Update the measurement covariance
@@ -303,19 +310,31 @@ namespace diff_drive_controller
303310
/// Current timestamp:
304311
ros::Time timestamp_;
305312

313+
/// Timestamp for last twist computed, ie. since when the (internal)
314+
/// incremental pose has been computed:
315+
ros::Time timestamp_twist_;
316+
306317
/// Current pose:
307318
double x_; // [m]
308319
double y_; // [m]
309320
double heading_; // [rad]
310321

322+
/// Current incremental pose:
323+
double d_x_; // [m]
324+
double d_y_; // [m]
325+
double d_yaw_; // [rad]
326+
311327
/// Current velocity:
312-
double v_x_; // [m/s]
313-
double v_y_; // [m/s]
314-
double v_yaw_; // [rad/s]
328+
double v_x_; // [m/s]
329+
double v_y_; // [m/s]
330+
double v_yaw_; // [rad/s]
315331

316332
/// Pose covariance:
317333
PoseCovariance pose_covariance_;
318334

335+
/// Incremental Pose covariance:
336+
PoseCovariance incremental_pose_covariance_;
337+
319338
/// Twist (and minimum twist) covariance:
320339
TwistCovariance twist_covariance_;
321340
TwistCovariance minimum_twist_covariance_;
Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2016, Clearpath Robotics, 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 PAL Robotics 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+
35+
/*
36+
* Author: Enrique Fernández
37+
*/
38+
39+
#ifndef RIGID_BODY_MOTION_H_
40+
#define RIGID_BODY_MOTION_H_
41+
42+
#include <Eigen/Dense>
43+
44+
#include <limits>
45+
46+
namespace diff_drive_controller
47+
{
48+
49+
/**
50+
* \brief Compute rigid body motion in SE(2) using element-wise equations.
51+
* \param[in, out] x Pose x component
52+
* \param[in, out] y Pose y component
53+
* \param[in, out] yaw Pose yaw component
54+
* \param[in] v_x Velocity/Twist x component
55+
* \param[in] v_y Velocity/Twist y component
56+
* \param[in] v_yaw Velocity/Twist yaw component
57+
* \param[in] dt Time step
58+
*/
59+
static void integrate_motion(double& x, double &y, double &yaw,
60+
const double v_x, const double v_y, const double v_yaw,
61+
const double dt)
62+
{
63+
const double cos_yaw = std::cos(yaw);
64+
const double sin_yaw = std::sin(yaw);
65+
66+
x += (v_x * cos_yaw - v_y * sin_yaw) * dt;
67+
y += (v_x * sin_yaw + v_y * cos_yaw) * dt;
68+
yaw += v_yaw * dt;
69+
}
70+
71+
/**
72+
* \brief Compute rigid body motion in SE(2) using element-wise equations.
73+
* Also computes the Jacobians wrt the pose and the velocity/twist.
74+
* \param[in, out] x Pose x component
75+
* \param[in, out] y Pose y component
76+
* \param[in, out] yaw Pose yaw component
77+
* \param[in] v_x Velocity/Twist x component
78+
* \param[in] v_y Velocity/Twist y component
79+
* \param[in] v_yaw Velocity/Twist yaw component
80+
* \param[in] dt Time step
81+
*/
82+
static void integrate_motion(double& x, double &y, double &yaw,
83+
const double v_x, const double v_y, const double v_yaw,
84+
const double dt,
85+
Eigen::Matrix3d& J_pose, Eigen::Matrix3d& J_twist)
86+
{
87+
const double cos_yaw = std::cos(yaw);
88+
const double sin_yaw = std::sin(yaw);
89+
90+
x += (v_x * cos_yaw - v_y * sin_yaw) * dt;
91+
y += (v_x * sin_yaw + v_y * cos_yaw) * dt;
92+
yaw += v_yaw * dt;
93+
94+
J_pose << 1.0, 0.0, (-v_x * sin_yaw - v_y * cos_yaw) * dt,
95+
0.0, 1.0, ( v_x * cos_yaw - v_y * sin_yaw) * dt,
96+
0.0, 0.0, 1.0;
97+
98+
J_twist << cos_yaw * dt, -sin_yaw * dt, 0.0,
99+
sin_yaw * dt, cos_yaw * dt, 0.0,
100+
0.0, 0.0, dt;
101+
}
102+
103+
}
104+
105+
#endif /* RIGID_BODY_MOTION_H_ */

diff_drive_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
<!--Tests-->
4747
<build_depend>rostest</build_depend>
4848

49+
<test_depend>gtest</test_depend>
4950
<test_depend>std_srvs</test_depend>
5051
<test_depend>controller_manager</test_depend>
5152
<test_depend>control_toolbox</test_depend>

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -620,6 +620,12 @@ namespace diff_drive_controller
620620
if (last_odom_publish_time_ + publish_period_ < time + half_period &&
621621
odom_pub_->trylock())
622622
{
623+
// Update twist:
624+
// Note that the twist must be computed at the same frequency that it gets
625+
// published, because otherwise the code that uses it cannot apply the
626+
// same period it was used to compute it.
627+
odometry_.updateTwist(time);
628+
623629
last_odom_publish_time_ = time;
624630

625631
// Populate odom message and publish:
@@ -646,6 +652,12 @@ namespace diff_drive_controller
646652
last_odom_tf_publish_time_ + publish_period_ < time + half_period &&
647653
tf_odom_pub_->trylock())
648654
{
655+
// Note that the tf odometry doesn't need the twist, only the pose.
656+
// In the current implementation the pose is computed on its own, ie. w/o
657+
// using the (internal) incremental pose. Therefore, it's always up to
658+
// date with every control cycle and can be published at any rate because
659+
// it doesn't depend on any period.
660+
649661
last_odom_tf_publish_time_ = time;
650662

651663
// Populate tf odometry frame message and publish:

0 commit comments

Comments
 (0)