Classes | Public Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboRosApiPlugin Class Reference

A plugin loaded within the gzserver on startup. More...

#include <gazebo_ros_api_plugin.h>

List of all members.

Classes

class  ForceJointJob
class  WrenchBodyJob

Public Member Functions

void advertiseServices ()
 advertise services
bool applyBodyWrench (gazebo_msgs::ApplyBodyWrench::Request &req, gazebo_msgs::ApplyBodyWrench::Response &res)
bool applyJointEffort (gazebo_msgs::ApplyJointEffort::Request &req, gazebo_msgs::ApplyJointEffort::Response &res)
bool clearBodyWrenches (gazebo_msgs::BodyRequest::Request &req, gazebo_msgs::BodyRequest::Response &res)
bool clearBodyWrenches (std::string body_name)
bool clearJointForces (gazebo_msgs::JointRequest::Request &req, gazebo_msgs::JointRequest::Response &res)
bool clearJointForces (std::string joint_name)
bool deleteModel (gazebo_msgs::DeleteModel::Request &req, gazebo_msgs::DeleteModel::Response &res)
 delete model given name
void gazeboQueueThread ()
 ros queue thread for this node
 GazeboRosApiPlugin ()
 Constructor.
bool getJointProperties (gazebo_msgs::GetJointProperties::Request &req, gazebo_msgs::GetJointProperties::Response &res)
bool getLinkProperties (gazebo_msgs::GetLinkProperties::Request &req, gazebo_msgs::GetLinkProperties::Response &res)
bool getLinkState (gazebo_msgs::GetLinkState::Request &req, gazebo_msgs::GetLinkState::Response &res)
bool getModelProperties (gazebo_msgs::GetModelProperties::Request &req, gazebo_msgs::GetModelProperties::Response &res)
bool getModelState (gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)
bool getPhysicsProperties (gazebo_msgs::GetPhysicsProperties::Request &req, gazebo_msgs::GetPhysicsProperties::Response &res)
bool getWorldProperties (gazebo_msgs::GetWorldProperties::Request &req, gazebo_msgs::GetWorldProperties::Response &res)
void Load (int argc, char **argv)
 Gazebo-inherited load function.
