mirror of https://github.com/ArduPilot/ardupilot
AP_Common: Add % operator to TSIndex
This commit is contained in:
parent
b3a2b360e6
commit
ab2dea5b86
|
@ -49,6 +49,11 @@ public:
|
|||
return typesafe_index(p++);
|
||||
}
|
||||
|
||||
typesafe_index operator%(const base_type& val)
|
||||
{
|
||||
return typesafe_index(p % val);
|
||||
}
|
||||
|
||||
bool operator<(const base_type& val) const
|
||||
{
|
||||
return (p<val);
|
||||
|
@ -110,4 +115,4 @@ public:
|
|||
{
|
||||
return _priv_instance[index.get_int()];
|
||||
}
|
||||
};
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue