crocoddyl
1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
contact-friction-cone.hpp
1
// BSD 3-Clause License
3
//
4
// Copyright (C) 2019-2021, LAAS-CNRS, University of Edinburgh, INRIA
5
// Copyright note valid unless otherwise stated in individual files.
6
// All rights reserved.
8
9
#ifndef CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_
10
#define CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_
11
12
#include "crocoddyl/multibody/fwd.hpp"
13
#include "crocoddyl/core/costs/residual.hpp"
14
#include "crocoddyl/multibody/states/multibody.hpp"
15
#include "crocoddyl/multibody/residuals/contact-friction-cone.hpp"
16
#include "crocoddyl/core/utils/exception.hpp"
17
18
#include "crocoddyl/multibody/frames-deprecated.hpp"
19
20
namespace
crocoddyl {
21
22
#pragma GCC diagnostic push // TODO: Remove once the deprecated FrameXX has been removed in a future release
23
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
24
47
template
<
typename
_Scalar>
48
class
CostModelContactFrictionConeTpl
:
public
CostModelResidualTpl
<_Scalar> {
49
public
:
50
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51
52
typedef
_Scalar Scalar;
53
typedef
MathBaseTpl<Scalar>
MathBase
;
54
typedef
CostModelResidualTpl<Scalar>
Base
;
55
typedef
CostDataContactFrictionConeTpl<Scalar>
Data
;
56
typedef
StateMultibodyTpl<Scalar>
StateMultibody
;
57
typedef
ActivationModelAbstractTpl<Scalar>
ActivationModelAbstract
;
58
typedef
ResidualModelContactFrictionConeTpl<Scalar>
ResidualModelContactFrictionCone
;
59
typedef
FrameFrictionConeTpl<Scalar>
FrameFrictionCone
;
60
typedef
typename
MathBase::VectorXs VectorXs;
61
70
CostModelContactFrictionConeTpl
(boost::shared_ptr<StateMultibody> state,
71
boost::shared_ptr<ActivationModelAbstract> activation,
const
FrameFrictionCone
& fref,
72
const
std::size_t nu);
73
83
CostModelContactFrictionConeTpl
(boost::shared_ptr<StateMultibody> state,
84
boost::shared_ptr<ActivationModelAbstract> activation,
85
const
FrameFrictionCone
& fref);
86
96
CostModelContactFrictionConeTpl
(boost::shared_ptr<StateMultibody> state,
const
FrameFrictionCone
& fref,
97
const
std::size_t nu);
98
108
CostModelContactFrictionConeTpl
(boost::shared_ptr<StateMultibody> state,
const
FrameFrictionCone
& fref);
109
virtual
~
CostModelContactFrictionConeTpl
();
110
111
protected
:
115
virtual
void
set_referenceImpl
(
const
std::type_info& ti,
const
void
* pv);
116
120
virtual
void
get_referenceImpl
(
const
std::type_info& ti,
void
* pv);
121
122
using
Base::activation_
;
123
using
Base::nu_
;
124
using
Base::residual_
;
125
using
Base::state_
;
126
using
Base::unone_
;
127
128
private
:
129
FrameFrictionCone
fref_;
130
};
131
132
}
// namespace crocoddyl
133
134
/* --- Details -------------------------------------------------------------- */
135
/* --- Details -------------------------------------------------------------- */
136
/* --- Details -------------------------------------------------------------- */
137
#include "crocoddyl/multibody/costs/contact-friction-cone.hxx"
138
139
#pragma GCC diagnostic pop
140
141
#endif // CROCODDYL_MULTIBODY_COSTS_CONTACT_FRICTION_CONE_HPP_
crocoddyl::CostModelContactFrictionConeTpl
Contact friction cone cost.
Definition:
contact-friction-cone.hpp:48
crocoddyl::CostModelResidualTpl
Residual-based cost.
Definition:
residual.hpp:36
crocoddyl::MathBaseTpl< Scalar >
crocoddyl::CostModelAbstractTpl::unone_
VectorXs unone_
No control vector.
Definition:
cost-base.hpp:244
crocoddyl::CostModelAbstractTpl::activation_
boost::shared_ptr< ActivationModelAbstract > activation_
Activation model.
Definition:
cost-base.hpp:241
crocoddyl::CostModelAbstractTpl
Abstract class for cost models.
Definition:
cost-base.hpp:49
crocoddyl::CostModelContactFrictionConeTpl::CostModelContactFrictionConeTpl
CostModelContactFrictionConeTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameFrictionCone &fref, const std::size_t nu)
Initialize the contact friction cone cost model.
crocoddyl::CostModelContactFrictionConeTpl::set_referenceImpl
virtual void set_referenceImpl(const std::type_info &ti, const void *pv)
Modify the contact friction cone reference.
crocoddyl::StateMultibodyTpl
State multibody representation.
Definition:
fwd.hpp:305
crocoddyl::CostModelContactFrictionConeTpl::get_referenceImpl
virtual void get_referenceImpl(const std::type_info &ti, void *pv)
Return the contact friction cone reference.
crocoddyl::CostModelAbstractTpl::state_
boost::shared_ptr< StateAbstract > state_
State description.
Definition:
cost-base.hpp:240
crocoddyl::ResidualModelContactFrictionConeTpl
Contact friction cone residual.
Definition:
fwd.hpp:107
crocoddyl::CostDataResidualTpl
Definition:
residual.hpp:136
crocoddyl::CostModelAbstractTpl::residual_
boost::shared_ptr< ResidualModelAbstract > residual_
Residual model.
Definition:
cost-base.hpp:242
crocoddyl::FrameFrictionConeTpl< Scalar >
crocoddyl::ActivationModelAbstractTpl< Scalar >
crocoddyl::CostModelAbstractTpl::nu_
std::size_t nu_
Control dimension.
Definition:
cost-base.hpp:243
include
crocoddyl
multibody
costs
contact-friction-cone.hpp
Generated by
1.8.17