Skip to content

Commit a9d5c21

Browse files
author
Gabriel Alcantara Costa Silva
committed
add service to reset odometry
1 parent 9bbdedd commit a9d5c21

File tree

4 files changed

+42
-0
lines changed

4 files changed

+42
-0
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h

+7
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@
5353
#include <realtime_tools/realtime_buffer.h>
5454
#include <realtime_tools/realtime_publisher.h>
5555
#include <tf/tfMessage.h>
56+
#include <std_srvs/Trigger.h>
5657

5758
namespace diff_drive_controller{
5859

@@ -142,6 +143,7 @@ namespace diff_drive_controller{
142143
/// Odometry related:
143144
std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
144145
std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
146+
ros::ServiceServer reset_odometry_srv_;
145147
Odometry odometry_;
146148

147149
/// Controller state publisher
@@ -249,6 +251,11 @@ namespace diff_drive_controller{
249251
*/
250252
void cmdVelCallback(const geometry_msgs::Twist& command);
251253

254+
/**
255+
* \brief Reset Odometry internal state callback
256+
*/
257+
bool resetOdometryCallback(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &res);
258+
252259
/**
253260
* \brief Get the wheel names from a wheel param
254261
* \param [in] controller_nh Controller node handler

diff_drive_controller/include/diff_drive_controller/odometry.h

+7
Original file line numberDiff line numberDiff line change
@@ -153,6 +153,11 @@ namespace diff_drive_controller
153153
*/
154154
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
155155

156+
/**
157+
* \brief Reset Odometry internal state
158+
*/
159+
void resetInternalState();
160+
156161
private:
157162

158163
/// Rolling mean accumulator and window:
@@ -199,6 +204,8 @@ namespace diff_drive_controller
199204
double left_wheel_old_pos_;
200205
double right_wheel_old_pos_;
201206

207+
bool first_data_;
208+
202209
/// Rolling mean accumulators for the linar and angular velocities:
203210
size_t velocity_rolling_window_size_;
204211
RollingMeanAcc linear_acc_;

diff_drive_controller/src/diff_drive_controller.cpp

+9
Original file line numberDiff line numberDiff line change
@@ -353,6 +353,7 @@ namespace diff_drive_controller{
353353
}
354354

355355
sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this);
356+
reset_odometry_srv_ = controller_nh.advertiseService("/reset_odometry", &DiffDriveController::resetOdometryCallback, this);
356357

357358
// Initialize dynamic parameters
358359
DynamicParams dynamic_params;
@@ -831,4 +832,12 @@ namespace diff_drive_controller{
831832
}
832833
}
833834

835+
bool DiffDriveController::resetOdometryCallback(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &res)
836+
{
837+
brake();
838+
odometry_.resetInternalState();
839+
res.success = true;
840+
return true;
841+
}
842+
834843
} // namespace diff_drive_controller

diff_drive_controller/src/odometry.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ namespace diff_drive_controller
5959
, right_wheel_radius_(0.0)
6060
, left_wheel_old_pos_(0.0)
6161
, right_wheel_old_pos_(0.0)
62+
, first_data_(true)
6263
, velocity_rolling_window_size_(velocity_rolling_window_size)
6364
, linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
6465
, angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
@@ -75,6 +76,15 @@ namespace diff_drive_controller
7576

7677
bool Odometry::update(double left_pos, double right_pos, const ros::Time &time)
7778
{
79+
if(first_data_)
80+
{
81+
left_wheel_old_pos_ = left_pos * left_wheel_radius_;
82+
right_wheel_old_pos_ = right_pos * right_wheel_radius_;
83+
timestamp_ = time;
84+
first_data_ = false;
85+
return true;
86+
}
87+
7888
/// Get current wheel joint positions:
7989
const double left_wheel_cur_pos = left_pos * left_wheel_radius_;
8090
const double right_wheel_cur_pos = right_pos * right_wheel_radius_;
@@ -173,4 +183,13 @@ namespace diff_drive_controller
173183
angular_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_);
174184
}
175185

186+
void Odometry::resetInternalState()
187+
{
188+
resetAccumulators();
189+
x_ = 0.0;
190+
y_ = 0.0;
191+
heading_ = 0.0;
192+
first_data_ = true;
193+
}
194+
176195
} // namespace diff_drive_controller

0 commit comments

Comments
 (0)