Skip to content

Commit d60d8dd

Browse files
committed
fix clang-tidy failures for rolling
1 parent 7bd69b7 commit d60d8dd

File tree

3 files changed

+12
-4
lines changed

3 files changed

+12
-4
lines changed

moveit_planners/pilz_industrial_motion_planner/src/path_polyline_generator.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -73,12 +73,12 @@ std::vector<KDL::Frame> PathPolylineGenerator::filterWaypoints(const KDL::Frame&
7373
double dist;
7474

7575
// add points and skip the points which are too close to each other
76-
for (size_t i = 0; i < waypoints.size(); ++i)
76+
for (const auto& waypoint : waypoints)
7777
{
78-
dist = (last_point() - waypoints[i].p).Norm();
78+
dist = (last_point() - waypoint.p).Norm();
7979
if (dist > MIN_SEGMENT_LENGTH)
8080
{
81-
filtered_waypoints.push_back(waypoints[i]);
81+
filtered_waypoints.push_back(waypoint);
8282
++last_added_point_indx;
8383
}
8484
}

moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -382,7 +382,7 @@ TrajectoryGenerator::MotionPlanInfo::MotionPlanInfo(const planning_scene::Planni
382382

383383
void TrajectoryGenerator::setMaxCartesianSpeed(const moveit_msgs::msg::MotionPlanRequest& req)
384384
{
385-
if (req.max_cartesian_speed > 0.0 && req.cartesian_speed_limited_link != "")
385+
if (req.max_cartesian_speed > 0.0 && !req.cartesian_speed_limited_link.empty())
386386
{
387387
max_cartesian_speed_ = req.max_cartesian_speed;
388388
RCLCPP_INFO(getLogger(), "received max_cartesian_speed: %f", max_cartesian_speed_);

moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_polyline.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -145,13 +145,21 @@ void TrajectoryGeneratorPolyline::plan(const planning_scene::PlanningSceneConstP
145145
int code = e.GetType();
146146
std::ostringstream os;
147147
if (code == 3102 || code == 3103)
148+
{
148149
os << "zero distance between two points";
150+
}
149151
else if (code == 3104)
152+
{
150153
os << "waypoints specified in path constraints have three consicutive colinear points";
154+
}
151155
else if (code == 3105 || code == 3106)
156+
{
152157
os << "rounding circle of a point is bigger than the distance with one of the neighbor points";
158+
}
153159
else if (code == 3001 || code == 3002)
160+
{
154161
os << "the rounding radius is lower than KDL::epsilon. use bigger smoothness or resample your waypoints";
162+
}
155163
throw ConsicutiveColinearWaypoints(os.str());
156164
}
157165
// create velocity profile

0 commit comments

Comments
 (0)