Skip to content

Commit 325c401

Browse files
committed
Merge branch 'master' into ros2
2 parents b4a3709 + 4dfcf09 commit 325c401

File tree

30 files changed

+48
-50
lines changed

30 files changed

+48
-50
lines changed

.github/workflows/ci.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ jobs:
4747
# perform full clang-tidy check only on manual trigger (workflow_dispatch), PRs do check changed files, otherwise nothing
4848
CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }}
4949
CC: ${{ matrix.env.CLANG_TIDY && 'clang' }}
50-
CXX: ${{ matrix.env.CLANG_TIDY && 'clang++' }}
50+
CXX: ${{ matrix.env.CLANG_TIDY && 'clang++ -std=c++17' }}
5151

5252
name: "${{ matrix.env.IMAGE }}${{ matrix.env.NAME && ' • ' || ''}}${{ matrix.env.NAME }}${{ matrix.env.CLANG_TIDY && ' • clang-tidy' || '' }}"
5353
runs-on: ubuntu-latest

.github/workflows/format.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ jobs:
1818
submodules: recursive
1919
- name: Install clang-format-14
2020
run: sudo apt-get install clang-format-14
21-
- uses: rhaschke/pre-commit-action@main
21+
- uses: pre-commit/action@v3.0.1
2222
id: precommit
2323
- name: Upload pre-commit changes
2424
if: failure() && steps.precommit.outcome == 'failure'

core/include/moveit/task_constructor/cost_terms.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ class CostTerm
7070
class TrajectoryCostTerm : public CostTerm
7171
{
7272
public:
73-
enum class Mode
73+
enum class Mode : uint8_t
7474
{
7575
AUTO /* TRAJECTORY, or START_INTERFACE if no trajectory is given */,
7676
START_INTERFACE,

core/include/moveit/task_constructor/solvers/cartesian_path.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class CartesianPath : public PlannerInterface
6060
void setStepSize(double step_size) { setProperty("step_size", step_size); }
6161
void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); }
6262
template <typename T = float>
63-
void setJumpThreshold(double) {
63+
void setJumpThreshold(double /*unused*/) {
6464
static_assert(std::is_integral<T>::value, "setJumpThreshold() is deprecated. Replace with setPrecision.");
6565
}
6666
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }

