From 01e278befbf8be2556b6280b547c990834ebdb4f Mon Sep 17 00:00:00 2001 From: HiepLM Date: Fri, 27 Mar 2026 13:05:23 +0700 Subject: [PATCH] update --- .../Packages/move_base/src/move_base.cpp | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index 3730106..11e92f2 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -976,12 +976,6 @@ bool move_base::MoveBase::moveTo( const robot_geometry_msgs::PoseStamped &goal, robot::log_info("[MoveBase::moveTo] Processing goal through action server..."); as_->processGoal(action_goal); - - setTwistLinear(old_linear_fwd_); - setTwistLinear(old_linear_bwd_); - setTwistAngular(old_angular_fwd_); - setTwistAngular(old_angular_rev_); - robot::log_info("[MoveBase::moveTo] Goal processed successfully by action server"); } catch (const std::exception &e) @@ -1124,11 +1118,6 @@ bool move_base::MoveBase::moveTo(const robot_protocol_msgs::Order &msg, } as_->processGoal(action_goal); - - setTwistLinear(old_linear_fwd_); - setTwistLinear(old_linear_bwd_); - setTwistAngular(old_angular_fwd_); - setTwistAngular(old_angular_rev_); } catch (const std::exception &e) { @@ -1290,10 +1279,6 @@ bool move_base::MoveBase::dockTo(const std::string &marker, const robot_geometry robot::log_info("[MoveBase::moveTo] Processing goal through action server..."); as_->processGoal(action_goal); - setTwistLinear(old_linear_fwd_); - setTwistLinear(old_linear_bwd_); - setTwistAngular(old_angular_fwd_); - setTwistAngular(old_angular_rev_); robot::log_info("[MoveBase::moveTo] Goal processed successfully by action server"); } catch (const std::exception &e) @@ -1440,10 +1425,6 @@ bool move_base::MoveBase::dockTo(const robot_protocol_msgs::Order &msg, return false; } as_->processGoal(action_goal); - setTwistLinear(old_linear_fwd_); - setTwistLinear(old_linear_bwd_); - setTwistAngular(old_angular_fwd_); - setTwistAngular(old_angular_rev_); } catch (const std::exception &e) {