wbc
RobotModelHyrodyn.hpp
Go to the documentation of this file.
1#ifndef ROBOTMODELHYRODYN_HPP
2#define ROBOTMODELHYRODYN_HPP
3
5
6#include <hyrodyn/robot_model_hyrodyn.hpp>
7#include <base/commands/Joints.hpp>
8
9namespace wbc{
10
12private:
14
15protected:
16 hyrodyn::RobotModel_HyRoDyn hyrodyn;
17
18 void clear();
19public:
21 virtual ~RobotModelHyrodyn();
22
28 virtual bool configure(const RobotModelConfig& cfg);
29
35 virtual void update(const base::samples::Joints& joint_state,
36 const base::samples::RigidBodyStateSE3& floating_base_state = base::samples::RigidBodyStateSE3());
37
39 virtual void systemState(base::VectorXd &q, base::VectorXd &qd, base::VectorXd &qdd);
40
47 virtual const base::samples::RigidBodyStateSE3 &rigidBodyState(const std::string &root_frame, const std::string &tip_frame);
48
54 virtual const base::MatrixXd &spaceJacobian(const std::string &root_frame, const std::string &tip_frame);
55
61 virtual const base::MatrixXd &bodyJacobian(const std::string &root_frame, const std::string &tip_frame);
62
68 virtual const base::MatrixXd &comJacobian();
69
77 virtual const base::MatrixXd &jacobianDot(const std::string &root_frame, const std::string &tip_frame);
78
84 virtual const base::Acceleration &spatialAccelerationBias(const std::string &root_frame, const std::string &tip_frame);
85
87 virtual const base::MatrixXd &jointSpaceInertiaMatrix();
88
90 virtual const base::VectorXd &biasForces();
91
93 virtual const base::samples::RigidBodyStateSE3& centerOfMass();
94
96 hyrodyn::RobotModel_HyRoDyn *hyrodynHandle(){return &hyrodyn;}
97
99 virtual void computeInverseDynamics(base::commands::Joints &solver_output);
100};
101
102}
103
104#endif
Definition RobotModelHyrodyn.hpp:11
virtual const base::samples::RigidBodyStateSE3 & centerOfMass()
Return Current center of gravity in expressed base frame.
Definition RobotModelHyrodyn.cpp:387
virtual const base::samples::RigidBodyStateSE3 & rigidBodyState(const std::string &root_frame, const std::string &tip_frame)
Computes and returns the relative transform between the two given frames. By convention this is the p...
Definition RobotModelHyrodyn.cpp:216
virtual void systemState(base::VectorXd &q, base::VectorXd &qd, base::VectorXd &qdd)
Definition RobotModelHyrodyn.cpp:199
hyrodyn::RobotModel_HyRoDyn * hyrodynHandle()
Return pointer to the internal hyrodyn model.
Definition RobotModelHyrodyn.hpp:96
virtual void computeInverseDynamics(base::commands::Joints &solver_output)
Compute and return the inverse dynamics solution.
Definition RobotModelHyrodyn.cpp:401
virtual bool configure(const RobotModelConfig &cfg)
Load and configure the robot model.
Definition RobotModelHyrodyn.cpp:23
virtual const base::MatrixXd & spaceJacobian(const std::string &root_frame, const std::string &tip_frame)
Returns the Space Jacobian for the kinematic chain between root and the tip frame as full body Jacobi...
Definition RobotModelHyrodyn.cpp:241
virtual ~RobotModelHyrodyn()
Definition RobotModelHyrodyn.cpp:13
virtual const base::VectorXd & biasForces()
Definition RobotModelHyrodyn.cpp:367
virtual const base::MatrixXd & bodyJacobian(const std::string &root_frame, const std::string &tip_frame)
Returns the Body Jacobian for the kinematic chain between root and the tip frame as full body Jacobia...
Definition RobotModelHyrodyn.cpp:282
RobotModelHyrodyn()
Definition RobotModelHyrodyn.cpp:10
hyrodyn::RobotModel_HyRoDyn hyrodyn
Definition RobotModelHyrodyn.hpp:16
virtual const base::Acceleration & spatialAccelerationBias(const std::string &root_frame, const std::string &tip_frame)
Returns the spatial acceleration bias, i.e. the term Jdot*qdot.
Definition RobotModelHyrodyn.cpp:342
virtual const base::MatrixXd & jointSpaceInertiaMatrix()
Definition RobotModelHyrodyn.cpp:348
virtual const base::MatrixXd & jacobianDot(const std::string &root_frame, const std::string &tip_frame)
Returns the derivative of the Jacobian for the kinematic chain between root and the tip frame as full...
Definition RobotModelHyrodyn.cpp:337
void clear()
Definition RobotModelHyrodyn.cpp:16
virtual void update(const base::samples::Joints &joint_state, const base::samples::RigidBodyStateSE3 &floating_base_state=base::samples::RigidBodyStateSE3())
Update the robot configuration.
Definition RobotModelHyrodyn.cpp:108
virtual const base::MatrixXd & comJacobian()
Returns the CoM Jacobian for the entire robot, which maps the robot joint velocities to linear spatia...
Definition RobotModelHyrodyn.cpp:325
Interface for all robot models. This has to provide all kinematics and dynamics information that is r...
Definition RobotModel.hpp:22
base::samples::RigidBodyStateSE3 floating_base_state
Definition RobotModel.hpp:31
base::samples::Joints joint_state
Definition RobotModel.hpp:42
Definition ContactsAccelerationConstraint.cpp:3
Robot Model configuration class.
Definition RobotModelConfig.hpp:40
Definition RobotModel.hpp:239