Skip to content

Commit 2153237

Browse files
committed
clang-format: readability-identifier-naming
Probably the most invasive format patch, also changing some internal API. I deliberately disabled ClassCase and MethodCase checks for the moment to avoid public API changes in this patch set.
1 parent fa041ed commit 2153237

20 files changed

+172
-135
lines changed

.clang-tidy

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ Checks: '-*,
66
modernize-loop-convert,
77
readability-named-parameter,
88
readability-container-size-empty,
9+
readability-identifier-naming,
910
'
1011
HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h'
1112
AnalyzeTemporaryDtors: false
@@ -18,14 +19,14 @@ CheckOptions:
1819
value: '2'
1920
# type names
2021
- key: readability-identifier-naming.ClassCase
21-
value: CamelCase
22+
value: aNy_CasE # CamelCase
2223
- key: readability-identifier-naming.EnumCase
2324
value: CamelCase
2425
- key: readability-identifier-naming.UnionCase
2526
value: CamelCase
2627
# method names
2728
- key: readability-identifier-naming.MethodCase
28-
value: camelBack
29+
value: aNy_CasE # camelBack
2930
# variable names
3031
- key: readability-identifier-naming.VariableCase
3132
value: lower_case

core/src/container.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ void ContainerBasePrivate::liftSolution(SolutionBasePtr solution, const Interfac
123123
if (!storeSolution(solution))
124124
return;
125125

126-
auto findOrCreateExternal = [this](const InterfaceState* internal, bool& created) -> InterfaceState* {
126+
auto find_or_create_external = [this](const InterfaceState* internal, bool& created) -> InterfaceState* {
127127
auto it = internal_to_external_.find(internal);
128128
if (it != internal_to_external_.end())
129129
return it->second;
@@ -135,8 +135,8 @@ void ContainerBasePrivate::liftSolution(SolutionBasePtr solution, const Interfac
135135
};
136136
bool created_from = false;
137137
bool created_to = false;
138-
InterfaceState* external_from = findOrCreateExternal(internal_from, created_from);
139-
InterfaceState* external_to = findOrCreateExternal(internal_to, created_to);
138+
InterfaceState* external_from = find_or_create_external(internal_from, created_from);
139+
InterfaceState* external_to = find_or_create_external(internal_to, created_to);
140140

141141
// connect solution to start/end state
142142
solution->setStartState(*external_from);

core/src/introspection.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -204,7 +204,7 @@ void Introspection::fillStageStatistics(const Stage& stage, moveit_task_construc
204204

205205
moveit_task_constructor_msgs::TaskDescription&
206206
Introspection::fillTaskDescription(moveit_task_constructor_msgs::TaskDescription& msg) {
207-
ContainerBase::StageCallback stageProcessor = [this, &msg](const Stage& stage, unsigned int /*depth*/) -> bool {
207+
ContainerBase::StageCallback stage_processor = [this, &msg](const Stage& stage, unsigned int /*depth*/) -> bool {
208208
// this method is called for each child stage of a given parent
209209
moveit_task_constructor_msgs::StageDescription desc;
210210
desc.id = stageId(&stage);
@@ -231,7 +231,7 @@ Introspection::fillTaskDescription(moveit_task_constructor_msgs::TaskDescription
231231
};
232232

233233
msg.stages.clear();
234-
impl->task_->stages()->traverseRecursively(stageProcessor);
234+
impl->task_->stages()->traverseRecursively(stage_processor);
235235

236236
msg.id = impl->task_->id();
237237
msg.process_id = impl->process_id_;
@@ -240,7 +240,7 @@ Introspection::fillTaskDescription(moveit_task_constructor_msgs::TaskDescription
240240

241241
moveit_task_constructor_msgs::TaskStatistics&
242242
Introspection::fillTaskStatistics(moveit_task_constructor_msgs::TaskStatistics& msg) {
243-
ContainerBase::StageCallback stageProcessor = [this, &msg](const Stage& stage, unsigned int /*depth*/) -> bool {
243+
ContainerBase::StageCallback stage_processor = [this, &msg](const Stage& stage, unsigned int /*depth*/) -> bool {
244244
// this method is called for each child stage of a given parent
245245
moveit_task_constructor_msgs::StageStatistics stat; // create new Stage msg
246246
stat.id = stageId(&stage);
@@ -252,7 +252,7 @@ Introspection::fillTaskStatistics(moveit_task_constructor_msgs::TaskStatistics&
252252
};
253253

254254
msg.stages.clear();
255-
impl->task_->stages()->traverseRecursively(stageProcessor);
255+
impl->task_->stages()->traverseRecursively(stage_processor);
256256

257257
msg.id = impl->task_->id();
258258
msg.process_id = impl->process_id_;

core/src/properties.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ class PropertyTypeRegistry
8585
return it->second->second;
8686
}
8787
};
88-
static PropertyTypeRegistry registry_singleton_;
88+
static PropertyTypeRegistry REGISTRY_SINGLETON;
8989

9090
bool PropertyTypeRegistry::insert(const std::type_index& type_index, const std::string& type_name,
9191
PropertySerializerBase::SerializeFunction serialize,
@@ -106,7 +106,7 @@ bool PropertyTypeRegistry::insert(const std::type_index& type_index, const std::
106106
bool PropertySerializerBase::insert(const std::type_index& type_index, const std::string& type_name,
107107
PropertySerializerBase::SerializeFunction serialize,
108108
PropertySerializerBase::DeserializeFunction deserialize) {
109-
return registry_singleton_.insert(type_index, type_name, serialize, deserialize);
109+
return REGISTRY_SINGLETON.insert(type_index, type_name, serialize, deserialize);
110110
}
111111

112112
Property::Property(const type_info& type_info, const std::string& description, const boost::any& default_value)
@@ -149,14 +149,14 @@ void Property::reset() {
149149
std::string Property::serialize(const boost::any& value) {
150150
if (value.empty())
151151
return "";
152-
return registry_singleton_.entry(value.type()).serialize_(value);
152+
return REGISTRY_SINGLETON.entry(value.type()).serialize_(value);
153153
}
154154

155155
boost::any Property::deserialize(const std::string& type_name, const std::string& wire) {
156156
if (type_name != Property::typeName(typeid(std::string)) && wire.empty())
157157
return boost::any();
158158
else
159-
return registry_singleton_.entry(type_name).deserialize_(wire);
159+
return REGISTRY_SINGLETON.entry(type_name).deserialize_(wire);
160160
}
161161

162162
std::string Property::typeName() const {
@@ -170,7 +170,7 @@ std::string Property::typeName(const type_info& type_info) {
170170
if (type_info == typeid(boost::any))
171171
return "";
172172
else
173-
return registry_singleton_.entry(type_info).name_;
173+
return REGISTRY_SINGLETON.entry(type_info).name_;
174174
}
175175

176176
bool Property::initsFrom(Property::SourceFlags source) const {
@@ -316,9 +316,9 @@ Property::undefined::undefined(const std::string& name, const std::string& msg)
316316
setName(name);
317317
}
318318

319-
static boost::format type_error_fmt("type (%1%) doesn't match property's declared type (%2%)");
319+
static boost::format TYPE_ERROR_FMT("type (%1%) doesn't match property's declared type (%2%)");
320320
Property::type_error::type_error(const std::string& current_type, const std::string& declared_type)
321-
: Property::error(boost::str(type_error_fmt % current_type % declared_type)) {}
321+
: Property::error(boost::str(TYPE_ERROR_FMT % current_type % declared_type)) {}
322322

323323
} // namespace task_constructor
324324
} // namespace moveit

core/src/solvers/cartesian_path.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -80,8 +80,8 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
8080
kinematic_constraints::KinematicConstraintSet kcs(sandbox_scene->getRobotModel());
8181
kcs.add(path_constraints, sandbox_scene->getTransforms());
8282

83-
auto isValid = [&sandbox_scene, &kcs](moveit::core::RobotState* state, const moveit::core::JointModelGroup* jmg,
84-
const double* joint_positions) {
83+
auto is_valid = [&sandbox_scene, &kcs](moveit::core::RobotState* state, const moveit::core::JointModelGroup* jmg,
84+
const double* joint_positions) {
8585
state->setJointGroupPositions(jmg, joint_positions);
8686
state->update();
8787
return !sandbox_scene->isStateColliding(const_cast<const robot_state::RobotState&>(*state), jmg->getName()) &&
@@ -93,11 +93,11 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
9393
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
9494
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
9595
moveit::core::MaxEEFStep(props.get<double>("step_size")),
96-
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), isValid);
96+
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid);
9797
#else
9898
double achieved_fraction = sandbox_scene->getCurrentStateNonConst().computeCartesianPath(
9999
jmg, trajectory, &link, target, true, props.get<double>("step_size"), props.get<double>("jump_threshold"),
100-
isValid);
100+
is_valid);
101101
#endif
102102

103103
if (!trajectory.empty()) {

core/src/stages/compute_ik.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -354,7 +354,7 @@ void ComputeIK::compute() {
354354
double min_solution_distance = props.get<double>("min_solution_distance");
355355

356356
IKSolutions ik_solutions;
357-
auto isValid = [sandbox_scene, ignore_collisions, min_solution_distance, &ik_solutions](
357+
auto is_valid = [sandbox_scene, ignore_collisions, min_solution_distance, &ik_solutions](
358358
robot_state::RobotState* state, const robot_model::JointModelGroup* jmg, const double* joint_positions) {
359359
for (const auto& sol : ik_solutions) {
360360
if (jmg->distance(joint_positions, sol.data()) < min_solution_distance)
@@ -378,7 +378,7 @@ void ComputeIK::compute() {
378378
tried_current_state_as_seed = true;
379379

380380
size_t previous = ik_solutions.size();
381-
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), remaining_time, isValid);
381+
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), remaining_time, is_valid);
382382

383383
auto now = std::chrono::steady_clock::now();
384384
remaining_time -= std::chrono::duration<double>(now - start_time).count();

core/src/stages/generate_grasp_pose.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -128,11 +128,11 @@ void GenerateGraspPose::compute() {
128128
geometry_msgs::PoseStamped target_pose_msg;
129129
target_pose_msg.header.frame_id = props.get<std::string>("object");
130130

131-
double current_angle_ = 0.0;
132-
while (current_angle_ < 2. * M_PI && current_angle_ > -2. * M_PI) {
131+
double current_angle = 0.0;
132+
while (current_angle < 2. * M_PI && current_angle > -2. * M_PI) {
133133
// rotate object pose about z-axis
134-
Eigen::Isometry3d target_pose(Eigen::AngleAxisd(current_angle_, Eigen::Vector3d::UnitZ()));
135-
current_angle_ += props.get<double>("angle_delta");
134+
Eigen::Isometry3d target_pose(Eigen::AngleAxisd(current_angle, Eigen::Vector3d::UnitZ()));
135+
current_angle += props.get<double>("angle_delta");
136136

137137
InterfaceState state(scene);
138138
tf::poseEigenToMsg(target_pose, target_pose_msg.pose);
@@ -141,7 +141,7 @@ void GenerateGraspPose::compute() {
141141

142142
SubTrajectory trajectory;
143143
trajectory.setCost(0.0);
144-
trajectory.setComment(std::to_string(current_angle_));
144+
trajectory.setComment(std::to_string(current_angle));
145145

146146
// add frame at target pose
147147
rviz_marker_tools::appendFrame(trajectory.markers(), target_pose_msg, 0.1, "grasp frame");

core/test/test_container.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -11,14 +11,14 @@
1111

1212
using namespace moveit::task_constructor;
1313

14-
static unsigned int mock_id = 0;
14+
static unsigned int MOCK_ID = 0;
1515

1616
class GeneratorMockup : public Generator
1717
{
1818
int runs = 0;
1919

2020
public:
21-
GeneratorMockup(int runs = 0) : Generator("generator " + std::to_string(++mock_id)), runs(runs) {}
21+
GeneratorMockup(int runs = 0) : Generator("generator " + std::to_string(++MOCK_ID)), runs(runs) {}
2222
bool canCompute() const override { return runs > 0; }
2323
void compute() override {
2424
if (runs > 0)
@@ -30,7 +30,7 @@ class MonitoringGeneratorMockup : public MonitoringGenerator
3030
{
3131
public:
3232
MonitoringGeneratorMockup(Stage* monitored)
33-
: MonitoringGenerator("monitoring generator " + std::to_string(++mock_id), monitored) {}
33+
: MonitoringGenerator("monitoring generator " + std::to_string(++MOCK_ID), monitored) {}
3434
bool canCompute() const override { return false; }
3535
void compute() override {}
3636
void onNewSolution(const SolutionBase& /*solution*/) override {}
@@ -43,7 +43,7 @@ class PropagatorMockup : public PropagatingEitherWay
4343

4444
public:
4545
PropagatorMockup(int fw = 0, int bw = 0)
46-
: PropagatingEitherWay("propagate " + std::to_string(++mock_id)), fw_runs(fw), bw_runs(bw) {}
46+
: PropagatingEitherWay("propagate " + std::to_string(++MOCK_ID)), fw_runs(fw), bw_runs(bw) {}
4747
void computeForward(const InterfaceState& /* from */) override {
4848
if (fw_runs > 0)
4949
--fw_runs;
@@ -58,15 +58,15 @@ class ForwardMockup : public PropagatorMockup
5858
public:
5959
ForwardMockup(int runs = 0) : PropagatorMockup(runs, 0) {
6060
restrictDirection(FORWARD);
61-
setName("forward " + std::to_string(mock_id));
61+
setName("forward " + std::to_string(MOCK_ID));
6262
}
6363
};
6464
class BackwardMockup : public PropagatorMockup
6565
{
6666
public:
6767
BackwardMockup(int runs = 0) : PropagatorMockup(0, runs) {
6868
restrictDirection(BACKWARD);
69-
setName("backward " + std::to_string(mock_id));
69+
setName("backward " + std::to_string(MOCK_ID));
7070
}
7171
};
7272

@@ -75,7 +75,7 @@ class ConnectMockup : public Connecting
7575
int runs = 0;
7676

7777
public:
78-
ConnectMockup(int runs = 0) : Connecting("connect " + std::to_string(++mock_id)), runs(runs) {}
78+
ConnectMockup(int runs = 0) : Connecting("connect " + std::to_string(++MOCK_ID)), runs(runs) {}
7979
void compute(const InterfaceState& /* from */, const InterfaceState& /* to */) override {
8080
if (runs > 0)
8181
--runs;
@@ -189,7 +189,7 @@ class InitTest : public ::testing::Test
189189
}
190190
void initContainer(const std::initializer_list<StageType>& types = {}) {
191191
container.clear();
192-
mock_id = 0;
192+
MOCK_ID = 0;
193193
append(container, types);
194194
}
195195

demo/src/pick_place_task.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -117,13 +117,13 @@ void PickPlaceTask::init() {
117117
* Current State *
118118
* *
119119
***************************************************/
120-
Stage* current_state = nullptr; // Forward current_state on to grasp pose generator
120+
Stage* current_state_ptr = nullptr; // Forward current_state on to grasp pose generator
121121
{
122-
auto _current_state = std::make_unique<stages::CurrentState>("current state");
122+
auto current_state = std::make_unique<stages::CurrentState>("current state");
123123

124124
// Verify that object is not attached
125125
auto applicability_filter =
126-
std::make_unique<stages::PredicateFilter>("applicability test", std::move(_current_state));
126+
std::make_unique<stages::PredicateFilter>("applicability test", std::move(current_state));
127127
applicability_filter->setPredicate([object](const SolutionBase& s, std::string& comment) {
128128
if (s.start()->scene()->getCurrentState().hasAttachedBody(object)) {
129129
comment = "object with id '" + object + "' is already attached and cannot be picked";
@@ -132,7 +132,7 @@ void PickPlaceTask::init() {
132132
return true;
133133
});
134134

135-
current_state = applicability_filter.get();
135+
current_state_ptr = applicability_filter.get();
136136
t.add(std::move(applicability_filter));
137137
}
138138

@@ -201,7 +201,7 @@ void PickPlaceTask::init() {
201201
stage->setPreGraspPose(hand_open_pose_);
202202
stage->setObject(object);
203203
stage->setAngleDelta(M_PI / 12);
204-
stage->setMonitoredStage(current_state); // Hook into current state
204+
stage->setMonitoredStage(current_state_ptr); // Hook into current state
205205

206206
// Compute IK
207207
auto wrapper = std::make_unique<stages::ComputeIK>("grasp pose IK", std::move(stage));

visualization/motion_planning_tasks/properties/property_factory.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -80,8 +80,8 @@ PropertyFactory::PropertyFactory() {
8080
}
8181

8282
PropertyFactory& PropertyFactory::instance() {
83-
static PropertyFactory instance_;
84-
return instance_;
83+
static PropertyFactory instance;
84+
return instance;
8585
}
8686

8787
void PropertyFactory::registerType(const std::string& type_name, const PropertyFactoryFunction& f) {

0 commit comments

Comments
 (0)