Skip to content

Commit

Permalink
Merge branch 'master' into ros2
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Dec 22, 2024
2 parents b4a3709 + 4dfcf09 commit 325c401
Show file tree
Hide file tree
Showing 30 changed files with 48 additions and 50 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ jobs:
# perform full clang-tidy check only on manual trigger (workflow_dispatch), PRs do check changed files, otherwise nothing
CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }}
CC: ${{ matrix.env.CLANG_TIDY && 'clang' }}
CXX: ${{ matrix.env.CLANG_TIDY && 'clang++' }}
CXX: ${{ matrix.env.CLANG_TIDY && 'clang++ -std=c++17' }}

name: "${{ matrix.env.IMAGE }}${{ matrix.env.NAME && ' • ' || ''}}${{ matrix.env.NAME }}${{ matrix.env.CLANG_TIDY && ' • clang-tidy' || '' }}"
runs-on: ubuntu-latest
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/format.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ jobs:
submodules: recursive
- name: Install clang-format-14
run: sudo apt-get install clang-format-14
- uses: rhaschke/pre-commit-action@main
- uses: pre-commit/action@v3.0.1
id: precommit
- name: Upload pre-commit changes
if: failure() && steps.precommit.outcome == 'failure'
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/cost_terms.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class CostTerm
class TrajectoryCostTerm : public CostTerm
{
public:
enum class Mode
enum class Mode : uint8_t
{
AUTO /* TRAJECTORY, or START_INTERFACE if no trajectory is given */,
START_INTERFACE,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class CartesianPath : public PlannerInterface
void setStepSize(double step_size) { setProperty("step_size", step_size); }
void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); }
template <typename T = float>
void setJumpThreshold(double) {
void setJumpThreshold(double /*unused*/) {
static_assert(std::is_integral<T>::value, "setJumpThreshold() is deprecated. Replace with setPrecision.");
}
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }
Expand Down
6 changes: 3 additions & 3 deletions core/include/moveit/task_constructor/stage.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ MOVEIT_CLASS_FORWARD(RobotTrajectory);
namespace moveit {
namespace task_constructor {

enum InterfaceFlag
enum InterfaceFlag : uint8_t
{
READS_START = 0x01,
READS_END = 0x02,
Expand Down Expand Up @@ -155,7 +155,7 @@ class Stage
*
* INTERFACE takes precedence over PARENT.
*/
enum PropertyInitializerSource
enum PropertyInitializerSource : uint8_t
{ // TODO: move to property.cpp
DEFAULT = 0,
MANUAL = 1,
Expand Down Expand Up @@ -293,7 +293,7 @@ class PropagatingEitherWay : public ComputeBase
PRIVATE_CLASS(PropagatingEitherWay)
PropagatingEitherWay(const std::string& name = "propagating either way");

enum Direction
enum Direction : uint8_t
{
AUTO = 0x00, // auto-derive direction from context
FORWARD = 0x01, // propagate forward only
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/stages/connect.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class Connect : public Connecting
bool compatible(const InterfaceState& from_state, const InterfaceState& to_state) const override;

public:
enum MergeMode
enum MergeMode : uint8_t
{
SEQUENTIAL = 0,
WAYPOINTS = 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ class GenerateRandomPose : public GeneratePose

/** Function signature for pose dimension samplers.
* The input parameter is the seed, the returned value is the sampling result. */
typedef std::function<double(double)> PoseDimensionSampler;
enum PoseDimension
using PoseDimensionSampler = std::function<double(double)>;
enum PoseDimension : uint8_t
{
X,
Y,
Expand Down
6 changes: 3 additions & 3 deletions core/include/moveit/task_constructor/storage.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class InterfaceState
friend class ContainerBasePrivate; // allow setting priority_ for pruning

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

enum Direction
enum Direction : uint8_t
{
FORWARD,
BACKWARD,
};
enum Update
enum Update : uint8_t
{
STATUS = 1 << 0,
PRIORITY = 1 << 1,
Expand Down
2 changes: 1 addition & 1 deletion core/python/bindings/src/properties.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class PropertyConverterRegistry
PropertyConverterBase::from_python_converter_function from_;
};
// map from type_index to corresponding converter functions
typedef std::map<std::type_index, Entry> RegistryMap;
using RegistryMap = std::map<std::type_index, Entry>;
RegistryMap types_;
// map from ros-msg-names to entry in types_
using RosMsgTypeNameMap = std::map<std::string, RegistryMap::iterator>;
Expand Down
14 changes: 7 additions & 7 deletions core/src/container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,24 +63,24 @@ printChildrenInterfaces(const ContainerBasePrivate& container, bool success, con
std::ostream& os = std::cerr) {
static unsigned int id = 0;
const unsigned int width = 10; // indentation of name
os << std::endl << (success ? '+' : '-') << ' ' << creator.name() << ' ';
os << '\n' << (success ? '+' : '-') << ' ' << creator.name() << ' ';
if (success)
os << ++id << ' ';
if (const auto conn = dynamic_cast<const ConnectingPrivate*>(creator.pimpl()))
os << conn->pendingPairsPrinter();
os << std::endl;
os << '\n';

for (const auto& child : container.children()) {
auto cimpl = child->pimpl();
os << std::setw(width) << std::left << child->name();
if (!cimpl->starts() && !cimpl->ends())
os << "" << std::endl;
os << "\n";
if (cimpl->starts())
os << "" << *child->pimpl()->starts() << std::endl;
os << "" << *child->pimpl()->starts() << '\n';
if (cimpl->starts() && cimpl->ends())
os << std::setw(width) << " ";
if (cimpl->ends())
os << "" << *child->pimpl()->ends() << std::endl;
os << "" << *child->pimpl()->ends() << '\n';
}
}

Expand Down Expand Up @@ -460,7 +460,7 @@ void ContainerBase::explainFailure(std::ostream& os) const {
if (stage->numFailures()) {
os << stage->name() << " (0/" << stage->numFailures() << ")";
stage->explainFailure(os);
os << std::endl;
os << '\n';
break;
}
stage->explainFailure(os); // recursively process children
Expand All @@ -469,7 +469,7 @@ void ContainerBase::explainFailure(std::ostream& os) const {

std::ostream& operator<<(std::ostream& os, const ContainerBase& container) {
ContainerBase::StageCallback processor = [&os](const Stage& stage, unsigned int depth) -> bool {
os << std::string(2 * depth, ' ') << *stage.pimpl() << std::endl;
os << std::string(2 * depth, ' ') << *stage.pimpl() << '\n';
return true;
};
container.traverseRecursively(processor);
Expand Down
2 changes: 1 addition & 1 deletion core/src/introspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ void Introspection::publishAllSolutions(bool wait) {
publishSolution(*solution);

if (wait) {
std::cout << "Press <Enter> to continue ..." << std::endl;
std::cout << "Press <Enter> to continue ...\n";
int ch = getchar();
if (ch == 'q' || ch == 'Q')
break;
Expand Down
8 changes: 4 additions & 4 deletions core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,9 +91,9 @@ const char* InitStageException::what() const noexcept {
}

std::ostream& operator<<(std::ostream& os, const InitStageException& e) {
os << "Error initializing stage" << (e.errors_.size() > 1 ? "s" : "") << ":" << std::endl;
os << "Error initializing stage" << (e.errors_.size() > 1 ? "s" : "") << ":\n ";
for (const auto& pair : e.errors_)
os << pair.first->name() << ": " << pair.second << std::endl;
os << pair.first->name() << ": " << pair.second << '\n';
return os;
}

Expand Down Expand Up @@ -841,10 +841,10 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags
os << (updated ? " !" : " +");
else
os << " ";
os << d << " " << this->pullInterface(d) << ": " << *this->pullInterface(d) << std::endl;
os << d << " " << this->pullInterface(d) << ": " << *this->pullInterface(d) << '\n';
}
os << std::setw(15) << " ";
os << pendingPairsPrinter() << std::endl;
os << pendingPairsPrinter() << '\n';
#endif
}

Expand Down
2 changes: 0 additions & 2 deletions core/src/stages/predicate_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,6 @@ void PredicateFilter::init(const moveit::core::RobotModelConstPtr& robot_model)
void PredicateFilter::onNewSolution(const SolutionBase& s) {
const auto& props = properties();

// false-positive in clang-tidy 10.0.0: predicate might change comment
// NOLINTNEXTLINE(performance-unnecessary-copy-initialization)
std::string comment = s.comment();

double cost = s.cost();
Expand Down
2 changes: 1 addition & 1 deletion core/test/pick_pa10.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ TEST(PA10, pick) {
try {
t.plan();
} catch (const InitStageException& e) {
ADD_FAILURE() << "planning failed with exception" << std::endl << e << t;
ADD_FAILURE() << "planning failed with exception\n" << e << t;
}

auto solutions = t.solutions().size();
Expand Down
2 changes: 1 addition & 1 deletion core/test/pick_pr2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ TEST(PR2, pick) {
spawnObject();
t.plan();
} catch (const InitStageException& e) {
ADD_FAILURE() << "planning failed with exception" << std::endl << e << t;
ADD_FAILURE() << "planning failed with exception\n" << e << t;
}

auto solutions = t.solutions().size();
Expand Down
2 changes: 1 addition & 1 deletion core/test/pick_ur5.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ TEST(UR5, pick) {
spawnObject();
t.plan();
} catch (const InitStageException& e) {
ADD_FAILURE() << "planning failed with exception" << std::endl << e << t;
ADD_FAILURE() << "planning failed with exception\n" << e << t;
}

auto solutions = t.solutions().size();
Expand Down
8 changes: 4 additions & 4 deletions core/test/stage_mockups.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ struct GeneratorMockup : public Generator
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
bool canCompute() const override;
void compute() override;
virtual void reset() override { runs_ = 0; };
void reset() override { runs_ = 0; };
};

struct MonitoringGeneratorMockup : public MonitoringGenerator
Expand All @@ -82,7 +82,7 @@ struct MonitoringGeneratorMockup : public MonitoringGenerator
bool canCompute() const override { return false; }
void compute() override {}
void onNewSolution(const SolutionBase& s) override;
virtual void reset() override { runs_ = 0; };
void reset() override { runs_ = 0; };
};

struct ConnectMockup : public Connecting
Expand All @@ -99,7 +99,7 @@ struct ConnectMockup : public Connecting
using Connecting::compatible; // make this accessible for testing

void compute(const InterfaceState& from, const InterfaceState& to) override;
virtual void reset() override { runs_ = 0; };
void reset() override { runs_ = 0; };
};

struct PropagatorMockup : public PropagatingEitherWay
Expand All @@ -116,7 +116,7 @@ struct PropagatorMockup : public PropagatingEitherWay

void computeForward(const InterfaceState& from) override;
void computeBackward(const InterfaceState& to) override;
virtual void reset() override { runs_ = 0; };
void reset() override { runs_ = 0; };
};

struct ForwardMockup : public PropagatorMockup
Expand Down
4 changes: 2 additions & 2 deletions core/test/test_container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

using namespace moveit::task_constructor;

enum StageType
enum StageType : uint8_t
{
GEN,
FW,
Expand Down Expand Up @@ -625,7 +625,7 @@ TEST(Task, reuse) {
configure(t);
EXPECT_TRUE(t.plan(1));
} catch (const InitStageException& e) {
ADD_FAILURE() << "InitStageException:" << std::endl << e << t;
ADD_FAILURE() << "InitStageException:\n" << e << t;
}
}

Expand Down
2 changes: 1 addition & 1 deletion core/test/test_cost_queue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ TYPED_TEST(OrderedTest, sorting) {
template <typename ValueType, typename CostType>
std::ostream& operator<<(std::ostream& os, const cost_ordered<ValueType, CostType>& queue) {
for (const auto& pair : queue.sorted())
os << pair.cost() << ": " << pair.value() << std::endl;
os << pair.cost() << ": " << pair.value() << '\n';
return os;
}

Expand Down
2 changes: 1 addition & 1 deletion core/test/test_move_to.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ TEST(Task, taskMoveConstructor) {
t.init();
EXPECT_TRUE(t.plan(1));
} catch (const InitStageException& e) {
ADD_FAILURE() << "InitStageException:" << std::endl << e << t;
ADD_FAILURE() << "InitStageException:\n" << e << t;
}
}

Expand Down
2 changes: 1 addition & 1 deletion demo/src/alternative_path_costs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ int main(int argc, char** argv) {
try {
t.plan(0);
} catch (const InitStageException& e) {
std::cout << e << std::endl;
std::cout << e << '\n';
}

// keep alive for interactive inspection in rviz
Expand Down
2 changes: 1 addition & 1 deletion demo/src/cartesian.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ int main(int argc, char** argv) {
if (task.plan())
task.introspection().publishSolution(*task.solutions().front());
} catch (const InitStageException& ex) {
std::cerr << "planning failed with exception" << std::endl << ex << task;
std::cerr << "planning failed with exception\n" << ex << task;
}

// keep alive for interactive inspection in rviz
Expand Down
2 changes: 1 addition & 1 deletion demo/src/fallbacks_move_to.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ int main(int argc, char** argv) {
try {
t.plan();
} catch (const InitStageException& e) {
std::cout << e << std::endl;
std::cout << e << '\n';
}

// keep alive for interactive inspection in rviz
Expand Down
2 changes: 1 addition & 1 deletion demo/src/ik_clearance_cost.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ int main(int argc, char** argv) {
try {
t.plan(0);
} catch (const InitStageException& e) {
std::cout << e << std::endl;
std::cout << e << '\n';
}

// Keep introspection alive
Expand Down
2 changes: 1 addition & 1 deletion demo/src/modular.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ int main(int argc, char** argv) {
if (task.plan())
task.introspection().publishSolution(*task.solutions().front());
} catch (const InitStageException& ex) {
std::cerr << "planning failed with exception" << std::endl << ex << task;
std::cerr << "planning failed with exception\n" << ex << task;
}

// keep alive for interactive inspection in rviz
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ class Geometry;

namespace rviz_marker_tools {

enum Color
enum Color : uint8_t
{
BLACK = 0,
BROWN = 1,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ using namespace moveit::task_constructor;

namespace moveit_rviz_plugin {

enum NodeFlag
enum NodeFlag : uint8_t
{
WAS_VISITED = 0x01, // indicate that model should emit change notifications
NAME_CHANGED = 0x02, // indicate that name was manually changed
Expand Down
2 changes: 1 addition & 1 deletion visualization/motion_planning_tasks/src/task_list_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class BaseTaskModel : public QAbstractItemModel
rviz_common::DisplayContext* display_context_;

public:
enum TaskModelFlag
enum TaskModelFlag : uint8_t
{
LOCAL_MODEL = 0x01,
IS_DESTROYED = 0x02,
Expand Down
4 changes: 2 additions & 2 deletions visualization/motion_planning_tasks/src/task_panel.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ class TaskView : public SubPanel

protected:
// configuration settings
enum TaskExpand
enum TaskExpand : uint8_t
{
EXPAND_TOP = 1,
EXPAND_ALL,
Expand All @@ -132,7 +132,7 @@ class TaskView : public SubPanel
rviz_common::properties::BoolProperty* show_time_column;

public:
enum OldTaskHandling
enum OldTaskHandling : uint8_t
{
OLD_TASK_KEEP = 1,
OLD_TASK_REPLACE,
Expand Down
Loading

0 comments on commit 325c401

Please sign in to comment.