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

A simulated robot implementing the API for kinematics. More...

#include <robot_sim.h>

Inheritance diagram for arl::robot::RobotSim:
Collaboration diagram for arl::robot::RobotSim:

Public Member Functions

 RobotSim ()
 
 RobotSim (std::shared_ptr< arl::robot::Model > m, double cycle_rate_sec)
 Constructs a simulated object based on its model and the control cycle given by the user. More...
 
void waitNextCycle ()
 Waits the remaining amount of time for the next cycle using a ros::Rate. More...
 
bool isOk ()
 return current condition of the robot. By default a running controller will terminate if false is returned. More...
 
void setMode (arl::robot::Mode mode)
 Sets a dummy mode for the robot in order to be compliant with the interfaces of a real robot. More...
 
void setJointTrajectory (const KDL::JntArray &input, double duration, const int chain_index=-1)
 Sends joint trajectories to the robot using KDL. More...
 
void setJointTrajectory (const arma::vec &input, double duration, const int chain_index=-1)
 Sends joint trajectories to the robot using Armadillo. More...
 
void setJointTrajectory (const Eigen::VectorXd &input, double duration, const int chain_index=-1)
 Sends joint trajectories to the robot using Eigen. More...
 
template<typename T >
void setJointTrajectoryTemplate (const T &input, double duration, const int chain_index=-1)
 Perfoms a 5th-order trajectory. Called by the RobotSim::setJointTrajectory() functions. More...
 
void setJointPosition (const KDL::JntArray &input, const int chain_index=-1)
 Sends joint positions to the robot using KDL. More...
 
void setJointPosition (const arma::vec &input, const int chain_index=-1)
 Sends joint positions to the robot using Armadillo. More...
 
void setJointPosition (const Eigen::VectorXd &input, const int chain_index=-1)
 Sends joint positions to the robot using Eigen. More...
 
template<typename T >
void setJointPositionTemplate (const T &input, const int chain_index=-1)
 Called by the RobotSim::setJointPosition() functions. Just writes the input to an internal state variable. More...
 
void getJointPosition (KDL::JntArray &output, const int chain_index=-1)
 Reads the current joint positions to the robot using KDL. More...
 
void getJointPosition (arma::vec &output, const int chain_index=-1)
 Reads the current joint positions from the robot using Armadillo. More...
 