core/include/moveit/task_constructor/stage.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ MOVEIT_CLASS_FORWARD(RobotTrajectory);
7272
namespace moveit {
7373
namespace task_constructor {
7474

75-
enum InterfaceFlag
75+
enum InterfaceFlag : uint8_t
7676
{
7777
READS_START = 0x01,
7878
READS_END = 0x02,
@@ -155,7 +155,7 @@ class Stage
155155
*
156156
* INTERFACE takes precedence over PARENT.
157157
*/
158-
enum PropertyInitializerSource
158+
enum PropertyInitializerSource : uint8_t
159159
{ // TODO: move to property.cpp
160160
DEFAULT = 0,
161161
MANUAL = 1,
@@ -293,7 +293,7 @@ class PropagatingEitherWay : public ComputeBase
293293
PRIVATE_CLASS(PropagatingEitherWay)
294294
PropagatingEitherWay(const std::string& name = "propagating either way");
295295

296-
enum Direction
296+
enum Direction : uint8_t
297297
{
298298
AUTO = 0x00, // auto-derive direction from context
299299
FORWARD = 0x01, // propagate forward only

core/include/moveit/task_constructor/stages/connect.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ class Connect : public Connecting
6767
bool compatible(const InterfaceState& from_state, const InterfaceState& to_state) const override;
6868

6969
public:
70-
enum MergeMode
70+
enum MergeMode : uint8_t
7171
{
7272
SEQUENTIAL = 0,
7373
WAYPOINTS = 1

core/include/moveit/task_constructor/stages/generate_random_pose.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,8 @@ class GenerateRandomPose : public GeneratePose
5656

5757
/** Function signature for pose dimension samplers.
5858
* The input parameter is the seed, the returned value is the sampling result. */
59-
typedef std::function<double(double)> PoseDimensionSampler;
60-
enum PoseDimension
59+
using PoseDimensionSampler = std::function<double(double)>;
60+
enum PoseDimension : uint8_t
6161
{
6262
X,
6363
Y,

core/include/moveit/task_constructor/storage.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ class InterfaceState
8181
friend class ContainerBasePrivate; // allow setting priority_ for pruning
8282

8383
public:
84-
enum Status
84+
enum Status : uint8_t
8585
{
8686
ENABLED, // state is actively considered during planning
8787
ARMED, // disabled state in a Connecting interface that will become re-enabled with a new opposite state
@@ -198,12 +198,12 @@ class Interface : public ordered<InterfaceState*>
198198
const InterfaceState* operator->() const noexcept { return base_type::const_iterator::operator*(); }
199199
};
200200

201-
enum Direction
201+
enum Direction : uint8_t
202202
{
203203
FORWARD,
204204
BACKWARD,
205205
};
206-
enum Update
206+
enum Update : uint8_t
207207
{
208208
STATUS = 1 << 0,
209209
PRIORITY = 1 << 1,

core/python/bindings/src/properties.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class PropertyConverterRegistry
5959
PropertyConverterBase::from_python_converter_function from_;
6060
};
6161
// map from type_index to corresponding converter functions
62-
typedef std::map<std::type_index, Entry> RegistryMap;
62+
using RegistryMap = std::map<std::type_index, Entry>;
6363
RegistryMap types_;
6464
// map from ros-msg-names to entry in types_
6565
using RosMsgTypeNameMap = std::map<std::string, RegistryMap::iterator>;

core/src/container.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -63,24 +63,24 @@ printChildrenInterfaces(const ContainerBasePrivate& container, bool success, con
6363
std::ostream& os = std::cerr) {
6464
static unsigned int id = 0;
6565
const unsigned int width = 10; // indentation of name
66-
os << std::endl << (success ? '+' : '-') << ' ' << creator.name() << ' ';
66+
os << '\n' << (success ? '+' : '-') << ' ' << creator.name() << ' ';
6767
if (success)
6868
os << ++id << ' ';
6969
if (const auto conn = dynamic_cast<const ConnectingPrivate*>(creator.pimpl()))
7070
os << conn->pendingPairsPrinter();
71-
os << std::endl;
71+
os << '\n';
7272

7373
for (const auto& child : container.children()) {
7474
auto cimpl = child->pimpl();
7575
os << std::setw(width) << std::left << child->name();
7676
if (!cimpl->starts() && !cimpl->ends())
77-
os << "" << std::endl;
77+
os << "\n";
7878
if (cimpl->starts())
79-
os << "" << *child->pimpl()->starts() << std::endl;
79+
os << "" << *child->pimpl()->starts() << '\n';
8080
if (cimpl->starts() && cimpl->ends())
8181
os << std::setw(width) << " ";
8282
if (cimpl->ends())
83-
os << "" << *child->pimpl()->ends() << std::endl;
83+
os << "" << *child->pimpl()->ends() << '\n';
8484
}
8585
}
8686

@@ -460,7 +460,7 @@ void ContainerBase::explainFailure(std::ostream& os) const {
460460
if (stage->numFailures()) {
461461
os << stage->name() << " (0/" << stage->numFailures() << ")";
462462
stage->explainFailure(os);
463-
os << std::endl;
463+
os << '\n';
464464
break;
465465
}
466466
stage->explainFailure(os); // recursively process children
@@ -469,7 +469,7 @@ void ContainerBase::explainFailure(std::ostream& os) const {
469469

470470
std::ostream& operator<<(std::ostream& os, const ContainerBase& container) {
471471
ContainerBase::StageCallback processor = [&os](const Stage& stage, unsigned int depth) -> bool {
472-
os << std::string(2 * depth, ' ') << *stage.pimpl() << std::endl;
472+
os << std::string(2 * depth, ' ') << *stage.pimpl() << '\n';
473473
return true;
474474
};
475475
container.traverseRecursively(processor);

0 commit comments

Comments
 (0)