|
| RobotModelHyrodyn () |
|
virtual | ~RobotModelHyrodyn () |
|
virtual bool | configure (const RobotModelConfig &cfg) |
| Load and configure the robot model.
|
|
virtual void | update (const base::samples::Joints &joint_state, const base::samples::RigidBodyStateSE3 &floating_base_state=base::samples::RigidBodyStateSE3()) |
| Update the robot configuration.
|
|
virtual void | systemState (base::VectorXd &q, base::VectorXd &qd, base::VectorXd &qdd) |
|
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 pose of the tip frame in root coordinates. This will create a kinematic chain between root and tip frame, if called for the first time with the given arguments.
|
|
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 Jacobian. Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.
|
|
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 Jacobian. Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.
|
|
virtual const base::MatrixXd & | comJacobian () |
| Returns the CoM Jacobian for the entire robot, which maps the robot joint velocities to linear spatial velocities in robot base coordinates. Size of the Jacobian will be 3 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot.
|
|
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 body Jacobian. By convention reference frame & reference point of the Jacobian will be the root frame (corresponding to the body Jacobian). Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.
|
|
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.
|
|
virtual const base::MatrixXd & | jointSpaceInertiaMatrix () |
|
virtual const base::VectorXd & | biasForces () |
|
virtual const base::samples::RigidBodyStateSE3 & | centerOfMass () |
| Return Current center of gravity in expressed base frame.
|
|
hyrodyn::RobotModel_HyRoDyn * | hyrodynHandle () |
| Return pointer to the internal hyrodyn model.
|
|
virtual void | computeInverseDynamics (base::commands::Joints &solver_output) |
| Compute and return the inverse dynamics solution.
|
|
| RobotModel () |
|
virtual | ~RobotModel () |
|
const base::samples::Joints & | jointState (const std::vector< std::string > &joint_names) |
|
const std::vector< std::string > & | jointNames () |
| Return all joint names.
|
|
const std::vector< std::string > & | actuatedJointNames () |
| Return only actuated joint names.
|
|
const std::vector< std::string > & | independentJointNames () |
| Return only independent joint names.
|
|
uint | jointIndex (const std::string &joint_name) |
| Get index of joint name.
|
|
const std::string & | baseFrame () |
| Get the base frame of the robot.
|
|
const std::string & | worldFrame () |
| Get the world frame id.
|
|
const base::JointLimits & | jointLimits () |
| Return current joint limits.
|
|
bool | hasLink (const std::string &link_name) |
| Return True if given link name is available in robot model, false otherwise.
|
|
bool | hasJoint (const std::string &joint_name) |
| Return True if given joint name is available in robot model, false otherwise.
|
|
bool | hasActuatedJoint (const std::string &joint_name) |
| Return True if given joint name is an actuated joint in robot model, false otherwise.
|
|
const base::MatrixXd & | selectionMatrix () |
| Return current selection matrix S that maps complete joint vector to actuated joint vector: q_a = S * q. The matrix consists of only zeros and ones. Size is na x nq, where na is the number of actuated joints and nq the total number of joints.
|
|
void | setActiveContacts (const ActiveContacts &contacts) |
| Provide information about which link is currently in contact with the environment.
|
|
const ActiveContacts & | getActiveContacts () |
| Provide links names that are possibly in contact with the environment (typically the end effector links)
|
|
uint | noOfJoints () |
| Return number of joints.
|
|
uint | noOfActuatedJoints () |
| Return number of actuated/active joints.
|
|
void | setGravityVector (const base::Vector3d &g) |
| Set the current gravity vector.
|
|
const base::samples::RigidBodyStateSE3 & | floatingBaseState () |
| Get current status of floating base.
|
|
void | setContactWrenches (const base::samples::Wrenches &wrenches) |
| Set contact wrenches, names have to consistent with the configured contact points.
|
|
const RobotModelConfig & | getRobotModelConfig () |
| Get current robot model config.
|
|
bool | hasFloatingBase () |
| Is floating base robot?
|
|
urdf::ModelInterfaceSharedPtr | loadRobotURDF (const std::string &file_or_string) |
| Load URDF model from either file or string.
|
|