robot_env_evaluator 1.0.1
Loading...
Searching...
No Matches
state_source_bridge.hpp
Go to the documentation of this file.
1
25#ifndef ROBOT_ENV_EVALUATOR_STATE_SOURCE_BRIDGE_HPP
26#define ROBOT_ENV_EVALUATOR_STATE_SOURCE_BRIDGE_HPP
27
28#include <Eigen/Dense>
29#include <stdexcept>
30#include <string>
31
32namespace robot_env_evaluator
33{
48 public:
52 virtual ~KinematicDataBridge() = default;
53
61 virtual void getForwardKinematics(const Eigen::VectorXd& q, Eigen::MatrixXd& result);
62
70 virtual void getJacobian(const Eigen::VectorXd& q, Eigen::MatrixXd& result);
71
79 virtual void getMassMatrix(const Eigen::VectorXd& q, Eigen::MatrixXd& result);
80
88 virtual void getCoriolis(const Eigen::VectorXd& q, Eigen::MatrixXd& result);
89
97 virtual void getGravity(const Eigen::VectorXd& q, Eigen::MatrixXd& result);
98 };
99} // namespace robot_env_evaluator
100
101#endif // ROBOT_ENV_EVALUATOR_STATE_SOURCE_BRIDGE_HPP
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.