Skip to content

Commit ee6c50a

Browse files
authored
Apply clang-format-10 (moveit#199)
1 parent 47f052b commit ee6c50a

37 files changed

+99
-93
lines changed

.clang-format

+1
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ BraceWrapping:
2424
BeforeCatch: false
2525
BeforeElse: false
2626
IndentBraces: false
27+
SplitEmptyRecord: false
2728
BreakBeforeBinaryOperators: None
2829
BreakBeforeBraces: Custom
2930
BreakBeforeTernaryOperators: false

core/include/moveit/task_constructor/container.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ class ParallelContainerBase;
120120
* - Fallbacks: the children are considered in series
121121
* - Merger: solutions of all children (actuating disjoint groups)
122122
* are merged into a single solution for parallel execution
123-
*/
123+
*/
124124
class ParallelContainerBase : public ContainerBase
125125
{
126126
public:

core/include/moveit/task_constructor/container_p.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,8 @@ namespace moveit {
4949
namespace core {
5050
MOVEIT_CLASS_FORWARD(JointModelGroup)
5151
MOVEIT_CLASS_FORWARD(RobotState)
52-
}
53-
}
52+
} // namespace core
53+
} // namespace moveit
5454

5555
namespace moveit {
5656
namespace task_constructor {

core/include/moveit/task_constructor/marker_tools.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@ namespace moveit {
1212
namespace core {
1313
MOVEIT_CLASS_FORWARD(RobotState)
1414
MOVEIT_CLASS_FORWARD(LinkModel)
15-
}
16-
}
15+
} // namespace core
16+
} // namespace moveit
1717

1818
namespace moveit {
1919
namespace task_constructor {

core/include/moveit/task_constructor/solvers/planner_interface.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,8 @@ namespace core {
5454
MOVEIT_CLASS_FORWARD(LinkModel)
5555
MOVEIT_CLASS_FORWARD(RobotModel)
5656
MOVEIT_CLASS_FORWARD(JointModelGroup)
57-
}
58-
}
57+
} // namespace core
58+
} // namespace moveit
5959

6060
namespace moveit {
6161
namespace task_constructor {

core/include/moveit/task_constructor/stage.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ namespace moveit {
5454
namespace core {
5555
MOVEIT_CLASS_FORWARD(RobotModel)
5656
}
57-
}
57+
} // namespace moveit
5858

5959
namespace planning_scene {
6060
MOVEIT_CLASS_FORWARD(PlanningScene)

core/include/moveit/task_constructor/stages/compute_ik.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ namespace moveit {
4545
namespace core {
4646
MOVEIT_CLASS_FORWARD(RobotState)
4747
MOVEIT_CLASS_FORWARD(JointModelGroup)
48-
}
49-
}
48+
} // namespace core
49+
} // namespace moveit
5050

