diff --git a/core/include/moveit/task_constructor/stage_p.h b/core/include/moveit/task_constructor/stage_p.h index b965ac19..21dcee2a 100644 --- a/core/include/moveit/task_constructor/stage_p.h +++ b/core/include/moveit/task_constructor/stage_p.h @@ -50,9 +50,13 @@ #include // define pimpl() functions accessing correctly casted pimpl_ pointer -#define PIMPL_FUNCTIONS(Class) \ - const Class##Private* Class::pimpl() const { return static_cast(pimpl_); } \ - Class##Private* Class::pimpl() { return static_cast(pimpl_); } +#define PIMPL_FUNCTIONS(Class) \ + const Class##Private* Class::pimpl() const { \ + return static_cast(pimpl_); \ + } \ + Class##Private* Class::pimpl() { \ + return static_cast(pimpl_); \ + } namespace moveit { namespace task_constructor { diff --git a/core/src/cost_terms.cpp b/core/src/cost_terms.cpp index 4bd6ebad..4373d7d1 100644 --- a/core/src/cost_terms.cpp +++ b/core/src/cost_terms.cpp @@ -241,8 +241,8 @@ double Clearance::operator()(const SubTrajectory& s, std::string& comment) const auto& state_properties{ state->properties() }; auto& stage_properties{ s.creator()->properties() }; request.group_name = state_properties.hasProperty(group_property) ? - state_properties.get(group_property) : - stage_properties.get(group_property); + state_properties.get(group_property) : + stage_properties.get(group_property); // look at all forbidden collisions involving group_name request.enableGroup(state->scene()->getRobotModel()); diff --git a/core/src/stages/compute_ik.cpp b/core/src/stages/compute_ik.cpp index bf0fa4a4..9ae90004 100644 --- a/core/src/stages/compute_ik.cpp +++ b/core/src/stages/compute_ik.cpp @@ -289,7 +289,7 @@ void ComputeIK::compute() { if (value.empty()) { // property undefined // determine IK link from eef/group if (!(link = eef_jmg ? robot_model->getLinkModel(eef_jmg->getEndEffectorParentGroup().second) : - jmg->getOnlyOneEndEffectorTip())) { + jmg->getOnlyOneEndEffectorTip())) { ROS_WARN_STREAM_NAMED("ComputeIK", "Failed to derive IK target link"); return; } diff --git a/core/src/stages/modify_planning_scene.cpp b/core/src/stages/modify_planning_scene.cpp index dd24c759..36a808d8 100644 --- a/core/src/stages/modify_planning_scene.cpp +++ b/core/src/stages/modify_planning_scene.cpp @@ -112,7 +112,7 @@ void ModifyPlanningScene::attachObjects(planning_scene::PlanningScene& scene, if (invert) attach = !attach; obj.object.operation = attach ? static_cast(moveit_msgs::CollisionObject::ADD) : - static_cast(moveit_msgs::CollisionObject::REMOVE); + static_cast(moveit_msgs::CollisionObject::REMOVE); for (const std::string& name : pair.second.first) { obj.object.id = name; scene.processAttachedCollisionObjectMsg(obj); diff --git a/core/src/stages/simple_grasp.cpp b/core/src/stages/simple_grasp.cpp index 8268eb85..85ed2fdf 100644 --- a/core/src/stages/simple_grasp.cpp +++ b/core/src/stages/simple_grasp.cpp @@ -129,7 +129,7 @@ void SimpleGraspBase::setup(std::unique_ptr&& generator, bool forward) { const std::string& eef = p.get("eef"); moveit_msgs::AttachedCollisionObject obj; obj.object.operation = forward ? static_cast(moveit_msgs::CollisionObject::ADD) : - static_cast(moveit_msgs::CollisionObject::REMOVE); + static_cast(moveit_msgs::CollisionObject::REMOVE); obj.link_name = scene->getRobotModel()->getEndEffector(eef)->getEndEffectorParentGroup().second; obj.object.id = p.get("object"); scene->processAttachedCollisionObjectMsg(obj); diff --git a/core/test/test_stage.cpp b/core/test/test_stage.cpp index 298d8c3f..1a81b438 100644 --- a/core/test/test_stage.cpp +++ b/core/test/test_stage.cpp @@ -119,7 +119,7 @@ void attachObject(PlanningScene& scene, const std::string& object, const std::st moveit_msgs::AttachedCollisionObject obj; obj.link_name = link; obj.object.operation = attach ? static_cast(moveit_msgs::CollisionObject::ADD) : - static_cast(moveit_msgs::CollisionObject::REMOVE); + static_cast(moveit_msgs::CollisionObject::REMOVE); obj.object.id = object; scene.processAttachedCollisionObjectMsg(obj); } diff --git a/visualization/motion_planning_tasks/properties/property_from_yaml.cpp b/visualization/motion_planning_tasks/properties/property_from_yaml.cpp index a46d18bf..c8763aff 100644 --- a/visualization/motion_planning_tasks/properties/property_from_yaml.cpp +++ b/visualization/motion_planning_tasks/properties/property_from_yaml.cpp @@ -53,7 +53,7 @@ class ScopedYamlEvent { public: ~ScopedYamlEvent() { yaml_event_delete(&event_); } - operator yaml_event_t const &() const { return event_; } + operator yaml_event_t const&() const { return event_; } operator yaml_event_t&() { return event_; } private: