mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
removed info about speed scaling rampup
This commit is contained in:
committed by
Tristan Schnell
parent
5f405b3996
commit
00d20cb501
@@ -243,7 +243,6 @@ void HardwareInterface ::read(const ros::Time& time, const ros::Duration& period
|
|||||||
|
|
||||||
if (pausing_state_ == PausingState::RAMPUP)
|
if (pausing_state_ == PausingState::RAMPUP)
|
||||||
{
|
{
|
||||||
ROS_INFO_STREAM("Ramping up speed scaling");
|
|
||||||
double speed_scaling_ramp = speed_scaling_combined_ + pausing_ramp_up_increment_;
|
double speed_scaling_ramp = speed_scaling_combined_ + pausing_ramp_up_increment_;
|
||||||
speed_scaling_combined_ = std::min(speed_scaling_ramp, speed_scaling_ * target_speed_fraction_);
|
speed_scaling_combined_ = std::min(speed_scaling_ramp, speed_scaling_ * target_speed_fraction_);
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user