mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
fix clang-tidy warnings
- virtual functions used in constructor / destructor - captured variable in lambda expression not used - unhandled enums in switch
This commit is contained in:
parent
ea75070155
commit
11fb15fd0c
@ -7,12 +7,12 @@
|
||||
#include <algorithm>
|
||||
|
||||
/// ValueOrPointeeLess provides correct comparison for plain and pointer-like types
|
||||
template <typename T, typename Default = void>
|
||||
template <typename T, typename = bool>
|
||||
struct ValueOrPointeeLess : public std::less<T> {};
|
||||
|
||||
/// The following template-specialization is for pointer-like types
|
||||
template <typename T>
|
||||
struct ValueOrPointeeLess<T, decltype(*std::declval<T>(), std::declval<void>())> {
|
||||
struct ValueOrPointeeLess<T, decltype(*std::declval<T>() < *std::declval<T>())> {
|
||||
bool operator()(const T& x, const T& y) const {
|
||||
return *x < *y;
|
||||
}
|
||||
|
||||
@ -192,6 +192,8 @@ class StagePrivate;
|
||||
/// abstract base class for solutions (primitive and sequences)
|
||||
class SolutionBase {
|
||||
public:
|
||||
virtual ~SolutionBase() = default;
|
||||
|
||||
inline const InterfaceState* start() const { return start_; }
|
||||
inline const InterfaceState* end() const { return end_; }
|
||||
|
||||
|
||||
@ -89,7 +89,7 @@ public:
|
||||
|
||||
// TODO: use Stage::insert as well?
|
||||
void add(Stage::pointer &&stage);
|
||||
void clear() override;
|
||||
void clear() final;
|
||||
|
||||
/// enable introspection publishing for use with rviz
|
||||
void enableIntrospection(bool enable = true);
|
||||
@ -103,7 +103,7 @@ public:
|
||||
void erase(TaskCallbackList::const_iterator which);
|
||||
|
||||
/// reset all stages
|
||||
void reset() override;
|
||||
void reset() final;
|
||||
/// initialize all stages with given scene
|
||||
void init();
|
||||
|
||||
|
||||
@ -836,7 +836,7 @@ WrapperBase::WrapperBase(const std::string &name, Stage::pointer &&child)
|
||||
WrapperBase::WrapperBase(WrapperBasePrivate *impl, Stage::pointer &&child)
|
||||
: ParallelContainerBase(impl)
|
||||
{
|
||||
if (child) insert(std::move(child));
|
||||
if (child) WrapperBase::insert(std::move(child));
|
||||
}
|
||||
|
||||
bool WrapperBase::insert(Stage::pointer &&stage, int before)
|
||||
|
||||
@ -379,7 +379,7 @@ void ComputeIK::compute()
|
||||
tried_current_state_as_seed= true;
|
||||
|
||||
size_t previous = ik_solutions.size();
|
||||
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), 1, remaining_time, isValid);
|
||||
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), remaining_time, isValid);
|
||||
|
||||
auto now = std::chrono::steady_clock::now();
|
||||
remaining_time -= std::chrono::duration<double>(now - start_time).count();
|
||||
|
||||
@ -153,6 +153,8 @@ void GeneratePlacePose::compute() {
|
||||
target_pose.linear() = orig_object_pose.linear();
|
||||
spawner(target_pose, 1);
|
||||
return;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@ -91,7 +91,7 @@ void SimpleGraspBase::setup(std::unique_ptr<Stage>&& generator, bool forward)
|
||||
p.declare<std::string>("object");
|
||||
p.configureInitFrom(Stage::PARENT | Stage::INTERFACE, { "eef", "object" });
|
||||
|
||||
allow_touch->setCallback([this, forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){
|
||||
allow_touch->setCallback([forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){
|
||||
collision_detection::AllowedCollisionMatrix& acm = scene->getAllowedCollisionMatrixNonConst();
|
||||
const std::string& eef = p.get<std::string>("eef");
|
||||
const std::string& object = p.get<std::string>("object");
|
||||
@ -125,7 +125,7 @@ void SimpleGraspBase::setup(std::unique_ptr<Stage>&& generator, bool forward)
|
||||
p.declare<std::string>("object");
|
||||
p.configureInitFrom(Stage::PARENT | Stage::INTERFACE, { "eef", "object" });
|
||||
|
||||
attach->setCallback([this, forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){
|
||||
attach->setCallback([forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){
|
||||
const std::string& eef = p.get<std::string>("eef");
|
||||
moveit_msgs::AttachedCollisionObject obj;
|
||||
obj.object.operation = forward ? (int8_t) moveit_msgs::CollisionObject::ADD
|
||||
|
||||
@ -187,7 +187,7 @@ void Task::enableIntrospection(bool enable)
|
||||
else if (!enable && introspection_) {
|
||||
// reset introspection instance of all stages
|
||||
pimpl()->setIntrospection(nullptr);
|
||||
pimpl()->traverseStages([this](Stage& stage, int) {
|
||||
pimpl()->traverseStages([](Stage& stage, int) {
|
||||
stage.pimpl()->setIntrospection(nullptr);
|
||||
return true;
|
||||
}, 1, UINT_MAX);
|
||||
|
||||
@ -25,7 +25,7 @@ public:
|
||||
pimpl()->setNextStarts(next);
|
||||
}
|
||||
|
||||
void init(const moveit::core::RobotModelConstPtr &robot_model) {
|
||||
void init(const moveit::core::RobotModelConstPtr &robot_model) override {
|
||||
ps.reset((new PlanningScene(robot_model)));
|
||||
}
|
||||
|
||||
|
||||
@ -133,6 +133,7 @@ rviz::Property* Parser::process(const yaml_event_t& event,
|
||||
case YAML_SEQUENCE_START_EVENT: return processSequence(name, description, old);
|
||||
case YAML_MAPPING_START_EVENT: return processMapping(name, description, old);
|
||||
case YAML_SCALAR_EVENT: return createScalar(name, description, byteArray(event), old);
|
||||
default: break;
|
||||
}
|
||||
assert(false); // should not be reached
|
||||
}
|
||||
|
||||
Loading…
Reference in New Issue
Block a user