25#ifndef ROBOT_ENV_EVALUATOR_STATE_SOURCE_BRIDGE_HPP
26#define ROBOT_ENV_EVALUATOR_STATE_SOURCE_BRIDGE_HPP
32namespace robot_env_evaluator
70 virtual void getJacobian(
const Eigen::VectorXd& q, Eigen::MatrixXd& result);
79 virtual void getMassMatrix(
const Eigen::VectorXd& q, Eigen::MatrixXd& result);
88 virtual void getCoriolis(
const Eigen::VectorXd& q, Eigen::MatrixXd& result);
97 virtual void getGravity(
const Eigen::VectorXd& q, Eigen::MatrixXd& result);
The KinematicDataBridge class.
virtual void getGravity(const Eigen::VectorXd &q, Eigen::MatrixXd &result)
Get the gravity vector for the given joint configuration.
virtual void getCoriolis(const Eigen::VectorXd &q, Eigen::MatrixXd &result)
Get the Coriolis matrix for the given joint configuration.
virtual void getJacobian(const Eigen::VectorXd &q, Eigen::MatrixXd &result)
Get the Jacobian for the given joint configuration.
virtual void getMassMatrix(const Eigen::VectorXd &q, Eigen::MatrixXd &result)
Get the mass matrix for the given joint configuration.
virtual void getForwardKinematics(const Eigen::VectorXd &q, Eigen::MatrixXd &result)
Get the forward kinematics for the given joint configuration.
virtual ~KinematicDataBridge()=default
Destroy the Kinematic Data Bridge object.