@@ -53,6 +53,7 @@ static const rclcpp::Logger LOGGER =
53
53
rclcpp::get_logger (" moveit_trajectory_processing.time_optimal_trajectory_generation" );
54
54
constexpr double DEFAULT_TIMESTEP = 1e-3 ;
55
55
constexpr double EPS = 1e-6 ;
56
+ constexpr double DEFAULT_SCALING_FACTOR = 1.0 ;
56
57
} // namespace
57
58
58
59
class LinearPathSegment : public PathSegment
@@ -880,11 +881,10 @@ bool TimeOptimalTrajectoryGeneration::computeTimeStamps(robot_trajectory::RobotT
880
881
}
881
882
882
883
// Validate scaling
883
- double velocity_scaling_factor = 1.0 ;
884
- verifyScalingFactor (velocity_scaling_factor, max_velocity_scaling_factor, VELOCITY);
884
+ double velocity_scaling_factor = verifyScalingFactor (velocity_scaling_factor, max_velocity_scaling_factor, VELOCITY);
885
885
886
- double acceleration_scaling_factor = 1.0 ;
887
- verifyScalingFactor (acceleration_scaling_factor, max_acceleration_scaling_factor, ACCELERATION);
886
+ double acceleration_scaling_factor =
887
+ verifyScalingFactor (acceleration_scaling_factor, max_acceleration_scaling_factor, ACCELERATION);
888
888
889
889
const std::vector<std::string>& vars = group->getVariableNames ();
890
890
const moveit::core::RobotModel& rmodel = group->getParentModel ();
@@ -980,11 +980,10 @@ bool TimeOptimalTrajectoryGeneration::computeTimeStamps(
980
980
}
981
981
982
982
// Validate scaling
983
- double velocity_scaling_factor = 1.0 ;
984
- verifyScalingFactor (velocity_scaling_factor, max_velocity_scaling_factor, VELOCITY);
983
+ double velocity_scaling_factor = verifyScalingFactor (velocity_scaling_factor, max_velocity_scaling_factor, VELOCITY);
985
984
986
- double acceleration_scaling_factor = 1.0 ;
987
- verifyScalingFactor (acceleration_scaling_factor, max_acceleration_scaling_factor, ACCELERATION);
985
+ double acceleration_scaling_factor =
986
+ verifyScalingFactor (acceleration_scaling_factor, max_acceleration_scaling_factor, ACCELERATION);
988
987
989
988
const unsigned num_joints = group->getVariableCount ();
990
989
const std::vector<std::string>& vars = group->getVariableNames ();
@@ -1211,30 +1210,27 @@ bool TimeOptimalTrajectoryGeneration::hasMixedJointTypes(const moveit::core::Joi
1211
1210
return have_prismatic && have_revolute;
1212
1211
}
1213
1212
1214
- void TimeOptimalTrajectoryGeneration::verifyScalingFactor (double & scaling_factor, const double max_scaling_factor ,
1215
- const LimitType limit_type) const
1213
+ double TimeOptimalTrajectoryGeneration::verifyScalingFactor (const double requested_scaling_factor ,
1214
+ const LimitType limit_type) const
1216
1215
{
1217
1216
std::string limit_type_str;
1218
- auto limit_type_it = LIMIT_TYPES. find (limit_type) ;
1217
+ double scaling_factor = DEFAULT_SCALING_FACTOR ;
1219
1218
1219
+ const auto limit_type_it = LIMIT_TYPES.find (limit_type);
1220
1220
if (limit_type_it != LIMIT_TYPES.end ())
1221
1221
{
1222
1222
limit_type_str = limit_type_it->second + " _" ;
1223
1223
}
1224
1224
1225
- if (max_scaling_factor > 0.0 && max_scaling_factor <= 1.0 )
1225
+ if (requested_scaling_factor > 0.0 && requested_scaling_factor <= 1.0 )
1226
1226
{
1227
- scaling_factor = max_scaling_factor;
1228
- }
1229
- else if (max_scaling_factor == 0.0 )
1230
- {
1231
- RCLCPP_DEBUG (LOGGER, " A max_%sscaling_factor of 0.0 was specified, defaulting to %f instead." ,
1232
- limit_type_str.c_str (), scaling_factor);
1227
+ scaling_factor = requested_scaling_factor;
1233
1228
}
1234
1229
else
1235
1230
{
1236
1231
RCLCPP_WARN (LOGGER, " Invalid max_%sscaling_factor %f specified, defaulting to %f instead." , limit_type_str.c_str (),
1237
- max_scaling_factor , scaling_factor);
1232
+ requested_scaling_factor , scaling_factor);
1238
1233
}
1234
+ return scaling_factor;
1239
1235
}
1240
1236
} // namespace trajectory_processing
0 commit comments