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

#include <GazeboServer.h>

Public Member Functions

 GazeboServer ()
 
 GazeboServer (int argc, char *argv[])
 
 GazeboServer (int argc, char const *argv[])
 
 GazeboServer (std::vector< std::string > server_options, const std::string &world_name="worlds/empty.world")
 
 GazeboServer (const std::string &world_name, std::vector< std::string > server_options={"--verbose"})
 
bool load (std::vector< std::string > server_options={"--verbose"}, const std::string &world_name="worlds/empty.world")
 
::gazebo::physics::WorldPtr loadWorld (const std::string &world_name)
 
bool enablePhysicsEngine (bool enable)
 
bool fileExists (const std::string &file_path)
 
std::string fileToString (const std::string &file_path)
 
bool spawnModel (const std::string &instanceName, const std::string &modelName)
 
double getDt ()
 
void runOnce ()
 
void run ()
 
void shutdown ()
 
::gazebo::physics::ModelPtr insertModelFromURDFFile (const std::string &urdf_url, Eigen::Vector3d init_pos=Eigen::Vector3d::Zero(), Eigen::Quaterniond init_rot=Eigen::Quaterniond::Identity(), std::string model_name="")
 
::gazebo::physics::ModelPtr insertModelFromURDFString (const std::string &urdf_str, Eigen::Vector3d init_pos=Eigen::Vector3d::Zero(), Eigen::Quaterniond init_rot=Eigen::Quaterniond::Identity(), std::string model_name="")
 
int getModelCount ()
 
std::vector< std::string > getModelNames ()
 
bool modelExists (const std::string &model_name)
 
const Eigen::Vector3d & getGravity ()
 
std::vector< std::string > getModelJointNames (const std::string &model_name)
 
::gazebo::physics::Joint_V getJointsFromNames (const std::string &model_name, const std::vector< std::string > &joint_names)
 
::gazebo::physics::ModelPtr getModelByName (const std::string &model_name)
 
::gazebo::physics::WorldPtr getWorld ()
 
void executeAfterWorldUpdate (std::function< void(uint32_t, double, double)> callback)
 
virtual ~GazeboServer ()
 

Constructor & Destructor Documentation

orca::gazebo::GazeboServer::GazeboServer ( )
inline
orca::gazebo::GazeboServer::GazeboServer ( int  argc,
char *  argv[] 
)
inline
orca::gazebo::GazeboServer::GazeboServer ( int  argc,
char const *  argv[] 
)
inline
orca::gazebo::GazeboServer::GazeboServer ( std::vector< std::string >  server_options,
const std::string &  world_name = "worlds/empty.world" 
)
inline
orca::gazebo::GazeboServer::GazeboServer ( const std::string &  world_name,
std::vector< std::string >  server_options = {"--verbose"} 
)
inline
virtual orca::gazebo::GazeboServer::~GazeboServer ( )
inlinevirtual

Member Function Documentation

bool orca::gazebo::GazeboServer::enablePhysicsEngine ( bool  enable)
inline
void orca::gazebo::GazeboServer::executeAfterWorldUpdate ( std::function< void(uint32_t, double, double)>  callback)
inline
bool orca::gazebo::GazeboServer::fileExists ( const std::string &  file_path)
inline
std::string orca::gazebo::GazeboServer::fileToString ( const std::string &  file_path)
inline
double orca::gazebo::GazeboServer::getDt ( )
inline
const Eigen::Vector3d& orca::gazebo::GazeboServer::getGravity ( )
inline
::gazebo::physics::Joint_V orca::gazebo::GazeboServer::getJointsFromNames ( const std::string &  model_name,
const std::vector< std::string > &  joint_names 
)
inline
::gazebo::physics::ModelPtr orca::gazebo::GazeboServer::getModelByName ( const std::string &  model_name)
inline
int orca::gazebo::GazeboServer::getModelCount ( )
inline
std::vector<std::string> orca::gazebo::GazeboServer::getModelJointNames ( const std::string &  model_name)
inline
std::vector<std::string> orca::gazebo::GazeboServer::getModelNames ( )
inline
::gazebo::physics::WorldPtr orca::gazebo::GazeboServer::getWorld ( )
inline
::gazebo::physics::ModelPtr orca::gazebo::GazeboServer::insertModelFromURDFFile ( const std::string &  urdf_url,
Eigen::Vector3d  init_pos = Eigen::Vector3d::Zero(),
Eigen::Quaterniond  init_rot = Eigen::Quaterniond::Identity(),
std::string  model_name = "" 
)
inline
::gazebo::physics::ModelPtr orca::gazebo::GazeboServer::insertModelFromURDFString ( const std::string &  urdf_str,
Eigen::Vector3d  init_pos = Eigen::Vector3d::Zero(),
Eigen::Quaterniond  init_rot = Eigen::Quaterniond::Identity(),
std::string  model_name = "" 
)
inline
bool orca::gazebo::GazeboServer::load ( std::vector< std::string >  server_options = {"--verbose"},
const std::string &  world_name = "worlds/empty.world" 
)
inline
::gazebo::physics::WorldPtr orca::gazebo::GazeboServer::loadWorld ( const std::string &  world_name)
inline
bool orca::gazebo::GazeboServer::modelExists ( const std::string &  model_name)
inline
void orca::gazebo::GazeboServer::run ( )
inline
void orca::gazebo::GazeboServer::runOnce ( )
inline
void orca::gazebo::GazeboServer::shutdown ( )
inline
bool orca::gazebo::GazeboServer::spawnModel ( const std::string &  instanceName,
const std::string &  modelName 
)
inline

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