Skip to content

Commit 0bee4d0

Browse files
Tomas BacaTomas Baca
authored andcommitted
fixed prints
1 parent 5a0aff7 commit 0bee4d0

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
@@ -1514,7 +1514,7 @@ void MpcController::MPC(const mrs_msgs::UavState &uav_state, const mrs_msgs::Tra
15141514

15151515
rampup_last_time_ = ros::Time::now();
15161516

1517-
ROS_INFO_THROTTLE(0.1, "[%s]: ramping up throttle, %.4f", name_.c_str(), throttle);
1517+
ROS_INFO_THROTTLE(0.1, "[%s]: ramping up throttle, %.4f", name_.c_str(), rampup_throttle_);
15181518
}
15191519

15201520
throttle = rampup_throttle_;

src/se3_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1266,7 +1266,7 @@ void Se3Controller::SE3Controller(const mrs_msgs::UavState& uav_state, const mrs
12661266

12671267
rampup_last_time_ = ros::Time::now();
12681268

1269-
ROS_INFO_THROTTLE(0.1, "[Se3Controller]: ramping up throttle, %.4f", throttle);
1269+
ROS_INFO_THROTTLE(0.1, "[Se3Controller]: ramping up throttle, %.4f", rampup_throttle_);
12701270
}
12711271

12721272
throttle = rampup_throttle_;

0 commit comments

Comments
 (0)