diff --git a/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h b/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h index 806246418..4b60b6a04 100644 --- a/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h +++ b/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h @@ -52,6 +52,7 @@ #include #include #include +#include #include namespace diff_drive_controller{ @@ -142,6 +143,7 @@ namespace diff_drive_controller{ /// Odometry related: std::shared_ptr > odom_pub_; std::shared_ptr > tf_odom_pub_; + ros::ServiceServer reset_odometry_srv_; Odometry odometry_; /// Controller state publisher @@ -249,6 +251,11 @@ namespace diff_drive_controller{ */ void cmdVelCallback(const geometry_msgs::Twist& command); + /** + * \brief Reset Odometry internal state callback + */ + bool resetOdometryCallback(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &res); + /** * \brief Get the wheel names from a wheel param * \param [in] controller_nh Controller node handler diff --git a/diff_drive_controller/include/diff_drive_controller/odometry.h b/diff_drive_controller/include/diff_drive_controller/odometry.h index 39a5eb820..02983e106 100644 --- a/diff_drive_controller/include/diff_drive_controller/odometry.h +++ b/diff_drive_controller/include/diff_drive_controller/odometry.h @@ -153,6 +153,11 @@ namespace diff_drive_controller */ void setVelocityRollingWindowSize(size_t velocity_rolling_window_size); + /** + * \brief Reset Odometry internal state + */ + void resetInternalState(); + private: /// Rolling mean accumulator and window: @@ -199,6 +204,8 @@ namespace diff_drive_controller double left_wheel_old_pos_; double right_wheel_old_pos_; + bool first_data_; + /// Rolling mean accumulators for the linar and angular velocities: size_t velocity_rolling_window_size_; RollingMeanAcc linear_acc_; diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 60bf846fa..1a52008fc 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -353,6 +353,7 @@ namespace diff_drive_controller{ } sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this); + reset_odometry_srv_ = controller_nh.advertiseService("/reset_odometry", &DiffDriveController::resetOdometryCallback, this); // Initialize dynamic parameters DynamicParams dynamic_params; @@ -831,4 +832,12 @@ namespace diff_drive_controller{ } } + bool DiffDriveController::resetOdometryCallback(std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &res) + { + brake(); + odometry_.resetInternalState(); + res.success = true; + return true; + } + } // namespace diff_drive_controller diff --git a/diff_drive_controller/src/odometry.cpp b/diff_drive_controller/src/odometry.cpp index d086d5ccf..d34cb7222 100644 --- a/diff_drive_controller/src/odometry.cpp +++ b/diff_drive_controller/src/odometry.cpp @@ -59,6 +59,7 @@ namespace diff_drive_controller , right_wheel_radius_(0.0) , left_wheel_old_pos_(0.0) , right_wheel_old_pos_(0.0) + , first_data_(true) , velocity_rolling_window_size_(velocity_rolling_window_size) , linear_acc_(RollingWindow::window_size = velocity_rolling_window_size) , angular_acc_(RollingWindow::window_size = velocity_rolling_window_size) @@ -75,6 +76,15 @@ namespace diff_drive_controller bool Odometry::update(double left_pos, double right_pos, const ros::Time &time) { + if(first_data_) + { + left_wheel_old_pos_ = left_pos * left_wheel_radius_; + right_wheel_old_pos_ = right_pos * right_wheel_radius_; + timestamp_ = time; + first_data_ = false; + return true; + } + /// Get current wheel joint positions: const double left_wheel_cur_pos = left_pos * left_wheel_radius_; const double right_wheel_cur_pos = right_pos * right_wheel_radius_; @@ -173,4 +183,13 @@ namespace diff_drive_controller angular_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_); } + void Odometry::resetInternalState() + { + resetAccumulators(); + x_ = 0.0; + y_ = 0.0; + heading_ = 0.0; + first_data_ = true; + } + } // namespace diff_drive_controller