#include <center_of_mass.h>
|
void | AssignScene (ScenePtr scene) override |
|
void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override |
|
void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override |
|
int | TaskSpaceDim () override |
|
virtual void | InstantiateBase (const Initializer &init) |
|
virtual void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian) |
|
virtual void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi) |
|
virtual void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du) |
|
virtual void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du, HessianRef ddphi_ddx, HessianRef ddphi_ddu, HessianRef ddphi_dxdu) |
|
virtual int | TaskSpaceJacobianDim () |
|
virtual void | PreUpdate () |
|
virtual std::vector< TaskVectorEntry > | GetLieGroupIndices () |
|
std::vector< KinematicFrameRequest > | GetFrames () const |
|
| Object () |
|
virtual | ~Object () |
|
virtual std::string | type () const |
| Type Information wrapper: must be virtual so that it is polymorphic... More...
|
|
std::string | GetObjectName () |
|
void | InstantiateObject (const Initializer &init) |
|
virtual std::string | Print (const std::string &prepend) const |
|
| InstantiableBase ()=default |
|
virtual | ~InstantiableBase ()=default |
|
virtual std::vector< Initializer > | GetAllTemplates () const =0 |
|
void | InstantiateInternal (const Initializer &init) override |
|
Initializer | GetInitializerTemplate () override |
|
std::vector< Initializer > | GetAllTemplates () const override |
|
virtual void | Instantiate (const CenterOfMassInitializer &init) |
|
const CenterOfMassInitializer & | GetParameters () const |
|
◆ AssignScene()
void exotica::CenterOfMass::AssignScene |
( |
ScenePtr |
scene | ) |
|
|
overridevirtual |
◆ Initialize()
void exotica::CenterOfMass::Initialize |
( |
| ) |
|
|
private |
◆ InitializeDebug()
void exotica::CenterOfMass::InitializeDebug |
( |
| ) |
|
|
private |
◆ TaskSpaceDim()
int exotica::CenterOfMass::TaskSpaceDim |
( |
| ) |
|
|
overridevirtual |
◆ Update() [1/2]
◆ Update() [2/2]
◆ com_links_marker_
visualization_msgs::Marker exotica::CenterOfMass::com_links_marker_ |
|
private |
◆ com_links_pub_
ros::Publisher exotica::CenterOfMass::com_links_pub_ |
|
private |
◆ com_marker_
visualization_msgs::Marker exotica::CenterOfMass::com_marker_ |
|
private |
◆ com_pub_
ros::Publisher exotica::CenterOfMass::com_pub_ |
|
private |
◆ dim_
int exotica::CenterOfMass::dim_ |
|
private |
◆ enable_z_
bool exotica::CenterOfMass::enable_z_ |
|
private |
◆ goal_marker_
visualization_msgs::Marker exotica::CenterOfMass::goal_marker_ |
|
private |
◆ goal_pub_
ros::Publisher exotica::CenterOfMass::goal_pub_ |
|
private |
◆ mass_
Eigen::VectorXd exotica::CenterOfMass::mass_ |
|
private |
The documentation for this class was generated from the following file:
- /tmp/exotica/exotations/exotica_core_task_maps/include/exotica_core_task_maps/center_of_mass.h