ORCA: Optimization-based framework for Robotic Control Applications
Public Member Functions | Protected Member Functions | List of all members
orca::gazebo::GazeboModel Class Reference

#include <GazeboModel.h>

Public Member Functions

 GazeboModel (const std::string &name)
 
 GazeboModel (::gazebo::physics::ModelPtr model)
 
const std::string & getName () const
 
const std::string & getBaseName ()
 
void setJointMapping (const std::vector< std::string > &joint_names)
 
bool setModelConfiguration (const std::vector< std::string > &joint_names, const std::vector< double > &joint_positions)
 
bool load (const std::string &model_name)
 
bool load (::gazebo::physics::ModelPtr model)
 
std::shared_ptr< orca::gazebo::GazeboForceTorqueSensorattachForceTorqueSensorToJoint (const std::string &joint_name, double update_rate=0)
 
std::shared_ptr< orca::gazebo::GazeboContactSensorattachContactSensorToLink (const std::string &link_name, const std::string &collision_name, double update_rate=0)
 
const Eigen::Vector3d & getGravity () const
 
const std::vector< std::string > & getActuatedJointNames () const
 
const Eigen::Matrix< double, 6, 1 > & getBaseVelocity () const
 
const Eigen::Affine3d & getWorldToBaseTransform () const
 
const Eigen::VectorXd & getJointPositions () const
 
const Eigen::VectorXd & getJointVelocities () const
 
void setJointGravityTorques (const Eigen::VectorXd &gravity_torques)
 
const Eigen::VectorXd & getJointExternalTorques () const
 
const Eigen::VectorXd & getJointMeasuredTorques () const
 
void setJointTorqueCommand (const Eigen::VectorXd &joint_torque_command)
 
int getNDof () const
 
void printState () const
 
void executeAfterWorldUpdate (std::function< void(uint32_t, double, double)> callback)
 
void setBrakes (bool enable)
 
double getIterations ()
 
void print () const
 

Protected Member Functions

void worldUpdateBegin ()
 
void worldUpdateEnd ()
 

Constructor & Destructor Documentation

◆ GazeboModel() [1/2]

orca::gazebo::GazeboModel::GazeboModel ( const std::string &  name)
inline

◆ GazeboModel() [2/2]

orca::gazebo::GazeboModel::GazeboModel ( ::gazebo::physics::ModelPtr  model)
inline

Member Function Documentation

◆ attachContactSensorToLink()

std::shared_ptr<orca::gazebo::GazeboContactSensor> orca::gazebo::GazeboModel::attachContactSensorToLink ( const std::string &  link_name,
const std::string &  collision_name,
double  update_rate = 0 
)
inline

◆ attachForceTorqueSensorToJoint()

std::shared_ptr<orca::gazebo::GazeboForceTorqueSensor> orca::gazebo::GazeboModel::attachForceTorqueSensorToJoint ( const std::string &  joint_name,
double  update_rate = 0 
)
inline

◆ executeAfterWorldUpdate()

void orca::gazebo::GazeboModel::executeAfterWorldUpdate ( std::function< void(uint32_t, double, double)>  callback)
inline

◆ getActuatedJointNames()

const std::vector<std::string>& orca::gazebo::GazeboModel::getActuatedJointNames ( ) const
inline

◆ getBaseName()

const std::string& orca::gazebo::GazeboModel::getBaseName ( )
inline

◆ getBaseVelocity()

const Eigen::Matrix<double,6,1>& orca::gazebo::GazeboModel::getBaseVelocity ( ) const
inline

◆ getGravity()

const Eigen::Vector3d& orca::gazebo::GazeboModel::getGravity ( ) const
inline

◆ getIterations()

double orca::gazebo::GazeboModel::getIterations ( )
inline

◆ getJointExternalTorques()

const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointExternalTorques ( ) const
inline

◆ getJointMeasuredTorques()

const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointMeasuredTorques ( ) const
inline

◆ getJointPositions()

const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointPositions ( ) const
inline

◆ getJointVelocities()

const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointVelocities ( ) const
inline

◆ getName()

const std::string& orca::gazebo::GazeboModel::getName ( ) const
inline

◆ getNDof()

int orca::gazebo::GazeboModel::getNDof ( ) const
inline

◆ getWorldToBaseTransform()

const Eigen::Affine3d& orca::gazebo::GazeboModel::getWorldToBaseTransform ( ) const
inline

◆ load() [1/2]

bool orca::gazebo::GazeboModel::load ( const std::string &  model_name)
inline

◆ load() [2/2]

bool orca::gazebo::GazeboModel::load ( ::gazebo::physics::ModelPtr  model)
inline

◆ print()

void orca::gazebo::GazeboModel::print ( ) const
inline

◆ printState()

void orca::gazebo::GazeboModel::printState ( ) const
inline

◆ setBrakes()

void orca::gazebo::GazeboModel::setBrakes ( bool  enable)
inline

◆ setJointGravityTorques()

void orca::gazebo::GazeboModel::setJointGravityTorques ( const Eigen::VectorXd &  gravity_torques)
inline

◆ setJointMapping()

void orca::gazebo::GazeboModel::setJointMapping ( const std::vector< std::string > &  joint_names)
inline

◆ setJointTorqueCommand()

void orca::gazebo::GazeboModel::setJointTorqueCommand ( const Eigen::VectorXd &  joint_torque_command)
inline

◆ setModelConfiguration()

bool orca::gazebo::GazeboModel::setModelConfiguration ( const std::vector< std::string > &  joint_names,
const std::vector< double > &  joint_positions 
)
inline

◆ worldUpdateBegin()

void orca::gazebo::GazeboModel::worldUpdateBegin ( )
inlineprotected

◆ worldUpdateEnd()

void orca::gazebo::GazeboModel::worldUpdateEnd ( )
inlineprotected

The documentation for this class was generated from the following file: