#include <gazebo_ros_factory.h>
Public Member Functions | |
GazeboRosFactory (Entity *parent) | |
Constructor. | |
virtual | ~GazeboRosFactory () |
Destructor. | |
Protected Member Functions | |
virtual void | FiniChild () |
Finalize the controller. | |
virtual void | InitChild () |
Init the controller. | |
virtual void | LoadChild (XMLConfigNode *node) |
Load the controller. | |
virtual void | UpdateChild () |
Update the controller. | |
Private Member Functions | |
bool | deleteModel (gazebo_plugins::DeleteModel::Request &req, gazebo_plugins::DeleteModel::Response &res) |
ros service call to delete model in Gazebo | |
void | FactoryQueueThread () |
bool | IsGazeboModelXML (std::string robot_model) |
check to see if string is a Gazebo Model XML | |
bool | IsURDF (std::string robot_model) |
check to see if string is a URDF XML | |
bool | pushToDeleteQueue (std::string model_name) |
push model name to iface queue for deletion | |
bool | pushToFactory (std::string gazebo_model_xml) |
push xml to factory, returns true if successful | |
bool | spawnModel (gazebo_plugins::SpawnModel::Request &req, gazebo_plugins::SpawnModel::Response &res) |
ros service call to spawn model via factory | |
Private Attributes | |
boost::thread | callback_queue_thread_ |
ros::ServiceServer | deleteModelService |
std::string | deleteModelServiceName |
ParamT< std::string > * | deleteModelServiceNameP |
ros::CallbackQueue | factory_queue_ |
use custom callback queue | |
gazebo::Model * | myParent |
controller parent, a model? | |
std::string | robotNamespace |
ParamT< std::string > * | robotNamespaceP |
for setting ROS name space | |
ros::NodeHandle * | rosnode_ |
A pointer to the ROS node. A node will be instantiated if it does not exist. | |
ros::ServiceServer | spawnModelService |
ros service | |
std::string | spawnModelServiceName |
ParamT< std::string > * | spawnModelServiceNameP |
Service Call Name. |
Definition at line 99 of file gazebo_ros_factory.h.
GazeboRosFactory::GazeboRosFactory | ( | Entity * | parent | ) |
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 52 of file gazebo_ros_factory.cpp.
GazeboRosFactory::~GazeboRosFactory | ( | ) | [virtual] |
Destructor.
Definition at line 70 of file gazebo_ros_factory.cpp.
bool GazeboRosFactory::deleteModel | ( | gazebo_plugins::DeleteModel::Request & | req, | |
gazebo_plugins::DeleteModel::Response & | res | |||
) | [private] |
ros service call to delete model in Gazebo
Definition at line 132 of file gazebo_ros_factory.cpp.
void GazeboRosFactory::FactoryQueueThread | ( | ) | [private] |
Definition at line 574 of file gazebo_ros_factory.cpp.
void GazeboRosFactory::FiniChild | ( | ) | [protected, virtual] |
Finalize the controller.
Definition at line 564 of file gazebo_ros_factory.cpp.
void GazeboRosFactory::InitChild | ( | ) | [protected, virtual] |
Init the controller.
Definition at line 545 of file gazebo_ros_factory.cpp.
bool GazeboRosFactory::IsGazeboModelXML | ( | std::string | robot_model | ) | [private] |
check to see if string is a Gazebo Model XML
Definition at line 121 of file gazebo_ros_factory.cpp.
bool GazeboRosFactory::IsURDF | ( | std::string | robot_model | ) | [private] |
check to see if string is a URDF XML
Definition at line 109 of file gazebo_ros_factory.cpp.
void GazeboRosFactory::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Load the controller.
node | XML config node |
Definition at line 79 of file gazebo_ros_factory.cpp.
bool GazeboRosFactory::pushToDeleteQueue | ( | std::string | model_name | ) | [private] |
push model name to iface queue for deletion
Connect to the libgazebo server
Open the Factory interface
Definition at line 490 of file gazebo_ros_factory.cpp.
bool GazeboRosFactory::pushToFactory | ( | std::string | gazebo_model_xml | ) | [private] |
push xml to factory, returns true if successful
Connect to the libgazebo server
Definition at line 425 of file gazebo_ros_factory.cpp.
bool GazeboRosFactory::spawnModel | ( | gazebo_plugins::SpawnModel::Request & | req, | |
gazebo_plugins::SpawnModel::Response & | res | |||
) | [private] |
ros service call to spawn model via factory
STRIP DECLARATION <? ... xml version="1.0" ... ?> from robot_model
Definition at line 157 of file gazebo_ros_factory.cpp.
void GazeboRosFactory::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 553 of file gazebo_ros_factory.cpp.
boost::thread gazebo::GazeboRosFactory::callback_queue_thread_ [private] |
Definition at line 163 of file gazebo_ros_factory.h.
ros::ServiceServer gazebo::GazeboRosFactory::deleteModelService [private] |
Definition at line 138 of file gazebo_ros_factory.h.
std::string gazebo::GazeboRosFactory::deleteModelServiceName [private] |
Definition at line 128 of file gazebo_ros_factory.h.
ParamT<std::string>* gazebo::GazeboRosFactory::deleteModelServiceNameP [private] |
Definition at line 127 of file gazebo_ros_factory.h.
ros::CallbackQueue gazebo::GazeboRosFactory::factory_queue_ [private] |
use custom callback queue
Definition at line 161 of file gazebo_ros_factory.h.
gazebo::Model* gazebo::GazeboRosFactory::myParent [private] |
controller parent, a model?
Definition at line 122 of file gazebo_ros_factory.h.
std::string gazebo::GazeboRosFactory::robotNamespace [private] |
Definition at line 132 of file gazebo_ros_factory.h.
ParamT<std::string>* gazebo::GazeboRosFactory::robotNamespaceP [private] |
for setting ROS name space
Definition at line 131 of file gazebo_ros_factory.h.
ros::NodeHandle* gazebo::GazeboRosFactory::rosnode_ [private] |
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 135 of file gazebo_ros_factory.h.
ros::ServiceServer gazebo::GazeboRosFactory::spawnModelService [private] |
ros service
Definition at line 137 of file gazebo_ros_factory.h.
std::string gazebo::GazeboRosFactory::spawnModelServiceName [private] |
Definition at line 126 of file gazebo_ros_factory.h.
ParamT<std::string>* gazebo::GazeboRosFactory::spawnModelServiceNameP [private] |
Service Call Name.
Definition at line 125 of file gazebo_ros_factory.h.