- 3.0.2 rigid body dynamics module.
ActuatorDynamics.h
Go to the documentation of this file.
1 /**********************************************************************************************************************
2 This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich.
3 Licensed under the BSD-2 license (see LICENSE file in main directory)
4 **********************************************************************************************************************/
5 
6 #pragma once
7 
9 
10 namespace ct {
11 namespace rbd {
12 
13 
24 template <size_t ACT_STATE_DIMS, size_t NJOINTS, typename SCALAR = double>
26 {
27 public:
28  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
29 
30  static const size_t ACT_STATE_DIM = ACT_STATE_DIMS;
31  static const size_t ACT_CONTROL_DIM = NJOINTS;
32 
35 
37 
38  virtual ~ActuatorDynamics(){};
39 
41 
42  virtual void computeActuatorDynamics(const JointState<NJOINTS, SCALAR>& robotJointState,
44  const SCALAR& t,
47 
60  const JointState<NJOINTS, SCALAR>& robotJointState,
61  const act_state_vector_t& actState) = 0;
62 
68  const JointState<NJOINTS, SCALAR>& refRobotJointState,
69  const core::ControlVector<NJOINTS, SCALAR>& refControl) = 0;
70 };
71 
72 
73 } // namespace rbd
74 } // namespace ct
virtual ~ActuatorDynamics()
Definition: ActuatorDynamics.h:38
joint state and joint velocity
Definition: JointState.h:21
ct::core::ControlVector< NJOINTS, SCALAR > act_control_vector_t
Definition: ActuatorDynamics.h:34
virtual void computeActuatorDynamics(const JointState< NJOINTS, SCALAR > &robotJointState, const ct::core::StateVector< ACT_STATE_DIMS, SCALAR > &actuatorState, const SCALAR &t, const ct::core::ControlVector< NJOINTS, SCALAR > &control, ct::core::StateVector< ACT_STATE_DIMS, SCALAR > &derivative)=0
clear all close all load ct GNMSLog0 mat reformat t
static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ACT_STATE_DIM
Definition: ActuatorDynamics.h:30
CppAD::AD< CppAD::cg::CG< double > > SCALAR
ActuatorDynamics()
Definition: ActuatorDynamics.h:36
ct::core::StateVector< ACT_STATE_DIMS, SCALAR > act_state_vector_t
Definition: ActuatorDynamics.h:33
virtual ActuatorDynamics< ACT_STATE_DIMS, NJOINTS, SCALAR > * clone() const =0
Definition: ActuatorDynamics.h:25
virtual core::ControlVector< NJOINTS, SCALAR > computeControlOutput(const JointState< NJOINTS, SCALAR > &robotJointState, const act_state_vector_t &actState)=0
output equation of the actuator
virtual ct::core::StateVector< ACT_STATE_DIMS, SCALAR > computeStateFromOutput(const JointState< NJOINTS, SCALAR > &refRobotJointState, const core::ControlVector< NJOINTS, SCALAR > &refControl)=0
reconstruct actuator state from a desired control output and robot joint state (e.g. for initialization)
static const size_t ACT_CONTROL_DIM
Definition: ActuatorDynamics.h:31