Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosApiPlugin Class Reference

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

#include <gazebo_ros_api_plugin.h>

Inheritance diagram for gazebo::GazeboRosApiPlugin:
Inheritance graph
[legend]

Classes

class  ForceJointJob
 
class  WrenchBodyJob
 

Public Member Functions

void advertiseServices ()
 advertise services More...
 
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 deleteLight (gazebo_msgs::DeleteLight::Request &req, gazebo_msgs::DeleteLight::Response &res)
 delete a given light by name More...
 
bool deleteModel (gazebo_msgs::DeleteModel::Request &req, gazebo_msgs::DeleteModel::Response &res)
 delete model given name More...
 
void gazeboQueueThread ()
 ros queue thread for this node More...
 
 GazeboRosApiPlugin ()
 Constructor. More...
 
bool getJointProperties (gazebo_msgs::GetJointProperties::Request &req, gazebo_msgs::GetJointProperties::Response &res)
 
bool getLightProperties (gazebo_msgs::GetLightProperties::Request &req, gazebo_msgs::GetLightProperties::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. More...
 
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 setLightProperties (gazebo_msgs::SetLightProperties::Request &req, gazebo_msgs::SetLightProperties::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 More...
 
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. More...
 
bool spawnURDFModel (gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
 Function for inserting a URDF into Gazebo from ROS Service Call. More...
 
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. More...
 

Private Member Functions

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

Private Attributes

std::map< std::string, unsigned int > access_count_get_model_state_
 index counters to count the accesses on models via GetModelState More...
 
ros::ServiceServer apply_body_wrench_service_
 
ros::ServiceServer apply_joint_effort_service_
 
boost::shared_ptr< ros::AsyncSpinnerasync_ros_spin_
 
ros::ServiceServer clear_body_wrenches_service_
 
ros::ServiceServer clear_joint_forces_service_
 
ros::ServiceServer delete_light_service_
 
ros::ServiceServer delete_model_service_
 
bool enable_ros_network_
 enable the communication of gazebo information using ROS service/topics More...
 
gazebo::transport::PublisherPtr factory_light_pub_
 
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_light_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::common::Time last_pub_clock_time_
 
gazebo::transport::PublisherPtr light_modify_pub_
 
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. More...
 
boost::shared_ptr< ros::NodeHandlenh_
 
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_
 
int pub_clock_frequency_
 
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_light_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_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 107 of file gazebo_ros_api_plugin.h.

Constructor & Destructor Documentation

gazebo::GazeboRosApiPlugin::GazeboRosApiPlugin ( )

Constructor.

Definition at line 30 of file gazebo_ros_api_plugin.cpp.

gazebo::GazeboRosApiPlugin::~GazeboRosApiPlugin ( )

Destructor.

Definition at line 43 of file gazebo_ros_api_plugin.cpp.

Member Function Documentation

void gazebo::GazeboRosApiPlugin::advertiseServices ( )

advertise services

Definition at line 235 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 1868 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1599 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1693 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1698 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1665 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1670 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::deleteLight ( gazebo_msgs::DeleteLight::Request &  req,
gazebo_msgs::DeleteLight::Response &  res 
)

delete a given light by name

Definition at line 835 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 766 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::forceJointSchedulerSlot ( )
private

Definition at line 2062 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::gazeboQueueThread ( )

ros queue thread for this node

Definition at line 226 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 1075 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getLightProperties ( gazebo_msgs::GetLightProperties::Request &  req,
gazebo_msgs::GetLightProperties::Response &  res 
)

Definition at line 1259 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 1121 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 1179 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 989 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::getModelState ( gazebo_msgs::GetModelState::Request &  req,
gazebo_msgs::GetModelState::Response &  res 
)

creates a header for the result

Author
Markus Bader marku.nosp@m.s.ba.nosp@m.der@t.nosp@m.uwie.nosp@m.n.ac..nosp@m.at
Date
21th Nov 2014

this is a redundant information

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

Definition at line 880 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 1407 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1055 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 2011 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 2001 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 114 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 162 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::onLinkStatesConnect ( )

Definition at line 538 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::onLinkStatesDisconnect ( )

Definition at line 552 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::onModelStatesConnect ( )

Definition at line 545 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::onModelStatesDisconnect ( )

Definition at line 563 of file gazebo_ros_api_plugin.cpp.

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

Unused.

Definition at line 221 of file gazebo_ros_api_plugin.cpp.

ignition::math::Pose3d gazebo::GazeboRosApiPlugin::parsePose ( const std::string &  str)
private

convert xml to Pose

Definition at line 2437 of file gazebo_ros_api_plugin.cpp.

ignition::math::Vector3d gazebo::GazeboRosApiPlugin::parseVector3 ( const std::string &  str)
private

convert xml to Pose

Definition at line 2470 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1653 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 2238 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::physicsReconfigureThread ( )
private

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

Definition at line 2311 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::publishLinkStates ( )
private

Definition at line 2137 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::publishModelStates ( )
private

Definition at line 2194 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 2097 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::publishSimTime ( )
private

Definition at line 2115 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1641 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1647 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 1459 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::setLightProperties ( gazebo_msgs::SetLightProperties::Request &  req,
gazebo_msgs::SetLightProperties::Response &  res 
)

Definition at line 1293 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1330 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 1770 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1722 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 1511 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 1360 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::shutdownSignal ( )

Detect if sig-int shutdown signal is recieved

Definition at line 108 of file gazebo_ros_api_plugin.cpp.

bool gazebo::GazeboRosApiPlugin::spawnAndConform ( TiXmlDocument &  gazebo_model_xml,
const 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 2597 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 653 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 574 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 2328 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::transformWrench ( ignition::math::Vector3d &  target_force,
ignition::math::Vector3d &  target_torque,
const ignition::math::Vector3d &  reference_force,
const ignition::math::Vector3d &  reference_torque,
const ignition::math::Pose3d &  target_to_reference 
)
private

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

Definition at line 1854 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1659 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1846 of file gazebo_ros_api_plugin.cpp.

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

Definition at line 1591 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateSDFAttributes ( TiXmlDocument &  gazebo_model_xml,
const std::string &  model_name,
const ignition::math::Vector3d &  initial_xyz,
const ignition::math::Quaterniond &  initial_q 
)
private

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

Definition at line 2342 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::updateURDFModelPose ( TiXmlDocument &  gazebo_model_xml,
const ignition::math::Vector3d &  initial_xyz,
const ignition::math::Quaterniond &  initial_q 
)
private

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

Definition at line 2503 of file gazebo_ros_api_plugin.cpp.

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

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

Definition at line 2551 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::walkChildAddRobotNamespace ( TiXmlNode *  model_xml)
private

Definition at line 2569 of file gazebo_ros_api_plugin.cpp.

void gazebo::GazeboRosApiPlugin::wrenchBodySchedulerSlot ( )
private

Definition at line 2023 of file gazebo_ros_api_plugin.cpp.

Member Data Documentation

std::map<std::string, unsigned int> gazebo::GazeboRosApiPlugin::access_count_get_model_state_
private

index counters to count the accesses on models via GetModelState

Definition at line 415 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::apply_body_wrench_service_
private

Definition at line 353 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::apply_joint_effort_service_
private

Definition at line 356 of file gazebo_ros_api_plugin.h.

boost::shared_ptr<ros::AsyncSpinner> gazebo::GazeboRosApiPlugin::async_ros_spin_
private

Definition at line 373 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::clear_body_wrenches_service_
private

Definition at line 364 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::clear_joint_forces_service_
private

Definition at line 363 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::delete_light_service_
private

Definition at line 341 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::delete_model_service_
private

Definition at line 340 of file gazebo_ros_api_plugin.h.

bool gazebo::GazeboRosApiPlugin::enable_ros_network_
private

enable the communication of gazebo information using ROS service/topics

Definition at line 418 of file gazebo_ros_api_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboRosApiPlugin::factory_light_pub_
private

Definition at line 321 of file gazebo_ros_api_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboRosApiPlugin::factory_pub_
private

Definition at line 320 of file gazebo_ros_api_plugin.h.

std::vector<GazeboRosApiPlugin::ForceJointJob*> gazebo::GazeboRosApiPlugin::force_joint_jobs_
private

Definition at line 412 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::force_update_event_
private

Definition at line 332 of file gazebo_ros_api_plugin.h.

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

Definition at line 328 of file gazebo_ros_api_plugin.h.

ros::CallbackQueue gazebo::GazeboRosApiPlugin::gazebo_queue_
private

Definition at line 327 of file gazebo_ros_api_plugin.h.

gazebo::transport::NodePtr gazebo::GazeboRosApiPlugin::gazebonode_
private

Definition at line 318 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_joint_properties_service_
private

Definition at line 345 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_light_properties_service_
private

Definition at line 348 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_link_properties_service_
private

Definition at line 346 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_link_state_service_
private

Definition at line 347 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_model_properties_service_
private

Definition at line 343 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_model_state_service_
private

Definition at line 342 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_physics_properties_service_
private

Definition at line 352 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::get_world_properties_service_
private

Definition at line 344 of file gazebo_ros_api_plugin.h.

gazebo::common::Time gazebo::GazeboRosApiPlugin::last_pub_clock_time_
private

Definition at line 385 of file gazebo_ros_api_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboRosApiPlugin::light_modify_pub_
private

Definition at line 322 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::load_gazebo_ros_api_plugin_event_
private

Definition at line 336 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 388 of file gazebo_ros_api_plugin.h.

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

Definition at line 326 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::pause_physics_service_
private

Definition at line 361 of file gazebo_ros_api_plugin.h.

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

Definition at line 381 of file gazebo_ros_api_plugin.h.

ros::ServiceClient gazebo::GazeboRosApiPlugin::physics_reconfigure_get_client_
private

Definition at line 379 of file gazebo_ros_api_plugin.h.

bool gazebo::GazeboRosApiPlugin::physics_reconfigure_initialized_
private

Definition at line 377 of file gazebo_ros_api_plugin.h.

ros::ServiceClient gazebo::GazeboRosApiPlugin::physics_reconfigure_set_client_
private

Definition at line 378 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 380 of file gazebo_ros_api_plugin.h.

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

Definition at line 376 of file gazebo_ros_api_plugin.h.

bool gazebo::GazeboRosApiPlugin::plugin_loaded_
private

Definition at line 310 of file gazebo_ros_api_plugin.h.

ros::Publisher gazebo::GazeboRosApiPlugin::pub_clock_
private

Definition at line 383 of file gazebo_ros_api_plugin.h.

int gazebo::GazeboRosApiPlugin::pub_clock_frequency_
private

Definition at line 384 of file gazebo_ros_api_plugin.h.

ros::Publisher gazebo::GazeboRosApiPlugin::pub_link_states_
private

Definition at line 367 of file gazebo_ros_api_plugin.h.

int gazebo::GazeboRosApiPlugin::pub_link_states_connection_count_
private

Definition at line 369 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::pub_link_states_event_
private

Definition at line 334 of file gazebo_ros_api_plugin.h.

ros::Publisher gazebo::GazeboRosApiPlugin::pub_model_states_
private

Definition at line 368 of file gazebo_ros_api_plugin.h.

int gazebo::GazeboRosApiPlugin::pub_model_states_connection_count_
private

Definition at line 370 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::pub_model_states_event_
private

Definition at line 335 of file gazebo_ros_api_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboRosApiPlugin::request_pub_
private

Definition at line 323 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::reset_simulation_service_
private

Definition at line 359 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::reset_world_service_
private

Definition at line 360 of file gazebo_ros_api_plugin.h.

gazebo::transport::SubscriberPtr gazebo::GazeboRosApiPlugin::response_sub_
private

Definition at line 324 of file gazebo_ros_api_plugin.h.

std::string gazebo::GazeboRosApiPlugin::robot_namespace_
private

Definition at line 316 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_joint_properties_service_
private

Definition at line 354 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_light_properties_service_
private

Definition at line 349 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_link_properties_service_
private

Definition at line 350 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_link_state_service_
private

Definition at line 358 of file gazebo_ros_api_plugin.h.

ros::Subscriber gazebo::GazeboRosApiPlugin::set_link_state_topic_
private

Definition at line 365 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_model_configuration_service_
private

Definition at line 357 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_model_state_service_
private

Definition at line 355 of file gazebo_ros_api_plugin.h.

ros::Subscriber gazebo::GazeboRosApiPlugin::set_model_state_topic_
private

Definition at line 366 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::set_physics_properties_service_
private

Definition at line 351 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::sigint_event_
private

Definition at line 314 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::spawn_sdf_model_service_
private

Definition at line 338 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::spawn_urdf_model_service_
private

Definition at line 339 of file gazebo_ros_api_plugin.h.

gazebo::transport::SubscriberPtr gazebo::GazeboRosApiPlugin::stat_sub_
private

Definition at line 319 of file gazebo_ros_api_plugin.h.

bool gazebo::GazeboRosApiPlugin::stop_
private

Definition at line 313 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::time_update_event_
private

Definition at line 333 of file gazebo_ros_api_plugin.h.

ros::ServiceServer gazebo::GazeboRosApiPlugin::unpause_physics_service_
private

Definition at line 362 of file gazebo_ros_api_plugin.h.

gazebo::physics::WorldPtr gazebo::GazeboRosApiPlugin::world_
private

Definition at line 330 of file gazebo_ros_api_plugin.h.

bool gazebo::GazeboRosApiPlugin::world_created_
private

Definition at line 390 of file gazebo_ros_api_plugin.h.

std::vector<GazeboRosApiPlugin::WrenchBodyJob*> gazebo::GazeboRosApiPlugin::wrench_body_jobs_
private

Definition at line 411 of file gazebo_ros_api_plugin.h.

gazebo::event::ConnectionPtr gazebo::GazeboRosApiPlugin::wrench_update_event_
private

Definition at line 331 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 Tue Mar 26 2019 02:31:35