GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: unittest/factory/constraint.hpp Lines: 6 6 100.0 %
Date: 2024-02-13 11:12:33 Branches: 4 6 66.7 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2020-2022, University of Edinburgh, IRI: CSIC-UPC
5
// Copyright note valid unless otherwise stated in individual files.
6
// All rights reserved.
7
///////////////////////////////////////////////////////////////////////////////
8
9
#ifndef CROCODDYL_CONSTRAINT_FACTORY_HPP_
10
#define CROCODDYL_CONSTRAINT_FACTORY_HPP_
11
12
#include "crocoddyl/core/constraint-base.hpp"
13
#include "crocoddyl/core/constraints/constraint-manager.hpp"
14
#include "crocoddyl/core/numdiff/constraint.hpp"
15
#include "crocoddyl/multibody/states/multibody.hpp"
16
#include "state.hpp"
17
18
namespace crocoddyl {
19
namespace unittest {
20
21
struct ConstraintModelTypes {
22
  enum Type {
23
    ConstraintModelResidualStateEquality,
24
    ConstraintModelResidualStateInequality,
25
    ConstraintModelResidualControlEquality,
26
    ConstraintModelResidualControlInequality,
27
    ConstraintModelResidualCoMPositionEquality,
28
    ConstraintModelResidualCoMPositionInequality,
29
    ConstraintModelResidualFramePlacementEquality,
30
    ConstraintModelResidualFramePlacementInequality,
31
    ConstraintModelResidualFrameRotationEquality,
32
    ConstraintModelResidualFrameRotationInequality,
33
    ConstraintModelResidualFrameTranslationEquality,
34
    ConstraintModelResidualFrameTranslationInequality,
35
    ConstraintModelResidualFrameVelocityEquality,
36
    ConstraintModelResidualFrameVelocityInequality,
37
    NbConstraintModelTypes
38
  };
39
23
  static std::vector<Type> init_all() {
40
23
    std::vector<Type> v;
41
23
    v.reserve(NbConstraintModelTypes);
42
345
    for (int i = 0; i < NbConstraintModelTypes; ++i) {
43
322
      v.push_back((Type)i);
44
    }
45
23
    return v;
46
  }
47
  static const std::vector<Type> all;
48
};
49
50
std::ostream& operator<<(std::ostream& os, ConstraintModelTypes::Type type);
51
52
class ConstraintModelFactory {
53
 public:
54
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55
56
  explicit ConstraintModelFactory();
57
  ~ConstraintModelFactory();
58
59
  boost::shared_ptr<crocoddyl::ConstraintModelAbstract> create(
60
      ConstraintModelTypes::Type constraint_type,
61
      StateModelTypes::Type state_type,
62
      std::size_t nu = std::numeric_limits<std::size_t>::max()) const;
63
};
64
65
boost::shared_ptr<crocoddyl::ConstraintModelAbstract> create_random_constraint(
66
    StateModelTypes::Type state_type);
67
68
}  // namespace unittest
69
}  // namespace crocoddyl
70
71
#endif  // CROCODDYL_COST_FACTORY_HPP_