void onLinkStatesConnect ()
void onLinkStatesDisconnect ()
void onModelStatesConnect ()
void onModelStatesDisconnect ()
bool pausePhysics (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool resetSimulation (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool resetWorld (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool setJointProperties (gazebo_msgs::SetJointProperties::Request &req, gazebo_msgs::SetJointProperties::Response &res)
bool setLinkProperties (gazebo_msgs::SetLinkProperties::Request &req, gazebo_msgs::SetLinkProperties::Response &res)
bool setLinkState (gazebo_msgs::SetLinkState::Request &req, gazebo_msgs::SetLinkState::Response &res)
bool setModelConfiguration (gazebo_msgs::SetModelConfiguration::Request &req, gazebo_msgs::SetModelConfiguration::Response &res)
bool setModelState (gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
bool setPhysicsProperties (gazebo_msgs::SetPhysicsProperties::Request &req, gazebo_msgs::SetPhysicsProperties::Response &res)
void shutdownSignal ()
 Detect if sig-int shutdown signal is recieved
ROS_DEPRECATED bool spawnGazeboModel (gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
 Function for inserting a URDF into Gazebo from ROS Service Call. Deprecated in ROS Hydro - replace with spawnURDFModel()
bool spawnSDFModel (gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
 Both SDFs and converted URDFs get sent to this function for further manipulation from a ROS Service call.
bool spawnURDFModel (gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
 Function for inserting a URDF into Gazebo from ROS Service Call.
bool unpausePhysics (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void updateLinkState (const gazebo_msgs::LinkState::ConstPtr &link_state)
void updateModelState (const gazebo_msgs::ModelState::ConstPtr &model_state)
 ~GazeboRosApiPlugin ()
 Destructor.

Private Member Functions

void forceJointSchedulerSlot ()
bool isSDF (std::string model_xml)
 utility for checking if string is in SDF format
bool isURDF (std::string model_xml)
 utility for checking if string is in URDF format
void loadGazeboRosApiPlugin (std::string world_name)
 Connect to Gazebo via its plugin interface, get a pointer to the world, start events.
void onResponse (ConstResponsePtr &response)
 Unused.
gazebo::math::Pose parsePose (const std::string &str)
 convert xml to Pose
gazebo::math::Vector3 parseVector3 (const std::string &str)
 convert xml to Pose
void physicsReconfigureCallback (gazebo_ros::PhysicsConfig &config, uint32_t level)
 Used for the dynamic reconfigure callback function template.
void physicsReconfigureThread ()
 waits for the rest of Gazebo to be ready before initializing the dynamic reconfigure services
void publishLinkStates ()
void publishModelStates ()
void publishSimTime (const boost::shared_ptr< gazebo::msgs::WorldStatistics const > &msg)
void publishSimTime ()
bool spawnAndConform (TiXmlDocument &gazebo_model_xml, std::string model_name, gazebo_msgs::SpawnModel::Response &res)
void stripXmlDeclaration (std::string &model_xml)
void transformWrench (gazebo::math::Vector3 &target_force, gazebo::math::Vector3 &target_torque, gazebo::math::Vector3 reference_force, gazebo::math::Vector3 reference_torque, gazebo::math::Pose target_to_reference)
 helper function for applyBodyWrench shift wrench from reference frame to target frame
void updateSDFAttributes (TiXmlDocument &gazebo_model_xml, std::string model_name, gazebo::math::Vector3 initial_xyz, gazebo::math::Quaternion initial_q)
 Update the model name and pose of the SDF file before sending to Gazebo.
void updateURDFModelPose (TiXmlDocument &gazebo_model_xml, gazebo::math::Vector3 initial_xyz, gazebo::math::Quaternion initial_q)
 Update the model pose of the URDF file before sending to Gazebo.
void updateURDFName (TiXmlDocument &gazebo_model_xml, std::string model_name)
 Update the model name of the URDF file before sending to Gazebo.
void walkChildAddRobotNamespace (TiXmlNode *robot_xml)
void wrenchBodySchedulerSlot ()

Private Attributes

ros::ServiceServer apply_body_wrench_service_
ros::ServiceServer apply_joint_effort_service_
boost::shared_ptr
< ros::AsyncSpinner
async_ros_spin_
ros::ServiceServer clear_body_wrenches_service_
ros::ServiceServer clear_joint_forces_service_
ros::ServiceServer delete_model_service_
gazebo::transport::PublisherPtr factory_pub_
std::vector
< GazeboRosApiPlugin::ForceJointJob * > 
force_joint_jobs_
gazebo::event::ConnectionPtr force_update_event_
boost::shared_ptr< boost::thread > gazebo_callback_queue_thread_
ros::CallbackQueue gazebo_queue_
gazebo::transport::NodePtr gazebonode_
ros::ServiceServer get_joint_properties_service_
ros::ServiceServer get_link_properties_service_
ros::ServiceServer get_link_state_service_
ros::ServiceServer get_model_properties_service_
ros::ServiceServer get_model_state_service_
ros::ServiceServer get_physics_properties_service_
ros::ServiceServer get_world_properties_service_
gazebo::event::ConnectionPtr load_gazebo_ros_api_plugin_event_
boost::mutex lock_
 A mutex to lock access to fields that are used in ROS message callbacks.
boost::shared_ptr
< ros::NodeHandle
nh_
ros::ServiceServer pause_physics_service_
dynamic_reconfigure::Server
< gazebo_ros::PhysicsConfig >
::CallbackType 
physics_reconfigure_callback_
ros::ServiceClient physics_reconfigure_get_client_
bool physics_reconfigure_initialized_
ros::ServiceClient physics_reconfigure_set_client_
boost::shared_ptr
< dynamic_reconfigure::Server
< gazebo_ros::PhysicsConfig > > 
physics_reconfigure_srv_
boost::shared_ptr< boost::thread > physics_reconfigure_thread_
bool plugin_loaded_
ros::Publisher pub_clock_
ros::Publisher pub_link_states_
int pub_link_states_connection_count_
gazebo::event::ConnectionPtr pub_link_states_event_
ros::Publisher pub_model_states_
int pub_model_states_connection_count_
gazebo::event::ConnectionPtr pub_model_states_event_
gazebo::transport::PublisherPtr request_pub_
ros::ServiceServer reset_simulation_service_
ros::ServiceServer reset_world_service_
gazebo::transport::SubscriberPtr response_sub_
std::string robot_namespace_
ros::ServiceServer set_joint_properties_service_
ros::ServiceServer set_link_properties_service_
ros::ServiceServer set_link_state_service_
ros::Subscriber set_link_state_topic_
ros::ServiceServer set_model_configuration_service_
ros::ServiceServer set_model_state_service_
ros::Subscriber set_model_state_topic_
ros::ServiceServer set_physics_properties_service_
gazebo::event::ConnectionPtr sigint_event_
ros::ServiceServer spawn_gazebo_model_service_
ros::ServiceServer spawn_sdf_model_service_
ros::ServiceServer spawn_urdf_model_service_
gazebo::transport::SubscriberPtr stat_sub_
bool stop_
gazebo::event::ConnectionPtr time_update_event_
ros::ServiceServer unpause_physics_service_
gazebo::physics::WorldPtr world_
bool world_created_
std::vector
< GazeboRosApiPlugin::WrenchBodyJob * > 
wrench_body_jobs_
gazebo::event::ConnectionPtr wrench_update_event_

Detailed Description

A plugin loaded within the gzserver on startup.

Definition at line 103 of file gazebo_ros_api_plugin.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 30 of file gazebo_ros_api_plugin.cpp.

Destructor.

Definition at line 41 of file gazebo_ros_api_plugin.cpp.


Member Function Documentation

advertise services

Definition at line 215 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::applyBodyWrench ( gazebo_msgs::ApplyBodyWrench::Request &  req,
gazebo_msgs::ApplyBodyWrench::Response &  res 
)

shift wrench to body frame if a non-zero reference point is given

Todo:
: to be more general, should we make the reference point a reference pose?
Todo:
: FIXME map is really wrong, need to use tf here somehow

Definition at line 1582 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::applyJointEffort ( gazebo_msgs::ApplyJointEffort::Request &  req,
gazebo_msgs::ApplyJointEffort::Response &  res 
)

Definition at line 1338 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::clearBodyWrenches ( gazebo_msgs::BodyRequest::Request &  req,
gazebo_msgs::BodyRequest::Response &  res 
)

Definition at line 1421 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::clearBodyWrenches ( std::string  body_name)

Definition at line 1426 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::clearJointForces ( gazebo_msgs::JointRequest::Request &  req,
gazebo_msgs::JointRequest::Response &  res 
)

Definition at line 1393 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::clearJointForces ( std::string  joint_name)

Definition at line 1398 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::deleteModel ( gazebo_msgs::DeleteModel::Request &  req,
gazebo_msgs::DeleteModel::Response &  res 
)

delete model given name

Definition at line 704 of file gazebo_ros_api_plugin.cpp.

Definition at line 1750 of file gazebo_ros_api_plugin.cpp.

ros queue thread for this node

Definition at line 206 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getJointProperties ( gazebo_msgs::GetJointProperties::Request &  req,
gazebo_msgs::GetJointProperties::Response &  res 
)
Todo:
: FIXME

Definition at line 914 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getLinkProperties ( gazebo_msgs::GetLinkProperties::Request &  req,
gazebo_msgs::GetLinkProperties::Response &  res 
)
Todo:
: validate

Definition at line 950 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getLinkState ( gazebo_msgs::GetLinkState::Request &  req,
gazebo_msgs::GetLinkState::Response &  res 
)
Todo:
: FIXME map is really wrong, need to use tf here somehow

Definition at line 990 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getModelProperties ( gazebo_msgs::GetModelProperties::Request &  req,
gazebo_msgs::GetModelProperties::Response &  res 
)

Definition at line 838 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getModelState ( gazebo_msgs::GetModelState::Request &  req,
gazebo_msgs::GetModelState::Response &  res 
)
Todo:
: FIXME map is really wrong, need to use tf here somehow

Definition at line 765 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getPhysicsProperties ( gazebo_msgs::GetPhysicsProperties::Request &  req,
gazebo_msgs::GetPhysicsProperties::Response &  res 
)

: add support for simbody, dart and bullet physics properties.

Definition at line 1136 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getWorldProperties ( gazebo_msgs::GetWorldProperties::Request &  req,
gazebo_msgs::GetWorldProperties::Response &  res 
)

Definition at line 900 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::isSDF ( std::string  model_xml) [private]

utility for checking if string is in SDF format

Definition at line 1704 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::isURDF ( std::string  model_xml) [private]

utility for checking if string is in URDF format

Definition at line 1694 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::Load ( int  argc,
char **  argv 
)

Gazebo-inherited load function.

Called before Gazebo is loaded. Must not block. Capitalized per Gazebo cpp style guidelines

Parameters:
_argcNumber of command line arguments.
_argvArray of command line arguments.

setup custom callback queue

start a thread for the physics dynamic reconfigure node

Definition at line 112 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::loadGazeboRosApiPlugin ( std::string  world_name) [private]

Connect to Gazebo via its plugin interface, get a pointer to the world, start events.

advertise all services

Definition at line 158 of file gazebo_ros_api_plugin.cpp.

Definition at line 488 of file gazebo_ros_api_plugin.cpp.

Definition at line 502 of file gazebo_ros_api_plugin.cpp.

Definition at line 495 of file gazebo_ros_api_plugin.cpp.

Definition at line 513 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::onResponse ( ConstResponsePtr &  response) [private]

Unused.

Definition at line 201 of file gazebo_ros_api_plugin.cpp.

gazebo::math::Pose gazebo::GazeboRosApiPlugin::parsePose ( const std::string &  str) [private]

convert xml to Pose

Definition at line 2075 of file gazebo_ros_api_plugin.cpp.

gazebo::math::Vector3 gazebo::GazeboRosApiPlugin::parseVector3 ( const std::string &  str) [private]

convert xml to Pose

Definition at line 2108 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::pausePhysics ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 1381 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::physicsReconfigureCallback ( gazebo_ros::PhysicsConfig &  config,
uint32_t  level 
) [private]

Used for the dynamic reconfigure callback function template.

Definition at line 1878 of file gazebo_ros_api_plugin.cpp.

waits for the rest of Gazebo to be ready before initializing the dynamic reconfigure services

Definition at line 1951 of file gazebo_ros_api_plugin.cpp.

Definition at line 1798 of file gazebo_ros_api_plugin.cpp.

Definition at line 1843 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::publishSimTime ( const boost::shared_ptr< gazebo::msgs::WorldStatistics const > &  msg) [private]

Definition at line 1780 of file gazebo_ros_api_plugin.cpp.

Definition at line 1789 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::resetSimulation ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 1369 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::resetWorld ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 1375 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setJointProperties ( gazebo_msgs::SetJointProperties::Request &  req,
gazebo_msgs::SetJointProperties::Response &  res 
)
Todo:
: current settings only allows for setting of 1DOF joints (e.g. HingeJoint and SliderJoint) correctly.

Definition at line 1194 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setLinkProperties ( gazebo_msgs::SetLinkProperties::Request &  req,
gazebo_msgs::SetLinkProperties::Response &  res 
)

Definition at line 1056 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setLinkState ( gazebo_msgs::SetLinkState::Request &  req,
gazebo_msgs::SetLinkState::Response &  res 
)
Todo:
: FIXME map is really wrong, unless using tf here somehow

Definition at line 1494 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setModelConfiguration ( gazebo_msgs::SetModelConfiguration::Request &  req,
gazebo_msgs::SetModelConfiguration::Response &  res 
)

Definition at line 1450 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setModelState ( gazebo_msgs::SetModelState::Request &  req,
gazebo_msgs::SetModelState::Response &  res 
)
Todo:
: FIXME map is really wrong, need to use tf here somehow

Definition at line 1261 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setPhysicsProperties ( gazebo_msgs::SetPhysicsProperties::Request &  req,
gazebo_msgs::SetPhysicsProperties::Response &  res 
)

: add support for simbody, dart and bullet physics properties.

Definition at line 1082 of file gazebo_ros_api_plugin.cpp.

Detect if sig-int shutdown signal is recieved

Definition at line 106 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::spawnAndConform ( TiXmlDocument &  gazebo_model_xml,
std::string  model_name,
gazebo_msgs::SpawnModel::Response &  res 
) [private]

FIXME: should change publish to direct invocation World::LoadModel() and/or change the poll for Model existence to common::Events based check.

poll and wait, verify that the model is spawned within Hardcoded 10 seconds

Definition at line 2232 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::spawnGazeboModel ( gazebo_msgs::SpawnModel::Request &  req,
gazebo_msgs::SpawnModel::Response &  res 
)

Function for inserting a URDF into Gazebo from ROS Service Call. Deprecated in ROS Hydro - replace with spawnURDFModel()

Definition at line 592 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::spawnSDFModel ( gazebo_msgs::SpawnModel::Request &  req,
gazebo_msgs::SpawnModel::Response &  res 
)

Both SDFs and converted URDFs get sent to this function for further manipulation from a ROS Service call.

Todo:
: map is really wrong, need to use tf here somehow

Definition at line 599 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::spawnURDFModel ( gazebo_msgs::SpawnModel::Request &  req,
gazebo_msgs::SpawnModel::Response &  res 
)

Function for inserting a URDF into Gazebo from ROS Service Call.

STRIP DECLARATION <? ... xml version="1.0" ... ?> from model_xml

Todo:
: does tinyxml have functionality for this?
Todo:
: should gazebo take care of the declaration?

Definition at line 524 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::stripXmlDeclaration ( std::string &  model_xml) [private]

STRIP DECLARATION <? ... xml version="1.0" ... ?> from model_xml

Todo:
: does tinyxml have functionality for this?
Todo:
: should gazebo take care of the declaration?

Definition at line 1968 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::transformWrench ( gazebo::math::Vector3 target_force,
gazebo::math::Vector3 target_torque,
gazebo::math::Vector3  reference_force,
gazebo::math::Vector3  reference_torque,
gazebo::math::Pose  target_to_reference 
) [private]

helper function for applyBodyWrench shift wrench from reference frame to target frame

Definition at line 1569 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::unpausePhysics ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 1387 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateLinkState ( const gazebo_msgs::LinkState::ConstPtr &  link_state)

Definition at line 1561 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateModelState ( const gazebo_msgs::ModelState::ConstPtr &  model_state)

Definition at line 1330 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateSDFAttributes ( TiXmlDocument &  gazebo_model_xml,
std::string  model_name,
gazebo::math::Vector3  initial_xyz,
gazebo::math::Quaternion  initial_q 
) [private]

Update the model name and pose of the SDF file before sending to Gazebo.

Definition at line 1982 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateURDFModelPose ( TiXmlDocument &  gazebo_model_xml,
gazebo::math::Vector3  initial_xyz,
gazebo::math::Quaternion  initial_q 
) [private]

Update the model pose of the URDF file before sending to Gazebo.

Definition at line 2141 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateURDFName ( TiXmlDocument &  gazebo_model_xml,
std::string  model_name 
) [private]

Update the model name of the URDF file before sending to Gazebo.

Definition at line 2186 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::walkChildAddRobotNamespace ( TiXmlNode *  robot_xml) [private]

Definition at line 2204 of file gazebo_ros_api_plugin.cpp.

Definition at line 1716 of file gazebo_ros_api_plugin.cpp.


Member Data Documentation

Definition at line 333 of file gazebo_ros_api_plugin.h.

Definition at line 336 of file gazebo_ros_api_plugin.h.

Definition at line 353 of file gazebo_ros_api_plugin.h.

Definition at line 344 of file gazebo_ros_api_plugin.h.

Definition at line 343 of file gazebo_ros_api_plugin.h.

Definition at line 323 of file gazebo_ros_api_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboRosApiPlugin::factory_pub_ [private]

Definition at line 304 of file gazebo_ros_api_plugin.h.

Definition at line 390 of file gazebo_ros_api_plugin.h.

Definition at line 314 of file gazebo_ros_api_plugin.h.

boost::shared_ptr<boost::thread> gazebo::GazeboRosApiPlugin::gazebo_callback_queue_thread_ [private]

Definition at line 310 of file gazebo_ros_api_plugin.h.

Definition at line 309 of file gazebo_ros_api_plugin.h.

gazebo::transport::NodePtr gazebo::GazeboRosApiPlugin::gazebonode_ [private]

Definition at line 302 of file gazebo_ros_api_plugin.h.

Definition at line 327 of file gazebo_ros_api_plugin.h.

Definition at line 328 of file gazebo_ros_api_plugin.h.

Definition at line 329 of file gazebo_ros_api_plugin.h.

Definition at line 325 of file gazebo_ros_api_plugin.h.

Definition at line 324 of file gazebo_ros_api_plugin.h.

Definition at line 332 of file gazebo_ros_api_plugin.h.

Definition at line 326 of file gazebo_ros_api_plugin.h.

Definition at line 318 of file gazebo_ros_api_plugin.h.

boost::mutex gazebo::GazeboRosApiPlugin::lock_ [private]

A mutex to lock access to fields that are used in ROS message callbacks.

Definition at line 366 of file gazebo_ros_api_plugin.h.

boost::shared_ptr<ros::NodeHandle> gazebo::GazeboRosApiPlugin::nh_ [private]

Definition at line 308 of file gazebo_ros_api_plugin.h.

Definition at line 341 of file gazebo_ros_api_plugin.h.

dynamic_reconfigure::Server<gazebo_ros::PhysicsConfig>::CallbackType gazebo::GazeboRosApiPlugin::physics_reconfigure_callback_ [private]

Definition at line 361 of file gazebo_ros_api_plugin.h.

Definition at line 359 of file gazebo_ros_api_plugin.h.

Definition at line 357 of file gazebo_ros_api_plugin.h.

Definition at line 358 of file gazebo_ros_api_plugin.h.

boost::shared_ptr< dynamic_reconfigure::Server<gazebo_ros::PhysicsConfig> > gazebo::GazeboRosApiPlugin::physics_reconfigure_srv_ [private]

Definition at line 360 of file gazebo_ros_api_plugin.h.

boost::shared_ptr<boost::thread> gazebo::GazeboRosApiPlugin::physics_reconfigure_thread_ [private]

Definition at line 356 of file gazebo_ros_api_plugin.h.

Definition at line 294 of file gazebo_ros_api_plugin.h.

Definition at line 363 of file gazebo_ros_api_plugin.h.

Definition at line 347 of file gazebo_ros_api_plugin.h.

Definition at line 349 of file gazebo_ros_api_plugin.h.

Definition at line 316 of file gazebo_ros_api_plugin.h.

Definition at line 348 of file gazebo_ros_api_plugin.h.

Definition at line 350 of file gazebo_ros_api_plugin.h.

Definition at line 317 of file gazebo_ros_api_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboRosApiPlugin::request_pub_ [private]

Definition at line 305 of file gazebo_ros_api_plugin.h.

Definition at line 339 of file gazebo_ros_api_plugin.h.

Definition at line 340 of file gazebo_ros_api_plugin.h.

gazebo::transport::SubscriberPtr gazebo::GazeboRosApiPlugin::response_sub_ [private]

Definition at line 306 of file gazebo_ros_api_plugin.h.

Definition at line 300 of file gazebo_ros_api_plugin.h.

Definition at line 334 of file gazebo_ros_api_plugin.h.

Definition at line 330 of file gazebo_ros_api_plugin.h.

Definition at line 338 of file gazebo_ros_api_plugin.h.

Definition at line 345 of file gazebo_ros_api_plugin.h.

Definition at line 337 of file gazebo_ros_api_plugin.h.

Definition at line 335 of file gazebo_ros_api_plugin.h.

Definition at line 346 of file gazebo_ros_api_plugin.h.

Definition at line 331 of file gazebo_ros_api_plugin.h.

Definition at line 298 of file gazebo_ros_api_plugin.h.

Definition at line 320 of file gazebo_ros_api_plugin.h.

Definition at line 321 of file gazebo_ros_api_plugin.h.

Definition at line 322 of file gazebo_ros_api_plugin.h.

gazebo::transport::SubscriberPtr gazebo::GazeboRosApiPlugin::stat_sub_ [private]

Definition at line 303 of file gazebo_ros_api_plugin.h.

Definition at line 297 of file gazebo_ros_api_plugin.h.

Definition at line 315 of file gazebo_ros_api_plugin.h.

Definition at line 342 of file gazebo_ros_api_plugin.h.

gazebo::physics::WorldPtr gazebo::GazeboRosApiPlugin::world_ [private]

Definition at line 312 of file gazebo_ros_api_plugin.h.

Definition at line 368 of file gazebo_ros_api_plugin.h.

Definition at line 389 of file gazebo_ros_api_plugin.h.

Definition at line 313 of file gazebo_ros_api_plugin.h.


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


gazebo_ros
Author(s): John Hsu, Nate Koenig, Dave Coleman
autogenerated on Thu Jun 6 2019 18:41:03