clang-tidy: use using over typedef

$ run-clang-tidy.py -header-filter='.*' -checks='modernize-use-using' -fix

add .clang-tidy file
This commit is contained in:
v4hn 2020-05-17 20:49:35 +02:00
parent c662311a78
commit 36166348bc
23 changed files with 101 additions and 68 deletions

38
.clang-tidy Normal file
View File

@ -0,0 +1,38 @@
---
Checks: '-*,
modernize-use-using,
'
HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h'
AnalyzeTemporaryDtors: false
CheckOptions:
- key: llvm-namespace-comment.ShortNamespaceLines
value: '10'
- key: llvm-namespace-comment.SpacesBeforeComments
value: '2'
- key: readability-braces-around-statements.ShortStatementLines
value: '2'
# type names
- key: readability-identifier-naming.ClassCase
value: CamelCase
- key: readability-identifier-naming.EnumCase
value: CamelCase
- key: readability-identifier-naming.UnionCase
value: CamelCase
# method names
- key: readability-identifier-naming.MethodCase
value: camelBack
# variable names
- key: readability-identifier-naming.VariableCase
value: lower_case
- key: readability-identifier-naming.ClassMemberSuffix
value: '_'
# const static or global variables are UPPER_CASE
- key: readability-identifier-naming.EnumConstantCase
value: UPPER_CASE
- key: readability-identifier-naming.StaticConstantCase
value: UPPER_CASE
- key: readability-identifier-naming.ClassConstantCase
value: UPPER_CASE
- key: readability-identifier-naming.GlobalVariableCase
value: UPPER_CASE
...

View File

@ -49,14 +49,14 @@ class ContainerBase : public Stage
{ {
public: public:
PRIVATE_CLASS(ContainerBase) PRIVATE_CLASS(ContainerBase)
typedef std::unique_ptr<ContainerBase> pointer; using pointer = std::unique_ptr<ContainerBase>;
size_t numChildren() const; size_t numChildren() const;
Stage* findChild(const std::string& name) const; Stage* findChild(const std::string& name) const;
/** Callback function type used by traverse functions /** Callback function type used by traverse functions
* The callback should return false if traversal should be stopped. */ * The callback should return false if traversal should be stopped. */
typedef std::function<bool(const Stage&, unsigned int depth)> StageCallback; using StageCallback = std::function<bool(const Stage&, unsigned int)>;
/// traverse direct children of this container, calling the callback for each of them /// traverse direct children of this container, calling the callback for each of them
bool traverseChildren(const StageCallback& processor) const; bool traverseChildren(const StageCallback& processor) const;
/// traverse all children of this container recursively /// traverse all children of this container recursively
@ -98,8 +98,7 @@ protected:
/// called by a (direct) child when a new solution becomes available /// called by a (direct) child when a new solution becomes available
void onNewSolution(const SolutionBase& s) override; void onNewSolution(const SolutionBase& s) override;
typedef std::function<void(const SolutionSequence::container_type& trace, double trace_accumulated_cost)> using SolutionProcessor = std::function<void(const SolutionSequence::container_type&, double)>;
SolutionProcessor;
/// Traverse all solution pathes starting at start and going in given direction dir /// Traverse all solution pathes starting at start and going in given direction dir
/// until the end, i.e. until there are no more subsolutions in the given direction /// until the end, i.e. until there are no more subsolutions in the given direction

View File

@ -75,10 +75,10 @@ class ContainerBasePrivate : public StagePrivate
friend void swap(StagePrivate*& lhs, StagePrivate*& rhs); friend void swap(StagePrivate*& lhs, StagePrivate*& rhs);
public: public:
typedef StagePrivate::container_type container_type; using container_type = StagePrivate::container_type;
typedef container_type::iterator iterator; using iterator = container_type::iterator;
typedef container_type::const_iterator const_iterator; using const_iterator = container_type::const_iterator;
typedef std::function<bool(Stage&, int depth)> NonConstStageCallback; using NonConstStageCallback = std::function<bool(Stage&, int)>;
inline const container_type& children() const { return children_; } inline const container_type& children() const { return children_; }
@ -242,13 +242,13 @@ class MergerPrivate : public ParallelContainerBasePrivate
friend class Merger; friend class Merger;
moveit::core::JointModelGroupPtr jmg_merged_; moveit::core::JointModelGroupPtr jmg_merged_;
typedef std::vector<const SubTrajectory*> ChildSolutionList; using ChildSolutionList = std::vector<const SubTrajectory*>;
typedef std::map<const StagePrivate*, ChildSolutionList> ChildSolutionMap; using ChildSolutionMap = std::map<const StagePrivate*, ChildSolutionList>;
// map from external source state (iterator) to all corresponding children's solutions // map from external source state (iterator) to all corresponding children's solutions
std::map<InterfaceState*, ChildSolutionMap> source_state_to_solutions_; std::map<InterfaceState*, ChildSolutionMap> source_state_to_solutions_;
public: public:
typedef std::function<void(SubTrajectory&&)> Spawner; using Spawner = std::function<void(SubTrajectory&&)>;
MergerPrivate(Merger* me, const std::string& name); MergerPrivate(Merger* me, const std::string& name);
void resolveInterface(InterfaceFlags expected) override; void resolveInterface(InterfaceFlags expected) override;

View File

@ -30,21 +30,21 @@ class ordered
{ {
public: public:
typedef std::list<T> container_type; typedef std::list<T> container_type;
typedef typename container_type::value_type value_type; using value_type = typename container_type::value_type;
typedef typename container_type::size_type size_type; using size_type = typename container_type::size_type;
typedef typename container_type::difference_type difference_type; using difference_type = typename container_type::difference_type;
typedef typename container_type::reference reference; using reference = typename container_type::reference;
typedef typename container_type::const_reference const_reference; using const_reference = typename container_type::const_reference;
typedef typename container_type::pointer pointer; using pointer = typename container_type::pointer;
typedef typename container_type::const_pointer const_pointer; using const_pointer = typename container_type::const_pointer;
typedef typename container_type::iterator iterator; using iterator = typename container_type::iterator;
typedef typename container_type::const_iterator const_iterator; using const_iterator = typename container_type::const_iterator;
typedef typename container_type::reverse_iterator reverse_iterator; using reverse_iterator = typename container_type::reverse_iterator;
typedef typename container_type::const_reverse_iterator const_reverse_iterator; using const_reverse_iterator = typename container_type::const_reverse_iterator;
protected: protected:
container_type c; container_type c;
@ -133,7 +133,7 @@ namespace detail {
template <typename ValueType, typename CostType> template <typename ValueType, typename CostType>
struct ItemCostPair : std::pair<ValueType, CostType> struct ItemCostPair : std::pair<ValueType, CostType>
{ {
typedef CostType cost_type; using cost_type = CostType;
ItemCostPair(const std::pair<ValueType, CostType>& other) : std::pair<ValueType, CostType>(other) {} ItemCostPair(const std::pair<ValueType, CostType>& other) : std::pair<ValueType, CostType>(other) {}
ItemCostPair(std::pair<ValueType, CostType>&& other) : std::pair<ValueType, CostType>(std::move(other)) {} ItemCostPair(std::pair<ValueType, CostType>&& other) : std::pair<ValueType, CostType>(std::move(other)) {}
@ -153,7 +153,7 @@ template <typename ValueType, typename CostType = double,
typename Compare = std::less<detail::ItemCostPair<ValueType, CostType>>> typename Compare = std::less<detail::ItemCostPair<ValueType, CostType>>>
class cost_ordered : public ordered<detail::ItemCostPair<ValueType, CostType>, Compare> class cost_ordered : public ordered<detail::ItemCostPair<ValueType, CostType>, Compare>
{ {
typedef ordered<detail::ItemCostPair<ValueType, CostType>, Compare> base_type; using base_type = ordered<detail::ItemCostPair<ValueType, CostType>, Compare>;
public: public:
auto insert(const ValueType& value, const CostType cost) { return base_type::insert(std::make_pair(value, cost)); } auto insert(const ValueType& value, const CostType cost) { return base_type::insert(std::make_pair(value, cost)); }

View File

@ -19,7 +19,7 @@ namespace moveit {
namespace task_constructor { namespace task_constructor {
/** signature of callback function, passing the generated marker and the name of the robot link / scene object */ /** signature of callback function, passing the generated marker and the name of the robot link / scene object */
typedef std::function<void(visualization_msgs::Marker&, const std::string&)> MarkerCallback; using MarkerCallback = std::function<void(visualization_msgs::Marker&, const std::string&)>;
/** generate marker msgs to visualize the planning scene, calling the given callback for each of them /** generate marker msgs to visualize the planning scene, calling the given callback for each of them
* object_names: set of links to include (or all if empty) */ * object_names: set of links to include (or all if empty) */

View File

@ -89,9 +89,9 @@ public:
/// exception thrown when trying to set a value not matching the declared type /// exception thrown when trying to set a value not matching the declared type
class type_error; class type_error;
typedef uint SourceFlags; using SourceFlags = uint;
/// function callback used to initialize property value from another PropertyMap /// function callback used to initialize property value from another PropertyMap
typedef std::function<boost::any(const PropertyMap& other)> InitializerFunction; using InitializerFunction = std::function<boost::any(const PropertyMap&)>;
/// set current value and default value /// set current value and default value
void setValue(const boost::any& value); void setValue(const boost::any& value);
@ -191,8 +191,8 @@ struct hasDeserialize<T, decltype(std::declval<std::istream&>() >> std::declval<
class PropertySerializerBase class PropertySerializerBase
{ {
public: public:
typedef std::string (*SerializeFunction)(const boost::any&); using SerializeFunction = std::string (*)(const boost::any&);
typedef boost::any (*DeserializeFunction)(const std::string&); using DeserializeFunction = boost::any (*)(const std::string&);
static std::string dummySerialize(const boost::any&) { return ""; } static std::string dummySerialize(const boost::any&) { return ""; }
static boost::any dummyDeserialize(const std::string&) { return boost::any(); } static boost::any dummyDeserialize(const std::string&) { return boost::any(); }
@ -288,8 +288,8 @@ public:
Property& property(const std::string& name); Property& property(const std::string& name);
const Property& property(const std::string& name) const { return const_cast<PropertyMap*>(this)->property(name); } const Property& property(const std::string& name) const { return const_cast<PropertyMap*>(this)->property(name); }
typedef std::map<std::string, Property>::iterator iterator; using iterator = std::map<std::string, Property>::iterator;
typedef std::map<std::string, Property>::const_iterator const_iterator; using const_iterator = std::map<std::string, Property>::const_iterator;
iterator begin() { return props_.begin(); } iterator begin() { return props_.begin(); }
iterator end() { return props_.end(); } iterator end() { return props_.end(); }

View File

@ -84,7 +84,7 @@ enum InterfaceFlag
GENERATE = WRITES_PREV_END | WRITES_NEXT_START, GENERATE = WRITES_PREV_END | WRITES_NEXT_START,
}; };
typedef Flags<InterfaceFlag> InterfaceFlags; using InterfaceFlags = Flags<InterfaceFlag>;
/** invert interface such that /** invert interface such that
* - new end can connect to old start * - new end can connect to old start
@ -111,7 +111,7 @@ constexpr InterfaceFlags END_IF_MASK({ READS_END, WRITES_NEXT_START });
MOVEIT_CLASS_FORWARD(Interface) MOVEIT_CLASS_FORWARD(Interface)
MOVEIT_CLASS_FORWARD(Stage) MOVEIT_CLASS_FORWARD(Stage)
class InterfaceState; class InterfaceState;
typedef std::pair<const InterfaceState&, const InterfaceState&> InterfaceStatePair; using InterfaceStatePair = std::pair<const InterfaceState&, const InterfaceState&>;
/// exception thrown by Stage::init() /// exception thrown by Stage::init()
/// It collects individual errors in stages throughout the pipeline to allow overall error reporting /// It collects individual errors in stages throughout the pipeline to allow overall error reporting
@ -144,7 +144,7 @@ class Stage
{ {
public: public:
PRIVATE_CLASS(Stage) PRIVATE_CLASS(Stage)
typedef std::unique_ptr<Stage> pointer; using pointer = std::unique_ptr<Stage>;
/** Names for property initialization sources /** Names for property initialization sources
* *
* - INTERFACE allows to pass properties from one stage to the next (in a SerialContainer). * - INTERFACE allows to pass properties from one stage to the next (in a SerialContainer).
@ -203,8 +203,8 @@ public:
} }
void setForwardedProperties(const std::set<std::string>& names) { setProperty("forwarded_properties", names); } void setForwardedProperties(const std::set<std::string>& names) { setProperty("forwarded_properties", names); }
typedef std::function<void(const SolutionBase& s)> SolutionCallback; using SolutionCallback = std::function<void(const SolutionBase&)>;
typedef std::list<SolutionCallback> SolutionCallbackList; using SolutionCallbackList = std::list<SolutionCallback>;
/// add function to be called for every newly found solution or failure /// add function to be called for every newly found solution or failure
SolutionCallbackList::const_iterator addSolutionCallback(SolutionCallback&& cb); SolutionCallbackList::const_iterator addSolutionCallback(SolutionCallback&& cb);
/// remove function callback /// remove function callback

View File

@ -280,7 +280,7 @@ class ConnectingPrivate : public ComputeBasePrivate
{ {
friend class Connecting; friend class Connecting;
typedef std::pair<Interface::const_iterator, Interface::const_iterator> StatePair; using StatePair = std::pair<Interface::const_iterator, Interface::const_iterator>;
struct StatePairLess struct StatePairLess
{ {
bool operator()(const StatePair& x, const StatePair& y) const { bool operator()(const StatePair& x, const StatePair& y) const {

View File

@ -73,7 +73,7 @@ public:
WAYPOINTS = 1 WAYPOINTS = 1
}; };
typedef std::vector<std::pair<std::string, solvers::PlannerInterfacePtr>> GroupPlannerVector; using GroupPlannerVector = std::vector<std::pair<std::string, solvers::PlannerInterfacePtr> >;
Connect(const std::string& name = "connect", const GroupPlannerVector& planners = {}); Connect(const std::string& name = "connect", const GroupPlannerVector& planners = {});
void setPathConstraints(moveit_msgs::Constraints path_constraints) { void setPathConstraints(moveit_msgs::Constraints path_constraints) {

View File

@ -65,9 +65,8 @@ namespace stages {
class ModifyPlanningScene : public PropagatingEitherWay class ModifyPlanningScene : public PropagatingEitherWay
{ {
public: public:
typedef std::vector<std::string> Names; using Names = std::vector<std::string>;
typedef std::function<void(const planning_scene::PlanningScenePtr& scene, const PropertyMap& properties)> using ApplyCallback = std::function<void(const planning_scene::PlanningScenePtr&, const PropertyMap&)>;
ApplyCallback;
ModifyPlanningScene(const std::string& name = "modify planning scene"); ModifyPlanningScene(const std::string& name = "modify planning scene");
void computeForward(const InterfaceState& from) override; void computeForward(const InterfaceState& from) override;

View File

@ -56,7 +56,7 @@ namespace stages {
class PredicateFilter : public WrapperBase class PredicateFilter : public WrapperBase
{ {
public: public:
typedef std::function<bool(const SolutionBase&, std::string&)> Predicate; using Predicate = std::function<bool(const SolutionBase&, std::string&)>;
PredicateFilter(const std::string& name, Stage::pointer&& child = Stage::pointer()); PredicateFilter(const std::string& name, Stage::pointer&& child = Stage::pointer());

View File

@ -95,7 +95,7 @@ public:
} }
bool operator<(const Priority& other) const; bool operator<(const Priority& other) const;
}; };
typedef std::deque<SolutionBase*> Solutions; using Solutions = std::deque<SolutionBase*>;
/// create an InterfaceState from a planning scene /// create an InterfaceState from a planning scene
InterfaceState(const planning_scene::PlanningScenePtr& ps); InterfaceState(const planning_scene::PlanningScenePtr& ps);
@ -135,7 +135,7 @@ private:
/** Interface provides a cost-sorted list of InterfaceStates available as input for a stage. */ /** Interface provides a cost-sorted list of InterfaceStates available as input for a stage. */
class Interface : public ordered<InterfaceState*> class Interface : public ordered<InterfaceState*>
{ {
typedef ordered<InterfaceState*> base_type; using base_type = ordered<InterfaceState*>;
public: public:
// iterators providing convinient access to stored InterfaceState // iterators providing convinient access to stored InterfaceState
@ -166,7 +166,7 @@ public:
START = FORWARD, START = FORWARD,
END = BACKWARD END = BACKWARD
}; };
typedef std::function<void(iterator it, bool updated)> NotifyFunction; using NotifyFunction = std::function<void(iterator, bool)>;
Interface(const NotifyFunction& notify = NotifyFunction()); Interface(const NotifyFunction& notify = NotifyFunction());
/// add a new InterfaceState /// add a new InterfaceState
@ -288,7 +288,7 @@ MOVEIT_CLASS_FORWARD(SubTrajectory)
class SolutionSequence : public SolutionBase class SolutionSequence : public SolutionBase
{ {
public: public:
typedef std::vector<const SolutionBase*> container_type; using container_type = std::vector<const SolutionBase*>;
explicit SolutionSequence() : SolutionBase() {} explicit SolutionSequence() : SolutionBase() {}
SolutionSequence(container_type&& subsolutions, double cost = 0.0, StagePrivate* creator = nullptr) SolutionSequence(container_type&& subsolutions, double cost = 0.0, StagePrivate* creator = nullptr)

View File

@ -101,7 +101,7 @@ public:
Introspection& introspection(); Introspection& introspection();
typedef std::function<void(const Task& t)> TaskCallback; typedef std::function<void(const Task& t)> TaskCallback;
typedef std::list<TaskCallback> TaskCallbackList; using TaskCallbackList = std::list<TaskCallback>;
/// add function to be called after each top-level iteration /// add function to be called after each top-level iteration
TaskCallbackList::const_iterator addTaskCallback(TaskCallback&& cb); TaskCallbackList::const_iterator addTaskCallback(TaskCallback&& cb);
/// remove function callback /// remove function callback

View File

@ -48,8 +48,8 @@ class Flags
static_assert((sizeof(Enum) <= sizeof(int)), "Flags uses an int as storage, this enum will overflow!"); static_assert((sizeof(Enum) <= sizeof(int)), "Flags uses an int as storage, this enum will overflow!");
public: public:
typedef typename std::conditional<std::is_unsigned<Enum>::value, unsigned int, signed int>::type Int; using Int = typename std::conditional<std::is_unsigned<Enum>::value, unsigned int, int>::type;
typedef Enum enum_type; using enum_type = Enum;
// compiler-generated copy/move ctor/assignment operators are fine! // compiler-generated copy/move ctor/assignment operators are fine!
// zero flags // zero flags

View File

@ -60,7 +60,7 @@ class PropertyTypeRegistry
typedef std::map<std::type_index, Entry> RegistryMap; typedef std::map<std::type_index, Entry> RegistryMap;
RegistryMap types_; RegistryMap types_;
// map from type names (type.name or ROS msg name) to entry in types_ // map from type names (type.name or ROS msg name) to entry in types_
typedef std::map<std::string, RegistryMap::iterator> TypeNameMap; using TypeNameMap = std::map<std::string, RegistryMap::iterator>;
TypeNameMap names_; TypeNameMap names_;
public: public:

View File

@ -129,8 +129,8 @@ Task& Task::operator=(Task&& other) {
struct PlannerCache struct PlannerCache
{ {
typedef std::tuple<std::string, std::string, std::string> PlannerID; typedef std::tuple<std::string, std::string, std::string> PlannerID;
typedef std::map<PlannerID, std::weak_ptr<planning_pipeline::PlanningPipeline>> PlannerMap; using PlannerMap = std::map<PlannerID, std::weak_ptr<planning_pipeline::PlanningPipeline> >;
typedef std::list<std::pair<std::weak_ptr<const robot_model::RobotModel>, PlannerMap>> ModelList; using ModelList = std::list<std::pair<std::weak_ptr<const robot_model::RobotModel>, PlannerMap> >;
ModelList cache_; ModelList cache_;
PlannerMap::mapped_type& retrieve(const robot_model::RobotModelConstPtr& model, PlannerID id) { PlannerMap::mapped_type& retrieve(const robot_model::RobotModelConstPtr& model, PlannerID id) {

View File

@ -131,8 +131,8 @@ template <typename ValueType, typename CostType = int>
class CostOrderedTest : public ::testing::Test class CostOrderedTest : public ::testing::Test
{ {
protected: protected:
typedef std::deque<ValueType> container_type; using container_type = std::deque<ValueType>;
typedef cost_ordered<ValueType, std::deque<ValueType>, CostType> queue_type; using queue_type = cost_ordered<ValueType, std::deque<ValueType>, CostType>;
CostOrderedTest() {} CostOrderedTest() {}
@ -148,7 +148,7 @@ protected:
void SetUp() {} void SetUp() {}
void TearDown() {} void TearDown() {}
}; };
typedef CostOrderedTest<int, int> CostOrderedTestInt; using CostOrderedTestInt = CostOrderedTest<int, int>;
TEST_F(CostOrderedTestInt, ordered_push) { TEST_F(CostOrderedTestInt, ordered_push) {
auto top = *insert(2, 2); auto top = *insert(2, 2);

View File

@ -75,14 +75,11 @@ class PropertyFactory
public: public:
static PropertyFactory& instance(); static PropertyFactory& instance();
typedef std::function<rviz::Property*(const QString& name, moveit::task_constructor::Property&, using PropertyFactoryFunction =
const planning_scene::PlanningScene* scene, std::function<rviz::Property*(const QString&, moveit::task_constructor::Property&,
rviz::DisplayContext* display_context)> const planning_scene::PlanningScene*, rviz::DisplayContext*)>;
PropertyFactoryFunction; using TreeFactoryFunction = std::function<rviz::PropertyTreeModel*(
typedef std::function<rviz::PropertyTreeModel*(moveit::task_constructor::PropertyMap&, moveit::task_constructor::PropertyMap&, const planning_scene::PlanningScene*, rviz::DisplayContext*)>;
const planning_scene::PlanningScene* scene,
rviz::DisplayContext* display_context)>
TreeFactoryFunction;
/// register a factory function for type T /// register a factory function for type T
template <typename T> template <typename T>

View File

@ -114,7 +114,7 @@ class RemoteSolutionModel : public QAbstractTableModel
inline bool operator<(const Data& other) const { return this->id < other.id; } inline bool operator<(const Data& other) const { return this->id < other.id; }
}; };
// successful and failed solutions ordered by id / creation // successful and failed solutions ordered by id / creation
typedef std::list<Data> DataList; using DataList = std::list<Data>;
DataList data_; DataList data_;
size_t num_failed_data_ = 0; // number of failed solutions in data_ size_t num_failed_data_ = 0; // number of failed solutions in data_
size_t num_failed_ = 0; // number of reported failures size_t num_failed_ = 0; // number of reported failures

View File

@ -63,7 +63,7 @@ namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(DisplaySolution) MOVEIT_CLASS_FORWARD(DisplaySolution)
MOVEIT_CLASS_FORWARD(RemoteTaskModel) MOVEIT_CLASS_FORWARD(RemoteTaskModel)
typedef PluginlibFactory<moveit::task_constructor::Stage> StageFactory; typedef PluginlibFactory<moveit::task_constructor::Stage> StageFactory;
typedef std::shared_ptr<StageFactory> StageFactoryPtr; using StageFactoryPtr = std::shared_ptr<StageFactory>;
StageFactoryPtr getStageFactory(); StageFactoryPtr getStageFactory();

View File

@ -54,7 +54,7 @@ static QPixmap maskToColorAndAlpha(const QPixmap& mask, const QColor& color) {
} }
typedef QPair<QPixmap, QColor> MaskAndColor; typedef QPair<QPixmap, QColor> MaskAndColor;
typedef QList<MaskAndColor> MasksAndColors; using MasksAndColors = QList<MaskAndColor>;
static MasksAndColors masksAndColors(const Icon& icon, int dpr) { static MasksAndColors masksAndColors(const Icon& icon, int dpr) {
MasksAndColors result; MasksAndColors result;
for (const IconMaskAndColor& i : icon) { for (const IconMaskAndColor& i : icon) {

View File

@ -36,7 +36,7 @@ class QString;
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
namespace utils { namespace utils {
typedef QPair<QString, QColor> IconMaskAndColor; using IconMaskAndColor = QPair<QString, QColor>;
// Returns a recolored icon with shadow and custom disabled state for a // Returns a recolored icon with shadow and custom disabled state for a
// series of grayscalemask|Theme::Color mask pairs // series of grayscalemask|Theme::Color mask pairs

View File

@ -98,7 +98,7 @@ public:
bool empty() const { return steps_ == 0; } bool empty() const { return steps_ == 0; }
/// pair of trajectory part and way point index within part /// pair of trajectory part and way point index within part
typedef std::pair<size_t, size_t> IndexPair; using IndexPair = std::pair<size_t, size_t>;
IndexPair indexPair(size_t index) const; IndexPair indexPair(size_t index) const;
float getWayPointDurationFromPrevious(const IndexPair& idx_pair) const; float getWayPointDurationFromPrevious(const IndexPair& idx_pair) const;