5151
namespace moveit {
5252
namespace task_constructor {

core/include/moveit/task_constructor/stages/connect.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ namespace moveit {
4747
namespace core {
4848
MOVEIT_CLASS_FORWARD(RobotState)
4949
}
50-
}
50+
} // namespace moveit
5151

5252
namespace moveit {
5353
namespace task_constructor {

core/include/moveit/task_constructor/stages/modify_planning_scene.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ namespace moveit {
4848
namespace core {
4949
MOVEIT_CLASS_FORWARD(JointModelGroup)
5050
}
51-
}
51+
} // namespace moveit
5252

5353
namespace moveit {
5454
namespace task_constructor {

core/include/moveit/task_constructor/stages/move_relative.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ namespace moveit {
4848
namespace core {
4949
class RobotState;
5050
}
51-
}
51+
} // namespace moveit
5252
namespace moveit {
5353
namespace task_constructor {
5454
namespace stages {

core/include/moveit/task_constructor/stages/move_to.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ namespace moveit {
4848
namespace core {
4949
class RobotState;
5050
}
51-
}
51+
} // namespace moveit
5252
namespace moveit {
5353
namespace task_constructor {
5454
namespace stages {
@@ -101,10 +101,10 @@ class MoveTo : public PropagatingEitherWay
101101
bool getJointStateGoal(const boost::any& goal, const core::JointModelGroup* jmg, moveit::core::RobotState& state);
102102
bool getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStamped& ik_pose_msg,
103103
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
104-
decltype(std::declval<SolutionBase>().markers()) & markers);
104+
decltype(std::declval<SolutionBase>().markers())& markers);
105105
bool getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link,
106106
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
107-
decltype(std::declval<SolutionBase>().markers()) & /*unused*/);
107+
decltype(std::declval<SolutionBase>().markers())& /*unused*/);
108108

109109
protected:
110110
solvers::PlannerInterfacePtr planner_;

core/include/moveit/task_constructor/stages/predicate_filter.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ namespace moveit {
4141
namespace core {
4242
MOVEIT_CLASS_FORWARD(RobotState)
4343
}
44-
}
44+
} // namespace moveit
4545

4646
namespace moveit {
4747
namespace task_constructor {

core/include/moveit/task_constructor/stages/simple_grasp.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ namespace moveit {
4545
namespace core {
4646
MOVEIT_CLASS_FORWARD(RobotModel)
4747
}
48-
}
48+
} // namespace moveit
4949
namespace moveit {
5050
namespace task_constructor {
5151
namespace stages {

core/include/moveit/task_constructor/storage.h

+4-4
Original file line numberDiff line numberDiff line change
@@ -182,10 +182,10 @@ class Interface : public ordered<InterfaceState*>
182182

183183
// restrict access to some functions to ensure consistency
184184
// (we need to set/unset InterfaceState::owner_)
185-
using base_type::moveTo;
186-
using base_type::moveFrom;
187-
using base_type::insert;
188185
using base_type::erase;
186+
using base_type::insert;
187+
using base_type::moveFrom;
188+
using base_type::moveTo;
189189
using base_type::remove_if;
190190
};
191191

@@ -329,4 +329,4 @@ struct less<moveit::task_constructor::SolutionBase*>
329329
return *x < *y;
330330
}
331331
};
332-
}
332+
} // namespace std

core/include/moveit/task_constructor/task.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,8 @@ namespace moveit {
5252
namespace core {
5353
MOVEIT_CLASS_FORWARD(RobotModel)
5454
MOVEIT_CLASS_FORWARD(RobotState)
55-
}
56-
}
55+
} // namespace core
56+
} // namespace moveit
5757

5858
namespace moveit {
5959
namespace task_constructor {
@@ -108,9 +108,9 @@ class Task : protected WrapperBase
108108
void eraseTaskCallback(TaskCallbackList::const_iterator which);
109109

110110
/// expose SolutionCallback API
111-
using WrapperBase::SolutionCallback;
112111
using WrapperBase::addSolutionCallback;
113112
using WrapperBase::removeSolutionCallback;
113+
using WrapperBase::SolutionCallback;
114114

115115
/// reset all stages
116116
void reset() final;

core/include/moveit/task_constructor/type_traits.h

+3-2
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,9 @@ struct is_container_helper
5454

5555
template <typename T>
5656
struct is_container<
57-
T, std::conditional_t<false, is_container_helper<typename T::const_iterator, decltype(std::declval<T>().cbegin()),
58-
decltype(std::declval<T>().cend())>,
57+
T, std::conditional_t<false,
58+
is_container_helper<typename T::const_iterator, decltype(std::declval<T>().cbegin()),
59+
decltype(std::declval<T>().cend())>,
5960
void> > : public std::true_type
6061
{};
6162
} // namespace task_constructor

core/src/introspection.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ std::string getProcessId() {
5757
gethostname(our_hostname, sizeof(our_hostname) - 1);
5858
return std::to_string(getpid()) + "@" + our_hostname;
5959
}
60-
}
60+
} // namespace
6161

6262
class IntrospectionPrivate
6363
{

core/src/solvers/planner_interface.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,6 @@ PlannerInterface::PlannerInterface() {
4747
p.declare<double>("max_velocity_scaling_factor", 1.0, "scale down max velocity by this factor");
4848
p.declare<double>("max_acceleration_scaling_factor", 1.0, "scale down max acceleration by this factor");
4949
}
50-
}
51-
}
50+
} // namespace solvers
51+
} // namespace task_constructor
5252
} // namespace moveit