void getJointPosition (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint positions from the robot using Eigen. More...
 
template<typename T >
void getJointPositionTemplate (T &output, const int chain_index=-1)
 Called by the RobotSim::getJointPosition() functions. Just writes the the internal state variable to the output. More...
 
void getJacobian (KDL::Jacobian &output, const unsigned int chain_index=0)
 Reads the current base Jacobian matrix from the robot using KDL. More...
 
void getJacobian (arma::mat &output, const unsigned int chain_index=0)
 Reads the current base Jacobian matrix from the robot using Armadillo. More...
 
void getJacobian (Eigen::MatrixXd &output, const unsigned int chain_index=0)
 Reads the current base Jacobian matrix from the robot using Eigen. More...
 
template<typename T >
void getJacobianTemplate (T &output, const unsigned int chain_index=0)
 Called by the RobotSim::getJacobian() functions. Reads the jacobian from the Jacobian Solvers of the used Model. More...
 
void getTaskPose (KDL::Frame &output, const unsigned int chain_index=0)
 Reads the current Cartesian pose from the robot using KDL. More...
 
void getTaskPose (arma::mat &output, const unsigned int chain_index=0)
 Reads the current Cartesian pose from the robot using Armadillo. More...
 
void getTaskPose (Eigen::MatrixXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian pose from the robot using Eigen. More...
 
template<typename T >
void getTaskPoseTemplate (T &output, const unsigned int chain_index=0)
 Called by the RobotSim::getTaskPose() functions. Returns the Cartesian pose by using the current joint positions stored internally and the forward kinematics solvers of the used Model. More...
 
void getTaskPosition (KDL::Vector &output, const unsigned int chain_index=0)
 Reads the current Cartesian Position from the robot using KDL. More...
 
void getTaskPosition (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian position from the robot using Armadillo. More...
 
void getTaskPosition (Eigen::Vector3d &output, const unsigned int chain_index=0)
 Reads the current joint positions from the robot using Eigen. More...
 
template<typename T >
void getTaskPositionTemplate (T &output, const unsigned int chain_index=0)
 Called by the RobotSim::getTaskPosition() functions. The same as RobotSim::getTaskPose(), but only for position. More...
 
void getTaskOrientation (KDL::Rotation &output, const unsigned int chain_index=0)
 Reads the current Cartesian orientation (Rotation matrix) from the robot using KDL. More...
 
void getTaskOrientation (arma::mat &output, const unsigned int chain_index=0)
 Reads the current Cartesian orientation (Rotation matrix) from the robot using Armadillo. More...
 
void getTaskOrientation (Eigen::Matrix3d &output, const unsigned int chain_index=0)
 Reads the current Cartesian orientation (Rotation matrix) from the robot using Eigen. More...
 
template<typename T >
void getTaskOrientationTemplate (T &output, const unsigned int chain_index=0)
 Called by the RobotSim::getTaskOrientation() functions. The same as RobotSim::getTaskPose(), but only for the orientation. More...
 
void getTwist (KDL::Twist &output, const unsigned int chain_index=0)
 Reads the current Cartesian velocity from the robot using KDL. More...
 
void getTwist (arma::vec &output, const unsigned int chain_index=0)
 Reads the current Cartesian velocity from the robot using Armadillo. More...
 
void getTwist (Eigen::VectorXd &output, const unsigned int chain_index=0)
 Reads the current Cartesian velocity from the robot using Eigen. More...
 
template<typename T >
void getTwistTemplate (T &output, const unsigned int chain_index=0)
 Called by the RobotSim::getTwist() functions. Calls the getJointVelocity() and getJacobian() and multiply them in order to produce the Cartesian velocity. 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 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 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 getJointVelocity (Eigen::VectorXd &output, const int chain_index=-1)
 Reads the current joint velocities from the robot using Eigen. 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 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 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 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...
 

Additional Inherited Members

- 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...
 
- 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

A simulated robot implementing the API for kinematics.

Currently this dummy class provide only kinematic simulations, which means that does not solve for the dynamics. Dynamic simulations (reading and sending forces/torques to the robot) are not possible. It can be used for visualization purposes.

,

Constructor & Destructor Documentation

arl::robot::RobotSim::RobotSim ( )

Empty contructor

arl::robot::RobotSim::RobotSim ( std::shared_ptr< arl::robot::Model m,
double  cycle_rate_sec 
)

Constructs a simulated object based on its model and the control cycle given by the user.

Parameters
mThe model to be used by the simulated robot
cycle_rate_secThe The rate that the robot will run in sec. Defaults to 0.001

Member Function Documentation

void arl::robot::RobotSim::getJacobian ( KDL::Jacobian &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current base Jacobian matrix from 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.

Here is the call graph for this function:

void arl::robot::RobotSim::getJacobian ( arma::mat &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current base Jacobian matrix from the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::getJacobian ( Eigen::MatrixXd &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current base Jacobian matrix 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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::getJacobianTemplate ( T &  output,
const unsigned int  chain_index = 0 
)
inline

Called by the RobotSim::getJacobian() functions. Reads the jacobian from the Jacobian Solvers of the used Model.

Here is the call graph for this function:

void arl::robot::RobotSim::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.

Here is the call graph for this function:

void arl::robot::RobotSim::getJointPosition ( arma::vec &  output,
const int  chain_index = -1 
)
virtual

Reads the current joint positions from the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::getJointPositionTemplate ( T &  output,
const int  chain_index = -1 
)
inline

Called by the RobotSim::getJointPosition() functions. Just writes the the internal state variable to the output.

void arl::robot::RobotSim::getTaskOrientation ( KDL::Rotation &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian orientation (Rotation matrix) from 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.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskOrientation ( arma::mat &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian orientation (Rotation matrix) from the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskOrientation ( Eigen::Matrix3d &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian orientation (Rotation matrix) 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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::getTaskOrientationTemplate ( T &  output,
const unsigned int  chain_index = 0 
)
inline

Called by the RobotSim::getTaskOrientation() functions. The same as RobotSim::getTaskPose(), but only for the orientation.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskPose ( KDL::Frame &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian pose from 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.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskPose ( arma::mat &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian pose from the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskPose ( Eigen::MatrixXd &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian pose 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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::getTaskPoseTemplate ( T &  output,
const unsigned int  chain_index = 0 
)
inline

Called by the RobotSim::getTaskPose() functions. Returns the Cartesian pose by using the current joint positions stored internally and the forward kinematics solvers of the used Model.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskPosition ( KDL::Vector &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian Position from 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.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskPosition ( arma::vec &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian position from the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::getTaskPosition ( Eigen::Vector3d &  output,
const unsigned int  chain_index = 0 
)
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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::getTaskPositionTemplate ( T &  output,
const unsigned int  chain_index = 0 
)
inline

Called by the RobotSim::getTaskPosition() functions. The same as RobotSim::getTaskPose(), but only for position.

Here is the call graph for this function:

void arl::robot::RobotSim::getTwist ( KDL::Twist &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian velocity from 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.

Here is the call graph for this function:

void arl::robot::RobotSim::getTwist ( arma::vec &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian velocity from the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::getTwist ( Eigen::VectorXd &  output,
const unsigned int  chain_index = 0 
)
virtual

Reads the current Cartesian velocity 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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::getTwistTemplate ( T &  output,
const unsigned int  chain_index = 0 
)
inline

Called by the RobotSim::getTwist() functions. Calls the getJointVelocity() and getJacobian() and multiply them in order to produce the Cartesian velocity.

Here is the call graph for this function:

bool arl::robot::RobotSim::isOk ( )
virtual

return current condition of the robot. By default a running controller will terminate if false is returned.

Implements arl::robot::Robot.

void arl::robot::RobotSim::setJointPosition ( const KDL::JntArray &  input,
const int  chain_index = -1 
)
virtual

Sends joint positions to the robot using KDL.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::setJointPosition ( const arma::vec &  input,
const int  chain_index = -1 
)
virtual

Sends joint positions to the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::setJointPositionTemplate ( const T &  input,
const int  chain_index = -1 
)
inline

Called by the RobotSim::setJointPosition() functions. Just writes the input to an internal state variable.

Attention
It will throw an error in case the robot has not been set to Mode::POSITION_CONTROL
void arl::robot::RobotSim::setJointTrajectory ( const KDL::JntArray &  input,
double  duration,
const int  chain_index = -1 
)
virtual

Sends joint trajectories to the robot using KDL.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::setJointTrajectory ( const arma::vec &  input,
double  duration,
const int  chain_index = -1 
)
virtual

Sends joint trajectories to the robot using Armadillo.

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

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::setJointTrajectory ( const Eigen::VectorXd &  input,
double  duration,
const int  chain_index = -1 
)
virtual

Sends joint trajectories 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.

Here is the call graph for this function:

template<typename T >
void arl::robot::RobotSim::setJointTrajectoryTemplate ( const T &  input,
double  duration,
const int  chain_index = -1 
)
inline

Perfoms a 5th-order trajectory. Called by the RobotSim::setJointTrajectory() functions.

Attention
It will throw an error in case the robot has not been set to Mode::POSITION_CONTROL

Here is the call graph for this function:

void arl::robot::RobotSim::setMode ( arl::robot::Mode  mode)
virtual

Sets a dummy mode for the robot in order to be compliant with the interfaces of a real robot.

Reimplemented from arl::robot::Robot.

Here is the call graph for this function:

void arl::robot::RobotSim::waitNextCycle ( )
virtual

Waits the remaining amount of time for the next cycle using a ros::Rate.

Implements arl::robot::Robot.