Skip to content

Commit ab45598

Browse files
Tomas BacaTomas Baca
authored andcommitted
fixed prints
1 parent d771150 commit ab45598

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

src/mpc_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1695,7 +1695,7 @@ void MpcController::MPC(const mrs_msgs::msg::UavState &uav_state, const mrs_msgs
16951695

16961696
rampup_last_time_ = clock_->now();
16971697

1698-
RCLCPP_INFO_THROTTLE(node_->get_logger(), *clock_, 100, "[%s]: ramping up throttle, %.4f", name_.c_str(), throttle);
1698+
RCLCPP_INFO_THROTTLE(node_->get_logger(), *clock_, 100, "[%s]: ramping up throttle, %.4f", name_.c_str(), rampup_throttle_);
16991699
}
17001700

17011701
throttle = rampup_throttle_;

src/se3_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1559,7 +1559,7 @@ void Se3Controller::SE3Controller(const mrs_msgs::msg::UavState& uav_state, cons
15591559

15601560
rampup_last_time_ = clock_->now();
15611561

1562-
RCLCPP_INFO_THROTTLE(node_->get_logger(), *clock_, 100, "[Se3Controller]: ramping up throttle, %.4f", throttle);
1562+
RCLCPP_INFO_THROTTLE(node_->get_logger(), *clock_, 100, "[Se3Controller]: ramping up throttle, %.4f", rampup_throttle_);
15631563
}
15641564

15651565
throttle = rampup_throttle_;

0 commit comments

Comments
 (0)