core/src/stage.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -720,7 +720,7 @@ bool Connecting::compatible(const InterfaceState& from_state, const InterfaceSta
720720
auto it = std::find_if(to_attached.cbegin(), to_attached.cend(),
721721
[from_object](const moveit::core::AttachedBody* object) {
722722
return object->getName() == from_object->getName();
723-
});
723+
});
724724
if (it == to_attached.cend()) {
725725
ROS_DEBUG_STREAM_NAMED("Connecting", name() << ": object missing: " << from_object->getName());
726726
return false;

core/src/stages/compute_ik.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -354,8 +354,9 @@ void ComputeIK::compute() {
354354
double min_solution_distance = props.get<double>("min_solution_distance");
355355

356356
IKSolutions ik_solutions;
357-
auto is_valid = [sandbox_scene, ignore_collisions, min_solution_distance, &ik_solutions](
358-
robot_state::RobotState* state, const robot_model::JointModelGroup* jmg, const double* joint_positions) {
357+
auto is_valid = [sandbox_scene, ignore_collisions, min_solution_distance,
358+
&ik_solutions](robot_state::RobotState* state, const robot_model::JointModelGroup* jmg,
359+
const double* joint_positions) {
359360
for (const auto& sol : ik_solutions) {
360361
if (jmg->distance(joint_positions, sol.data()) < min_solution_distance)
361362
return false; // too close to already found solution

core/src/stages/fix_collision_objects.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -72,8 +72,8 @@ bool computeCorrection(const std::vector<cd::Contact>& contacts, Eigen::Vector3d
7272
correction.setZero();
7373
for (const cd::Contact& c : contacts) {
7474
if ((c.body_type_1 != cd::BodyTypes::WORLD_OBJECT && c.body_type_2 != cd::BodyTypes::WORLD_OBJECT)) {
75-
ROS_WARN_STREAM_NAMED("FixCollisionObjects", "Cannot fix collision between " << c.body_name_1 << " and "
76-
<< c.body_name_2);
75+
ROS_WARN_STREAM_NAMED("FixCollisionObjects",
76+
"Cannot fix collision between " << c.body_name_1 << " and " << c.body_name_2);
7777
return false;
7878
}
7979
if (c.body_type_1 == cd::BodyTypes::WORLD_OBJECT)

core/src/stages/move_to.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ bool MoveTo::getJointStateGoal(const boost::any& goal, const moveit::core::Joint
125125

126126
bool MoveTo::getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStamped& ik_pose_msg,
127127
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
128-
decltype(std::declval<SolutionBase>().markers()) & markers) {
128+
decltype(std::declval<SolutionBase>().markers())& markers) {
129129
try {
130130
const geometry_msgs::PoseStamped& target = boost::any_cast<geometry_msgs::PoseStamped>(goal);
131131
tf::poseMsgToEigen(target.pose, target_eigen);
@@ -147,7 +147,7 @@ bool MoveTo::getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStampe
147147

148148
bool MoveTo::getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link,
149149
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
150-
decltype(std::declval<SolutionBase>().markers()) & /*unused*/) {
150+
decltype(std::declval<SolutionBase>().markers())& /*unused*/) {
151151
try {
152152
const geometry_msgs::PointStamped& target = boost::any_cast<geometry_msgs::PointStamped>(goal);
153153
Eigen::Vector3d target_point;

core/src/task.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ Task::Task(const std::string& id, bool introspection, ContainerBase::pointer&& c
117117
}
118118

119119
Task::Task(Task&& other) // NOLINT(performance-noexcept-move-constructor)
120-
: WrapperBase(new TaskPrivate(this, std::string()), std::make_unique<SerialContainer>()) {
120+
: WrapperBase(new TaskPrivate(this, std::string()), std::make_unique<SerialContainer>()) {
121121
*this = std::move(other);
122122
}
123123

@@ -223,7 +223,7 @@ void Task::enableIntrospection(bool enable) {
223223
[](Stage& stage, int /*depth*/) {
224224
stage.pimpl()->setIntrospection(nullptr);
225225
return true;
226-
},
226+
},
227227
1, UINT_MAX);
228228
impl->introspection_.reset();
229229
}
@@ -275,7 +275,7 @@ void Task::init() {
275275
[impl](Stage& stage, int /*depth*/) {
276276
stage.pimpl()->setIntrospection(impl->introspection_.get());
277277
return true;
278-
},
278+
},
279279
1, UINT_MAX);
280280

281281
// first time publish task

core/test/models.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ namespace moveit {
66
namespace core {
77
MOVEIT_CLASS_FORWARD(RobotModel)
88
}
9-
}
9+
} // namespace moveit
1010

1111
// get a hard-coded model
1212
moveit::core::RobotModelPtr getModel();

visualization/motion_planning_tasks/properties/property_factory.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -48,15 +48,15 @@ namespace rviz {
4848
class Property;
4949
class PropertyTreeModel;
5050
class DisplayContext;
51-
}
51+
} // namespace rviz
5252
namespace planning_scene {
5353
class PlanningScene;
5454
}
5555
namespace moveit {
5656
namespace task_constructor {
5757
class Stage;
5858
}
59-
}
59+
} // namespace moveit
6060

6161
namespace moveit_rviz_plugin {
6262

visualization/motion_planning_tasks/src/icons.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -11,5 +11,5 @@ const Icon FORWARD({ { QLatin1String(":icons/downarrow.png"), QColor::fromRgba(0
1111
const Icon BACKWARD({ { QLatin1String(":icons/uparrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT);
1212
const Icon BOTHWAY({ { QLatin1String(":icons/updownarrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT);
1313
const Icon GENERATE({ { QLatin1String(":icons/generatearrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT);
14-
}
15-
}
14+
} // namespace icons
15+
} // namespace moveit_rviz_plugin

visualization/motion_planning_tasks/src/icons.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -10,5 +10,5 @@ extern const moveit_rviz_plugin::utils::Icon FORWARD;
1010
extern const moveit_rviz_plugin::utils::Icon BACKWARD;
1111
extern const moveit_rviz_plugin::utils::Icon BOTHWAY;
1212
extern const moveit_rviz_plugin::utils::Icon GENERATE;
13-
}
14-
}
13+
} // namespace icons
14+
} // namespace moveit_rviz_plugin

visualization/motion_planning_tasks/src/remote_task_model.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -596,7 +596,7 @@ void RemoteSolutionModel::sortInternal() {
596596
if (comp == 0) // if still undecided, id decides
597597
comp = (left->id < right->id ? -1 : 1);
598598
return (sort_order_ == Qt::AscendingOrder) ? (comp < 0) : (comp >= 0);
599-
});
599+
});
600600
}
601601

602602
// map old indexes to new ones

visualization/motion_planning_tasks/src/task_display.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,13 +54,13 @@
5454
namespace rviz {
5555
class StringProperty;
5656
class RosTopicProperty;
57-
}
57+
} // namespace rviz
5858

5959
namespace moveit {
6060
namespace core {
6161
MOVEIT_CLASS_FORWARD(RobotModel)
6262
}
63-
}
63+
} // namespace moveit
6464
namespace rdf_loader {
6565
MOVEIT_CLASS_FORWARD(RDFLoader)
6666
}

visualization/motion_planning_tasks/src/task_list_model.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class ServiceClient;
5858
namespace rviz {
5959
class PropertyTreeModel;
6060
class DisplayContext;
61-
}
61+
} // namespace rviz
6262

6363
namespace moveit_rviz_plugin {
6464

visualization/motion_planning_tasks/src/task_panel.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -226,7 +226,7 @@ TaskViewPrivate::TaskViewPrivate(TaskView* q_ptr) : q_ptr(q_ptr), exec_action_cl
226226
}
227227
tasks_view->setExpanded(parent, true); // expand parent group item
228228
}
229-
});
229+
});
230230

231231
tasks_view->setSelectionMode(QAbstractItemView::ExtendedSelection);
232232
tasks_view->setAcceptDrops(true);

visualization/motion_planning_tasks/src/task_panel.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ class WindowManagerInterface;
4949
class Property;
5050
class BoolProperty;
5151
class EnumProperty;
52-
}
52+
} // namespace rviz
5353

5454
namespace moveit_rviz_plugin {
5555

@@ -108,7 +108,7 @@ class MetaTaskListModel;
108108
* Subscribing to task_monitoring and task_solution topics, it collects information
109109
* about running tasks and their solutions and allows to inspect both,
110110
* successful solutions and failed solution attempts.
111-
*/
111+
*/
112112
class TaskViewPrivate;
113113
class TaskView : public SubPanel
114114
{

0 commit comments

Comments
 (0)