Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
B
bodydynamics
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Deploy
Releases
Model registry
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
mobile_robotics
wolf_projects
wolf_lib
plugins
bodydynamics
Commits
507ff7fa
Commit
507ff7fa
authored
2 years ago
by
Joan Solà Ortega
Browse files
Options
Downloads
Patches
Plain Diff
Rename FactorForceTorquePreint --> FactorForceTorque
parent
4c758806
No related branches found
No related tags found
3 merge requests
!31
devel->main
,
!29
Add functionality for UAV
,
!27
Fix test with acc_x = 2 m/s2
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
include/bodydynamics/factor/factor_force_torque.h
+14
-14
14 additions, 14 deletions
include/bodydynamics/factor/factor_force_torque.h
src/processor/processor_force_torque_preint.cpp
+3
-3
3 additions, 3 deletions
src/processor/processor_force_torque_preint.cpp
with
17 additions
and
17 deletions
include/bodydynamics/factor/factor_force_torque
_preint
.h
→
include/bodydynamics/factor/factor_force_torque.h
+
14
−
14
View file @
507ff7fa
...
...
@@ -19,11 +19,11 @@
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
//--------LICENSE_END--------
#ifndef FACTOR_FORCE_TORQUE_
PREINT_THETA_
H_
#define FACTOR_FORCE_TORQUE_
PREINT_THETA_
H_
#ifndef FACTOR_FORCE_TORQUE_H_
#define FACTOR_FORCE_TORQUE_H_
//Wolf includes
#include
"bodydynamics/capture/capture_force_torque
_preint
.h"
#include
"bodydynamics/capture/capture_force_torque.h"
#include
"bodydynamics/feature/feature_force_torque_preint.h"
#include
"bodydynamics/sensor/sensor_force_torque.h"
#include
"core/factor/factor_autodiff.h"
...
...
@@ -33,13 +33,13 @@
namespace
wolf
{
WOLF_PTR_TYPEDEFS
(
FactorForceTorque
Preint
);
WOLF_PTR_TYPEDEFS
(
FactorForceTorque
);
//class
class
FactorForceTorque
Preint
:
public
FactorAutodiff
<
FactorForceTorque
Preint
,
12
,
3
,
3
,
3
,
4
,
3
,
6
,
3
,
3
,
3
,
4
>
class
FactorForceTorque
:
public
FactorAutodiff
<
FactorForceTorque
,
12
,
3
,
3
,
3
,
4
,
3
,
6
,
3
,
3
,
3
,
4
>
{
public:
FactorForceTorque
Preint
(
const
FeatureForceTorquePreintPtr
&
_ftr_ptr
,
FactorForceTorque
(
const
FeatureForceTorquePreintPtr
&
_ftr_ptr
,
const
CaptureForceTorquePtr
&
_cap_origin_ptr
,
// gets to bp1, bw1
const
ProcessorBasePtr
&
_processor_ptr
,
const
CaptureBasePtr
&
_cap_ikin_other
,
...
...
@@ -47,7 +47,7 @@ class FactorForceTorquePreint : public FactorAutodiff<FactorForceTorquePreint, 1
bool
_apply_loss_function
,
FactorStatus
_status
=
FAC_ACTIVE
);
~
FactorForceTorque
Preint
()
override
=
default
;
~
FactorForceTorque
()
override
=
default
;
/** \brief : compute the residual from the state blocks being iterated by the solver.
-> computes the expected measurement
...
...
@@ -128,7 +128,7 @@ class FactorForceTorquePreint : public FactorAutodiff<FactorForceTorquePreint, 1
///////////////////// IMPLEMENTATION ////////////////////////////
inline
FactorForceTorque
Preint
::
FactorForceTorque
Preint
(
inline
FactorForceTorque
::
FactorForceTorque
(
const
FeatureForceTorquePreintPtr
&
_ftr_ptr
,
const
CaptureForceTorquePtr
&
_cap_origin_ptr
,
const
ProcessorBasePtr
&
_processor_ptr
,
...
...
@@ -136,8 +136,8 @@ inline FactorForceTorquePreint::FactorForceTorquePreint(
const
CaptureBasePtr
&
_cap_gyro_other
,
bool
_apply_loss_function
,
FactorStatus
_status
)
:
FactorAutodiff
<
FactorForceTorque
Preint
,
12
,
3
,
3
,
3
,
4
,
3
,
6
,
3
,
3
,
3
,
4
>
(
"FactorForceTorque
Preint
"
,
FactorAutodiff
<
FactorForceTorque
,
12
,
3
,
3
,
3
,
4
,
3
,
6
,
3
,
3
,
3
,
4
>
(
"FactorForceTorque"
,
TOP_MOTION
,
_ftr_ptr
,
_cap_origin_ptr
->
getFrame
(),
...
...
@@ -176,7 +176,7 @@ inline FactorForceTorquePreint::FactorForceTorquePreint(
}
template
<
typename
T
>
inline
bool
FactorForceTorque
Preint
::
operator
()(
const
T
*
const
_c1
,
inline
bool
FactorForceTorque
::
operator
()(
const
T
*
const
_c1
,
const
T
*
const
_cd1
,
const
T
*
const
_Lc1
,
const
T
*
const
_q1
,
...
...
@@ -206,7 +206,7 @@ inline bool FactorForceTorquePreint::operator ()(const T* const _c1,
}
template
<
typename
D1
,
typename
D2
,
typename
D3
,
typename
D4
>
inline
bool
FactorForceTorque
Preint
::
residual
(
const
MatrixBase
<
D1
>
&
_c1
,
inline
bool
FactorForceTorque
::
residual
(
const
MatrixBase
<
D1
>
&
_c1
,
const
MatrixBase
<
D1
>
&
_cd1
,
const
MatrixBase
<
D1
>
&
_Lc1
,
const
QuaternionBase
<
D2
>
&
_q1
,
...
...
@@ -305,7 +305,7 @@ inline bool FactorForceTorquePreint::residual(const MatrixBase<D1> & _c1,
return
true
;
}
// Matrix<double,12,1> FactorForceTorque
Preint
::residual() const
// Matrix<double,12,1> FactorForceTorque::residual() const
// {
// Matrix<double,12,1> res;
...
...
@@ -333,7 +333,7 @@ inline bool FactorForceTorquePreint::residual(const MatrixBase<D1> & _c1,
// return res;
// }
// double FactorForceTorque
Preint
::cost() const
// double FactorForceTorque::cost() const
// {
// Matrix<double,12,1> toto = residual();
// }
...
...
This diff is collapsed.
Click to expand it.
src/processor/processor_force_torque_preint.cpp
+
3
−
3
View file @
507ff7fa
...
...
@@ -21,10 +21,10 @@
//--------LICENSE_END--------
// wolf
#include
"bodydynamics/math/force_torque_delta_tools.h"
#include
"bodydynamics/capture/capture_force_torque
_preint
.h"
#include
"bodydynamics/capture/capture_force_torque.h"
#include
"bodydynamics/feature/feature_force_torque_preint.h"
#include
"bodydynamics/processor/processor_force_torque_preint.h"
#include
"bodydynamics/factor/factor_force_torque
_preint
.h"
#include
"bodydynamics/factor/factor_force_torque.h"
namespace
wolf
{
...
...
@@ -182,7 +182,7 @@ FactorBasePtr ProcessorForceTorquePreint::emplaceFactor(FeatureBasePtr _feature_
FeatureForceTorquePreintPtr
ftr_ftpreint
=
std
::
static_pointer_cast
<
FeatureForceTorquePreint
>
(
_feature_motion
);
CaptureForceTorquePtr
cap_ftpreint_new
=
std
::
static_pointer_cast
<
CaptureForceTorque
>
(
ftr_ftpreint
->
getCapture
());
auto
fac_ftpreint
=
FactorBase
::
emplace
<
FactorForceTorque
Preint
>
(
auto
fac_ftpreint
=
FactorBase
::
emplace
<
FactorForceTorque
>
(
ftr_ftpreint
,
ftr_ftpreint
,
cap_ftpreint_origin
,
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment