AUTh-ARL Core Stack  0.7
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
arl::mujoco::Robot Class Reference

Class representing a Robot in MuJoCo. More...

#include <robot.h>

Inheritance diagram for arl::mujoco::Robot:
Collaboration diagram for arl::mujoco::Robot:

Public Member Functions

 Robot (const std::shared_ptr< mujoco::Model > &model, const std::string &name)
 The default constructor. More...
 
 ~Robot ()
 
void waitNextCycle ()
 Waits for the next cycle of the control loop. More...
 
bool isOk ()
 Returns if the robot hardware is ok and operable. Should be implemented according to the robot in use. More...
 
void getJointPosition (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint positions from the robot using Eigen. More...
 
void getJointPosition (KDL::JntArray &output, const int chain_index=-1)
 Reads the current joint positions to the robot using KDL. More...
 
void getJointVelocity (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint velocities from the robot using Eigen. More...
 
void setJointPosition (const Eigen::VectorXd &input, const int chain_index=-1)
 Sends joint positions to the robot using Eigen. More...
 
- Public Member Functions inherited from arl::robot::Robot
 Robot ()
 Empty constructor. More...
 
 Robot (std::shared_ptr< Model > m, const std::string &name="Unnamed")
 Default constructor. More...
 
virtual void setJointPosition (const KDL::JntArray &input, const int chain_index=-1)
 Sends joint positions to the robot using KDL. More...
 
virtual void setJointPosition (const arma::vec &input, const int chain_index=-1)
 Sends joint positions to the robot using Armadillo. More...
 
virtual void setJointTrajectory (const KDL::JntArray &input, double duration, const int chain_index=-1)
 Sends joint trajectories to the robot using KDL. More...
 
virtual void setJointTrajectory (const arma::vec &input, double duration, const int chain_index=-1)
 Sends joint trajectories to the robot using Armadillo. More...
 
virtual void setJointTrajectory (const Eigen::VectorXd &input, double duration, const int chain_index=-1)
 Sends joint trajectories to the robot using Eigen. More...
 
virtual void setJointVelocity (const KDL::JntArray &input, const int chain_index=-1)
 Sends joint velocities to the robot using KDL. More...
 
virtual void setJointVelocity (const arma::vec &input, const int chain_index=-1)
 Sends joint velocities to the robot using Armadillo. More...
 
virtual void setJointVelocity (const Eigen::VectorXd &input, const int chain_index=-1)
 Sends joint velocities to the robot using Eigen. More...
 
virtual void setJointTorque (const KDL::JntArray &input, const int chain_index=-1)
 Sends joint velocities to the robot using KDL. More...
 
virtual void setJointTorque (const arma::vec &input, const int chain_index=-1)
 Sends joint torques to the robot using Armadillo. More...
 
virtual void setJointTorque (const Eigen::VectorXd &input, const int chain_index=-1)
 Sends joint torques to the robot using Eigen. More...
 
virtual void setTaskPose (const KDL::Frame &input, const unsigned int chain_index=0)
 Sends joint torques to the robot using KDL. More...
 
virtual void setTaskPose (const arma::mat &input, const unsigned int chain_index=0)
 Sends Cartesian pose to the robot using Armadillo. More...
 
virtual void setTaskPose (const Eigen::MatrixXd &input, const unsigned int chain_index=0)
 Sends Cartesian pose to the robot using Eigen. More...
 
virtual void setCartStiffness (const KDL::Wrench &input, const unsigned int chain_index=0)
 Sends the cartesian stiffness for robots which provide Cartesian Impedance controller. More...
 
virtual void setCartStiffness (const arma::vec &input, const unsigned int chain_index=0)
 Sends the cartesian stiffness for robots which provide Cartesian Impedance controller. More...
 
virtual void setCartStiffness (const Eigen::VectorXd &input, const unsigned int chain_index=0)
 Sends the cartesian stiffness for robots which provide Cartesian Impedance controller. More...
 
virtual void setCartDamping (const KDL::Wrench &input, const unsigned int chain_index=0)
 Sends the cartesian damping for robots which provide Cartesian Impedance controller. More...
 
virtual void setCartDamping (const arma::vec &input, const unsigned int chain_index=0)
 Sends the cartesian damping for robots which provide Cartesian Impedance controller. More...
 
virtual void setCartDamping (const Eigen::VectorXd &input, const unsigned int chain_index=0)
 Sends the cartesian damping for robots which provide Cartesian Impedance controller. More...
 
virtual void setTwist (const KDL::Twist &input, const unsigned int chain_index=0)
 
virtual void setTwist (const arma::vec &input, const unsigned int chain_index=0)
 Sends Cartesian velocity to the robot using Armadillo. More...
 
virtual void setTwist (const Eigen::VectorXd &input, const unsigned int chain_index=0)
 Sends Cartesian velocity to the robot using Eigen. More...
 
virtual void setWrench (const KDL::Wrench &input, const unsigned int chain_index=0)
 Sends Cartesian velocity to the robot using KDL. More...
 
virtual void setWrench (const arma::vec &input, const unsigned int chain_index=0)
 Sends Cartesian force/torque to the robot using Armadillo. More...
 
virtual void setWrench (const Eigen::VectorXd &input, const unsigned int chain_index=0)
 Sends Cartesian force/torque to the robot using Eigen. More...
 
virtual void getJointPosition (arma::vec &output, const int chain_index=-1)
 Reads the current joint positions from the robot using Armadillo. More...
 
virtual void getJointVelocity (KDL::JntArray &output, const int chain_index=-1)
 Reads the current joint velocities from the robot using KDL. More...
 
virtual void getJointVelocity (arma::vec &output, const int chain_index=-1)
 Reads the current joint velocities from the robot using Armadillo. More...
 
virtual void getJointTorque (KDL::JntArray &output, const int chain_index=-1)
 Reads the current joint torques from the robot using KDL. More...
 
virtual void getJointTorque (arma::vec &output, const int chain_index=-1)
 Reads the current joint torques from the robot using Armadillo. More...
 
virtual void getJointTorque (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint torques from the robot using Eigen. More...
 
virtual void getJointExternalTorque (KDL::JntArray &output, const int chain_index=-1)
 Reads the current external joint torques from the robot using KDL. More...
 
virtual void getJointExternalTorque (arma::vec &output, const int chain_index=-1)
 Reads the current external joint torques from the robot using Armadillo. More...
 
virtual void getJointExternalTorque (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current external joint torques from the robot using Eigen. More...
 
virtual void getJointStiffness (KDL::JntArray &output, const int chain_index=-1)
 Reads the current joint stiffness from the robot using KDL. More...
 
virtual void getJointStiffness (arma::vec &output, const int chain_index=-1)
 Reads the current joint stiffness from the robot using Armadillo. More...
 
virtual void getJointStiffness (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint stiffness from the robot using Eigen. More...
 
virtual void getJointDamping (KDL::JntArray &output, const int chain_index=-1)
 Reads the current joint damping from the robot using KDL. More...
 
virtual void getJointDamping (arma::vec &output, const int chain_index=-1)
 Reads the current joint damping from the robot using Armadillo. More...
 
virtual void getJointDamping (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint damping from the robot using Eigen. More...
 
virtual void getTaskPose (KDL::Frame &output, const unsigned int chain_index=0)
 Reads the current Cartesian pose from the robot using KDL. More...
 
virtual void getTaskPose (arma::mat &output, const unsigned int chain_index=0)
 Reads the current Cartesian pose from the robot using Armadillo. More...
 
virtual void getTaskPose (Eigen::MatrixXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian pose from the robot using Eigen. More...
 
virtual void getTaskPosition (KDL::Vector &output, const unsigned int chain_index=0)
 Reads the current Cartesian Position from the robot using KDL. More...
 
virtual void getTaskPosition (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian position from the robot using Armadillo. More...
 
virtual void getTaskPosition (Eigen::Vector3d &output, const unsigned int chain_index=0)
 Reads the current joint positions from the robot using Eigen. More...
 
virtual void getTaskOrientation (KDL::Rotation &output, const unsigned int chain_index=0)
 Reads the current Cartesian orientation (Rotation matrix) from the robot using KDL. More...
 
virtual void getTaskOrientation (arma::mat &output, const unsigned int chain_index=0)
 Reads the current Cartesian orientation (Rotation matrix) from the robot using Armadillo. More...
 
virtual void getTaskOrientation (Eigen::Matrix3d &output, const unsigned int chain_index=0)
 Reads the current Cartesian orientation (Rotation matrix) from the robot using Eigen. More...
 
virtual void getTwist (KDL::Twist &output, const unsigned int chain_index=0)
 Reads the current Cartesian velocity from the robot using KDL. More...
 
virtual void getTwist (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian velocity from the robot using Armadillo. More...
 
virtual void getTwist (Eigen::VectorXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian velocity from the robot using Eigen. More...
 
virtual void getWrench (KDL::Wrench &output, const unsigned int chain_index=0)
 Reads the current Cartesian force/torque from the robot using KDL. More...
 
virtual void getWrench (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian force/torque from the robot using Armadillo. More...
 
virtual void getWrench (Eigen::VectorXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian force/torque from the robot using Eigen. More...
 
virtual void getExternalWrench (KDL::Wrench &output, const unsigned int chain_index=0)
 Reads the current external Cartesian force/torque from the robot using KDL. More...
 
virtual void getExternalWrench (arma::vec &output, const unsigned int chain_index=0)
 Reads the current external Cartesian force/torque from the robot using Armadillo. More...
 
virtual void getExternalWrench (Eigen::VectorXd &output, const unsigned int chain_index=0)
 Reads the current external Cartesian force/torque from the robot using Eigen. More...
 
virtual void getTaskStiffness (KDL::JntArray &output, const unsigned int chain_index=0)
 Reads the current Cartesian stiffness from the robot using KDL. More...
 
virtual void getTaskStiffness (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian stiffness from the robot using Armadillo. More...
 
virtual void getTaskStiffness (Eigen::VectorXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian stiffness from the robot using Eigen. More...
 
virtual void getTaskDamping (KDL::JntArray &output, const unsigned int chain_index=0)
 Reads the current Cartesian damping from the robot using KDL. More...
 
virtual void getTaskDamping (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian damping rom the robot using Armadillo. More...
 
virtual void getTaskDamping (Eigen::VectorXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian damping from the robot using Eigen. More...
 
virtual void getJacobian (KDL::Jacobian &output, const unsigned int chain_index=0)
 Reads the current base Jacobian matrix from the robot using KDL. More...
 
virtual void getJacobian (arma::mat &output, const unsigned int chain_index=0)
 Reads the current base Jacobian matrix from the robot using Armadillo. More...
 
virtual void getJacobian (Eigen::MatrixXd &output, const unsigned int chain_index=0)
 Reads the current base Jacobian matrix from the robot using Eigen. More...
 
virtual void getMassMatrix (KDL::Frame &output, const int chain_index=0)
 Reads the current mass matrix from the robot. More...
 
virtual void getMassMatrix (arma::mat &output, const int chain_index=0)
 Reads the current mass matrix from the robot. More...
 
virtual void getMassMatrix (Eigen::MatrixXd &output, const int chain_index=0)
 Reads the current mass matrix from the robot. More...
 
virtual void stop ()
 
virtual void setMode (Mode mode)
 Sets the mode of the robot. More...
 
virtual void measure ()
 
template<typename T >
void getJointVelocityGeneric (T &output, const int chain_index=-1)
 Reads the joint velocity using the derivative of the position (previous and current position) More...
 
template<typename T >
void setJointVelocityGeneric (T &input, const int chain_index=-1)
 Reads the joint velocity by integrating the position (previous and current position) More...
 

Public Attributes

mjData * data
 
mjModel * mj_model
 
- Public Attributes inherited from arl::robot::Robot
arma::vec joint_pos_prev
 Stores the previous joint position used by arl::robot::setJointPositionGeneric. More...
 
double cycle
 The control cycle of the robot. More...
 
std::shared_ptr< Modelmodel
 A pointer to the Model that this Robot is using. More...
 
std::string robot_name
 The name of the robot. E.g. "KUKA LWR4". More...
 
std::string alias
 The alias of the robot, which is the name in lower case without spaces. E.g. "kuka_lwr4". More...
 
Mode mode
 The current Mode of the robot. More...
 

Additional Inherited Members

- Protected Member Functions inherited from arl::robot::Robot
void throwFunctionIsNotImplemented (std::string function_name)
 
- Protected Attributes inherited from arl::robot::Robot
std::vector< Statestate
 The current state of the robot. More...
 

Detailed Description

Class representing a Robot in MuJoCo.

Constructor & Destructor Documentation

arl::mujoco::Robot::Robot ( const std::shared_ptr< mujoco::Model > &  model,
const std::string &  name 
)

The default constructor.

Parameters
modelA MuJoCo Model
nameThe name of the robot
arl::mujoco::Robot::~Robot ( )

Member Function Documentation

void arl::mujoco::Robot::getJointPosition ( Eigen::VectorXd &  output,
const int  chain_index = -1 
)
virtual

Reads the current joint positions from the robot using Eigen.

Parameters
outputThe output given by the robot
chain_indexThe index of the robots chain. Defaults to 0.

Reimplemented from arl::robot::Robot.

void arl::mujoco::Robot::getJointPosition ( KDL::JntArray &  output,
const int  chain_index = -1 
)
virtual

Reads the current joint positions to the robot using KDL.

Parameters
outputThe output given by the robot
chain_indexThe index of the robots chain. Defaults to 0.

Reimplemented from arl::robot::Robot.

void arl::mujoco::Robot::getJointVelocity ( Eigen::VectorXd &  output,
const int  chain_index = -1 
)
virtual

Reads the current joint velocities from the robot using Eigen.

Parameters
outputThe output given by the robot
chain_indexThe index of the robots chain. Defaults to 0.

Reimplemented from arl::robot::Robot.

bool arl::mujoco::Robot::isOk ( )
virtual

Returns if the robot hardware is ok and operable. Should be implemented according to the robot in use.

Returns
True if the robot haven't returns any errors. False otherwise.

Implements arl::robot::Robot.

void arl::mujoco::Robot::setJointPosition ( const Eigen::VectorXd &  input,
const int  chain_index = -1 
)
virtual

Sends joint positions to the robot using Eigen.

Parameters
inputThe input for sending to robot
chain_indexThe index of the robots chain. Defaults to 0.

Reimplemented from arl::robot::Robot.

void arl::mujoco::Robot::waitNextCycle ( )
virtual

Waits for the next cycle of the control loop.

In the case of a MuJoCo Robot it reades the simulation time and moves MuJoCo simulation one time step ahead. Use it at each control loop as in real robots.

Implements arl::robot::Robot.

Member Data Documentation

mjData* arl::mujoco::Robot::data
mjModel* arl::mujoco::Robot::mj_model