Qontrol
|
Public Member Functions | |
void | setRobotState (const RobotState &robot_state) |
Load the robot model given a urdf path. More... | |
auto | getRobotState () -> RobotState |
Get the robot state (position, velocity, acceleration, and external torque) More... | |
virtual auto | getTipFrameName () -> std::string=0 |
Get the name of the tip frame in the model. More... | |
virtual auto | getRootFrameName () -> std::string=0 |
Get the name of the root frame in the model. More... | |
virtual auto | getNrOfDegreesOfFreedom () -> int=0 |
Get the robot number of degrees of freedom. More... | |
virtual void | setJointPosition (Eigen::VectorXd joint_position) |
Set the robot current joint position. More... | |
virtual auto | getJointPosition () -> Eigen::VectorXd |
get the robot current joint position More... | |
void | setLowerJointPositionLimits (Eigen::VectorXd lim) |
Set the robot lower joint position limits. More... | |
void | setUpperJointPositionLimits (Eigen::VectorXd lim) |
Set the robot upper joint position limits. More... | |
virtual auto | getLowerJointPositionLimits () -> Eigen::VectorXd |
Get the robot lower joint position limits. More... | |
virtual auto | getUpperJointPositionLimits () -> Eigen::VectorXd |
Get the robot upper joint position limits. More... | |
virtual void | setJointVelocity (Eigen::VectorXd joint_velocity) |
Set the robot current joint velocity. More... | |
virtual auto | getJointVelocity () -> Eigen::VectorXd |
Get the robot current joint velocity. More... | |
void | setJointVelocityLimits (Eigen::VectorXd lim) |
Set the robot joint velocity limts. More... | |
auto | getJointVelocityLimits () -> Eigen::VectorXd |
Get the robot joint velocity limts. More... | |
virtual void | setJointAcceleration (Eigen::VectorXd joint_acceleration) |
Set the robot current joint acceleration. More... | |
virtual auto | getJointAcceleration () -> Eigen::VectorXd |
Get the robot current joint acceleration. More... | |
virtual void | setJointTorque (Eigen::VectorXd joint_torque) |
Set the robot current joint torque. More... | |
virtual auto | getJointTorque () -> Eigen::VectorXd |
Get the robot current joint torque. More... | |
void | setJointTorqueLimits (Eigen::VectorXd lim) |
Set the robot joint torque limits. More... | |
auto | getJointTorqueLimits () -> Eigen::VectorXd |
Get the robot joint torque limits. More... | |
virtual void | setExternalJointTorque (Eigen::VectorXd external_joint_torque) |
Set the robot current external joint torque. More... | |
virtual auto | getExternalJointTorque () -> Eigen::VectorXd |
Get the robot current external joint torque. More... | |
virtual auto | getJointCoriolisTorques () -> Eigen::VectorXd=0 |
Get the vector representing the gravity effect associated to the \(g\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state. More... | |
virtual auto | getJointInertiaMatrix () -> Eigen::MatrixXd=0 |
Get the matrix representing the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state. More... | |
virtual auto | getInverseJointInertiaMatrix () -> Eigen::MatrixXd=0 |
Get the matrix representing the inverse of the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state. More... | |
virtual auto | getFramePose (const std::string &body_name) -> Eigen::Isometry3d=0 |
Get the pose of the frame called \(\text_it{body_name}\) in the URDF wrt. the root frame. More... | |
virtual auto | getTipFramePose () -> Eigen::Isometry3d=0 |
Get the pose of the tip frame wrt. the root frame. More... | |
virtual auto | getJacobian (const std::string &body_name) -> Eigen::MatrixXd=0 |
Get the Jacobian matrix expressed at the frame name \(\textit{body_name}\) in the URDF wrt. the root frame. More... | |
virtual auto | getJacobian (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::MatrixXd=0 |
virtual auto | getJacobianTimeDerivativeQdot (const std::string &body_name) -> Eigen::VectorXd=0 |
Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\). More... | |
virtual auto | getJacobianTimeDerivativeQdot (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::VectorXd=0 |
Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\). More... | |
virtual auto | getFrameVelocity (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the twist representing the velocity of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame. More... | |
virtual auto | getFrameVelocity (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the twist representing the \(\textit{frame}\) velocity wrt. the root frame. More... | |
virtual auto | getTipFrameVelocity () -> Eigen::Matrix< double, 6, 1 >=0 |
The twist representing the velocity of the tip frame wrt. the root frame. More... | |
virtual auto | getJointAccelerationFromTorques (Eigen::VectorXd torque) -> Eigen::VectorXd=0 |
virtual auto | getFrameAccelerationFromJointAcceleration (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration. More... | |
virtual auto | getFrameAccelerationFromJointAcceleration (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration. More... | |
virtual auto | getFrameAccelerationFromTorques (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque. More... | |
virtual auto | getFrameAccelerationFromTorques (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque. More... | |
virtual auto | getExternalWrench (const std::string &body_name) -> Eigen::Matrix< double, 6, 1 >=0 |
Get the external wrench applied on the named \(\textit{body_name}\) in the URDF wrt. the root frame given the external joint torques applied on the robot. More... | |
virtual auto | getExternalWrench (const std::string &body_name, const Eigen::Isometry3d &frame) -> Eigen::Matrix< double, 6, 1 >=0 |
auto | integrate (Eigen::VectorXd q, Eigen::VectorXd v, double dt) -> Eigen::VectorXd |
Static Public Member Functions | |
static auto | skew (Eigen::Vector3d vector) -> Eigen::Matrix3d |
compute the skew symetry matrix of a vector. Usefull to perform cross products More... | |
Protected Attributes | |
Eigen::VectorXd | lower_joint_position_limits |
Eigen::VectorXd | upper_joint_position_limits |
Eigen::VectorXd | joint_velocity_limits |
Eigen::VectorXd | joint_torque_limits |
|
virtual |
Get the robot current external joint torque.
|
pure virtual |
Get the external wrench applied on the named \(\textit{body_name}\) in the URDF wrt. the root frame given the external joint torques applied on the robot.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/acceleration.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the acceleration of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame given the robot current joint position/velocity/torque/external torque.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the pose of the frame called \(\text_it{body_name}\) in the URDF wrt. the root frame.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the twist representing the velocity of the frame named \(\textit{body_name}\) in the URDF wrt. the root frame.
body_name | The name of the frame in the urdf. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the twist representing the \(\textit{frame}\) velocity wrt. the root frame.
frame | A frame expressed wrt. the root frame. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the matrix representing the inverse of the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the Jacobian matrix expressed at the frame name \(\textit{body_name}\) in the URDF wrt. the root frame.
body_name | The name of the frame in the urdf |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
frame | A frame expressed wrt. the root frame. |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\).
body_name | The name of the frame in the urdf |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the vector representing the \(\dot{J}\dot{q}\) terme in the equation \(\dot{twist} = \dot{J}\dot{q} + J\ddot{q}\).
body_name | The name of the frame in the urdf |
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
virtual |
Get the robot current joint acceleration.
|
pure virtual |
Get the vector representing the gravity effect associated to the \(g\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the matrix representing the joint space inertia matrix associated to the \(M(q)\) term in the equation of motion: \( M(q)\ddot{q} + c(q, \dot{q}) + g(q) = \tau \). Taken at the current robot state.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
virtual |
get the robot current joint position
|
virtual |
Get the robot current joint torque.
auto Qontrol::Model::GenericModel::getJointTorqueLimits | ( | ) | -> Eigen::VectorXd |
Get the robot joint torque limits.
|
virtual |
Get the robot current joint velocity.
auto Qontrol::Model::GenericModel::getJointVelocityLimits | ( | ) | -> Eigen::VectorXd |
Get the robot joint velocity limts.
|
virtual |
Get the robot lower joint position limits.
|
pure virtual |
Get the robot number of degrees of freedom.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
auto Qontrol::Model::GenericModel::getRobotState | ( | ) | -> RobotState |
Get the robot state (position, velocity, acceleration, and external torque)
|
pure virtual |
Get the name of the root frame in the model.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the name of the tip frame in the model.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
Get the pose of the tip frame wrt. the root frame.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
pure virtual |
The twist representing the velocity of the tip frame wrt. the root frame.
Implemented in Qontrol::Model::RobotModel< RobotModelImplType::PINOCCHIO >.
|
virtual |
Get the robot upper joint position limits.
|
virtual |
Set the robot current external joint torque.
external_joint_torque | the robot external joint torque |
|
virtual |
Set the robot current joint acceleration.
joint_acceleration | the robot current joint acceleration |
|
virtual |
Set the robot current joint position.
joint_position | the robot current joint position |
|
virtual |
Set the robot current joint torque.
joint_torque | the robot current joint torque |
void Qontrol::Model::GenericModel::setJointTorqueLimits | ( | Eigen::VectorXd | lim | ) |
Set the robot joint torque limits.
lim | The robot upper velocity limits |
|
virtual |
Set the robot current joint velocity.
joint_velocity | the robot current joint velocity |
void Qontrol::Model::GenericModel::setJointVelocityLimits | ( | Eigen::VectorXd | lim | ) |
Set the robot joint velocity limts.
lim | The robot velocity limits |
void Qontrol::Model::GenericModel::setLowerJointPositionLimits | ( | Eigen::VectorXd | lim | ) |
Set the robot lower joint position limits.
lim | The robot lower position limits |
void Qontrol::Model::GenericModel::setRobotState | ( | const RobotState & | robot_state | ) |
Load the robot model given a urdf path.
urdf_path | a urdf string representing the robot description |
root_link | The name of the root link in the urdf file. By default the first link in the urdf is taken. |
tip_link | The name of the tip link in the urdf file. By default the last link in the urdf is taken. |
Sets the robot state (position, velocity, acceleration, and external torque)
robot_state | the robot state |
void Qontrol::Model::GenericModel::setUpperJointPositionLimits | ( | Eigen::VectorXd | lim | ) |
Set the robot upper joint position limits.
lim | The robot upper position limits |
|
static |
compute the skew symetry matrix of a vector. Usefull to perform cross products
vector | a vector |