#include <GazeboModel.h>
orca::gazebo::GazeboModel::GazeboModel |
( |
const std::string & |
name | ) |
|
|
inline |
orca::gazebo::GazeboModel::GazeboModel |
( |
::gazebo::physics::ModelPtr |
model | ) |
|
|
inline |
::gazebo::sensors::ContactSensorPtr orca::gazebo::GazeboModel::attachContactSensorToLink |
( |
const std::string & |
link_name, |
|
|
double |
update_rate = 0 |
|
) |
| |
|
inline |
::gazebo::sensors::ForceTorqueSensorPtr orca::gazebo::GazeboModel::attachForceTorqueSensorToJoint |
( |
const std::string & |
joint_name, |
|
|
double |
update_rate = 0 |
|
) |
| |
|
inline |
void orca::gazebo::GazeboModel::executeAfterWorldUpdate |
( |
std::function< void(uint32_t, double, double)> |
callback | ) |
|
|
inline |
const std::vector<std::string>& orca::gazebo::GazeboModel::getActuatedJointNames |
( |
| ) |
const |
|
inline |
const std::string& orca::gazebo::GazeboModel::getBaseName |
( |
| ) |
|
|
inline |
const Eigen::Matrix<double,6,1>& orca::gazebo::GazeboModel::getBaseVelocity |
( |
| ) |
const |
|
inline |
const Eigen::Vector3d& orca::gazebo::GazeboModel::getGravity |
( |
| ) |
const |
|
inline |
double orca::gazebo::GazeboModel::getIterations |
( |
| ) |
|
|
inline |
const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointExternalTorques |
( |
| ) |
const |
|
inline |
const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointMeasuredTorques |
( |
| ) |
const |
|
inline |
const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointPositions |
( |
| ) |
const |
|
inline |
const Eigen::VectorXd& orca::gazebo::GazeboModel::getJointVelocities |
( |
| ) |
const |
|
inline |
const std::string& orca::gazebo::GazeboModel::getName |
( |
| ) |
const |
|
inline |
int orca::gazebo::GazeboModel::getNDof |
( |
| ) |
const |
|
inline |
const Eigen::Affine3d& orca::gazebo::GazeboModel::getWorldToBaseTransform |
( |
| ) |
const |
|
inline |
bool orca::gazebo::GazeboModel::load |
( |
const std::string & |
model_name | ) |
|
|
inline |
bool orca::gazebo::GazeboModel::load |
( |
::gazebo::physics::ModelPtr |
model | ) |
|
|
inline |
void orca::gazebo::GazeboModel::print |
( |
| ) |
const |
|
inline |
void orca::gazebo::GazeboModel::printState |
( |
| ) |
const |
|
inline |
void orca::gazebo::GazeboModel::setBrakes |
( |
bool |
enable | ) |
|
|
inline |
void orca::gazebo::GazeboModel::setJointGravityTorques |
( |
const Eigen::VectorXd & |
gravity_torques | ) |
|
|
inline |
void orca::gazebo::GazeboModel::setJointMapping |
( |
const std::vector< std::string > & |
joint_names | ) |
|
|
inline |
void orca::gazebo::GazeboModel::setJointTorqueCommand |
( |
const Eigen::VectorXd & |
joint_torque_command | ) |
|
|
inline |
bool orca::gazebo::GazeboModel::setModelConfiguration |
( |
const std::vector< std::string > & |
joint_names, |
|
|
const std::vector< double > & |
joint_positions |
|
) |
| |
|
inline |
void orca::gazebo::GazeboModel::worldUpdateBegin |
( |
| ) |
|
|
inlineprotected |
void orca::gazebo::GazeboModel::worldUpdateEnd |
( |
| ) |
|
|
inlineprotected |
The documentation for this class was generated from the following file:
- /home/docs/checkouts/readthedocs.org/user_builds/orca-controller/checkouts/dev/include/orca/gazebo/GazeboModel.h