23 #ifndef __GAZEBO_ROS_API_PLUGIN_HH__ 24 #define __GAZEBO_ROS_API_PLUGIN_HH__ 34 #include <gazebo/physics/physics.hh> 35 #include <gazebo/common/common.hh> 36 #include <gazebo/transport/transport.hh> 43 #include <rosgraph_msgs/Clock.h> 46 #include "std_srvs/Empty.h" 48 #include "gazebo_msgs/JointRequest.h" 49 #include "gazebo_msgs/BodyRequest.h" 51 #include "gazebo_msgs/SpawnModel.h" 52 #include "gazebo_msgs/DeleteModel.h" 53 #include "gazebo_msgs/DeleteLight.h" 55 #include "gazebo_msgs/ApplyBodyWrench.h" 57 #include "gazebo_msgs/SetPhysicsProperties.h" 58 #include "gazebo_msgs/GetPhysicsProperties.h" 60 #include "gazebo_msgs/SetJointProperties.h" 62 #include "gazebo_msgs/GetWorldProperties.h" 64 #include "gazebo_msgs/GetModelProperties.h" 65 #include "gazebo_msgs/GetModelState.h" 66 #include "gazebo_msgs/SetModelState.h" 68 #include "gazebo_msgs/GetJointProperties.h" 69 #include "gazebo_msgs/ApplyJointEffort.h" 71 #include "gazebo_msgs/GetLinkProperties.h" 72 #include "gazebo_msgs/SetLinkProperties.h" 73 #include "gazebo_msgs/SetLinkState.h" 74 #include "gazebo_msgs/GetLinkState.h" 76 #include "gazebo_msgs/GetLightProperties.h" 77 #include "gazebo_msgs/SetLightProperties.h" 80 #include "gazebo_msgs/ModelState.h" 81 #include "gazebo_msgs/LinkState.h" 82 #include "gazebo_msgs/ModelStates.h" 83 #include "gazebo_msgs/LinkStates.h" 84 #include "gazebo_msgs/PerformanceMetrics.h" 86 #include "geometry_msgs/Vector3.h" 87 #include "geometry_msgs/Wrench.h" 88 #include "geometry_msgs/Pose.h" 89 #include "geometry_msgs/Twist.h" 93 #include <gazebo_msgs/SetModelConfiguration.h> 94 #include <boost/shared_ptr.hpp> 97 #include <dynamic_reconfigure/server.h> 98 #include <gazebo_ros/PhysicsConfig.h> 99 #include "gazebo_msgs/SetPhysicsProperties.h" 100 #include "gazebo_msgs/GetPhysicsProperties.h" 102 #include <boost/algorithm/string.hpp> 104 #ifndef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 105 #if (GAZEBO_MAJOR_VERSION == 11 && GAZEBO_MINOR_VERSION > 1) || \ 106 (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 14) 107 #define GAZEBO_ROS_HAS_PERFORMANCE_METRICS 109 #endif // ifndef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 133 void Load(
int argc,
char** argv);
153 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 154 void onPerformanceMetricsConnect();
158 void onPerformanceMetricsDisconnect();
163 gazebo_msgs::SpawnModel::Response &res);
167 gazebo_msgs::SpawnModel::Response &res);
170 bool deleteModel(gazebo_msgs::DeleteModel::Request &req,gazebo_msgs::DeleteModel::Response &res);
173 bool deleteLight(gazebo_msgs::DeleteLight::Request &req,gazebo_msgs::DeleteLight::Response &res);
176 bool getModelState(gazebo_msgs::GetModelState::Request &req,gazebo_msgs::GetModelState::Response &res);
179 bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req,gazebo_msgs::GetModelProperties::Response &res);
182 bool getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,gazebo_msgs::GetWorldProperties::Response &res);
185 bool getJointProperties(gazebo_msgs::GetJointProperties::Request &req,gazebo_msgs::GetJointProperties::Response &res);
188 bool getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,gazebo_msgs::GetLinkProperties::Response &res);
191 bool getLinkState(gazebo_msgs::GetLinkState::Request &req,gazebo_msgs::GetLinkState::Response &res);
194 bool getLightProperties(gazebo_msgs::GetLightProperties::Request &req,gazebo_msgs::GetLightProperties::Response &res);
197 bool setLightProperties(gazebo_msgs::SetLightProperties::Request &req,gazebo_msgs::SetLightProperties::Response &res);
200 bool setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req,gazebo_msgs::SetLinkProperties::Response &res);
203 bool setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req,gazebo_msgs::SetPhysicsProperties::Response &res);
206 bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req,gazebo_msgs::GetPhysicsProperties::Response &res);
209 bool setJointProperties(gazebo_msgs::SetJointProperties::Request &req,gazebo_msgs::SetJointProperties::Response &res);
212 bool setModelState(gazebo_msgs::SetModelState::Request &req,gazebo_msgs::SetModelState::Response &res);
215 void updateModelState(
const gazebo_msgs::ModelState::ConstPtr& model_state);
218 bool applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req,gazebo_msgs::ApplyJointEffort::Response &res);
221 bool resetSimulation(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
224 bool resetWorld(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
227 bool pausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
230 bool unpausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
233 bool clearJointForces(gazebo_msgs::JointRequest::Request &req,gazebo_msgs::JointRequest::Response &res);
237 bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req,gazebo_msgs::BodyRequest::Response &res);
241 bool setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req,gazebo_msgs::SetModelConfiguration::Response &res);
244 bool setLinkState(gazebo_msgs::SetLinkState::Request &req,gazebo_msgs::SetLinkState::Response &res);
247 void updateLinkState(
const gazebo_msgs::LinkState::ConstPtr& link_state);
250 bool applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req,gazebo_msgs::ApplyBodyWrench::Response &res);
276 const std::string &model_name,
277 const ignition::math::Vector3d &initial_xyz,
278 const ignition::math::Quaterniond &initial_q);
282 const ignition::math::Vector3d &initial_xyz,
283 const ignition::math::Quaterniond &initial_q);
286 void updateURDFName(TiXmlDocument &gazebo_model_xml,
const std::string &model_name);
292 bool spawnAndConform(TiXmlDocument &gazebo_model_xml,
const std::string &model_name,
293 gazebo_msgs::SpawnModel::Response &res);
297 void transformWrench(ignition::math::Vector3d &target_force, ignition::math::Vector3d &target_torque,
298 const ignition::math::Vector3d &reference_force,
299 const ignition::math::Vector3d &reference_torque,
300 const ignition::math::Pose3d &target_to_reference );
311 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 315 bool isURDF(std::string model_xml);
319 bool isSDF(std::string model_xml);
325 ignition::math::Pose3d
parsePose(
const std::string &str);
328 ignition::math::Vector3d
parseVector3(
const std::string &str);
bool getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req, gazebo_msgs::GetLinkProperties::Response &res)
void shutdownSignal()
Detect if sig-int shutdown signal is recieved
ros::ServiceServer reset_simulation_service_
ignition::math::Vector3d torque
bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req, gazebo_msgs::GetPhysicsProperties::Response &res)
gazebo::physics::LinkPtr body
ros::ServiceServer apply_body_wrench_service_
bool setJointProperties(gazebo_msgs::SetJointProperties::Request &req, gazebo_msgs::SetJointProperties::Response &res)
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.
bool setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req, gazebo_msgs::SetPhysicsProperties::Response &res)
gazebo::event::ConnectionPtr time_update_event_
bool setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req, gazebo_msgs::SetModelConfiguration::Response &res)
bool getModelState(gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)
ros::ServiceServer set_physics_properties_service_
void onLinkStatesDisconnect()
Callback for a subscriber disconnecting from LinkStates ros topic.
ros::Publisher pub_performance_metrics_
ros::ServiceServer get_model_properties_service_
ros::ServiceServer unpause_physics_service_
void forceJointSchedulerSlot()
bool setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req, gazebo_msgs::SetLinkProperties::Response &res)
boost::shared_ptr< dynamic_reconfigure::Server< gazebo_ros::PhysicsConfig > > physics_reconfigure_srv_
void loadGazeboRosApiPlugin(std::string world_name)
Connect to Gazebo via its plugin interface, get a pointer to the world, start events.
gazebo::common::Time last_pub_clock_time_
ros::ServiceServer spawn_urdf_model_service_
ros::ServiceServer get_light_properties_service_
dynamic_reconfigure::Server< gazebo_ros::PhysicsConfig >::CallbackType physics_reconfigure_callback_
bool isURDF(std::string model_xml)
utility for checking if string is in URDF format
boost::shared_ptr< ros::NodeHandle > nh_
void onLinkStatesConnect()
Callback for a subscriber connecting to LinkStates ros topic.
void wrenchBodySchedulerSlot()
boost::shared_ptr< boost::thread > physics_reconfigure_thread_
void physicsReconfigureThread()
waits for the rest of Gazebo to be ready before initializing the dynamic reconfigure services ...
bool setLinkState(gazebo_msgs::SetLinkState::Request &req, gazebo_msgs::SetLinkState::Response &res)
gazebo::transport::PublisherPtr request_pub_
ros::ServiceServer clear_body_wrenches_service_
ros::Subscriber set_link_state_topic_
ignition::math::Pose3d parsePose(const std::string &str)
convert xml to Pose
gazebo::transport::SubscriberPtr stat_sub_
void onModelStatesConnect()
Callback for a subscriber connecting to ModelStates ros topic.
ros::ServiceServer get_link_properties_service_
ros::ServiceServer set_model_configuration_service_
void advertiseServices()
advertise services
gazebo::physics::WorldPtr world_
int pub_model_states_connection_count_
ros::ServiceClient physics_reconfigure_set_client_
ros::ServiceServer delete_light_service_
bool resetSimulation(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer delete_model_service_
bool unpausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer apply_joint_effort_service_
ros::ServiceServer clear_joint_forces_service_
std::vector< GazeboRosApiPlugin::ForceJointJob * > force_joint_jobs_
std::map< std::string, unsigned int > access_count_get_model_state_
index counters to count the accesses on models via GetModelState
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
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 ...
ros::ServiceServer set_model_state_service_
ros::ServiceClient physics_reconfigure_get_client_
ros::ServiceServer reset_world_service_
gazebo::physics::JointPtr joint
bool applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req, gazebo_msgs::ApplyJointEffort::Response &res)
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.
bool getJointProperties(gazebo_msgs::GetJointProperties::Request &req, gazebo_msgs::GetJointProperties::Response &res)
ros::ServiceServer get_joint_properties_service_
bool getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req, gazebo_msgs::GetWorldProperties::Response &res)
void updateModelState(const gazebo_msgs::ModelState::ConstPtr &model_state)
void publishModelStates()
gazebo::event::ConnectionPtr sigint_event_
ros::Publisher pub_clock_
gazebo::event::ConnectionPtr pub_model_states_event_
bool deleteLight(gazebo_msgs::DeleteLight::Request &req, gazebo_msgs::DeleteLight::Response &res)
delete a given light by name
gazebo::event::ConnectionPtr wrench_update_event_
void Load(int argc, char **argv)
Gazebo-inherited load function.
gazebo::transport::PublisherPtr factory_light_pub_
void publishSimTime()
Callback to WorldUpdateBegin that publishes /clock. If pub_clock_frequency_ <= 0 (default behavior)...
bool pausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer set_link_properties_service_
ros::ServiceServer set_light_properties_service_
int pub_link_states_connection_count_
bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req, gazebo_msgs::BodyRequest::Response &res)
gazebo::transport::SubscriberPtr response_sub_
int pub_performance_metrics_connection_count_
GazeboRosApiPlugin()
Constructor.
bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req, gazebo_msgs::GetModelProperties::Response &res)
boost::shared_ptr< boost::thread > gazebo_callback_queue_thread_
ros::CallbackQueue gazebo_queue_
gazebo::event::ConnectionPtr force_update_event_
bool spawnURDFModel(gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
Function for inserting a URDF into Gazebo from ROS Service Call.
void walkChildAddRobotNamespace(TiXmlNode *model_xml)
std::string robot_namespace_
bool resetWorld(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool isSDF(std::string model_xml)
utility for checking if string is in SDF format
gazebo::transport::SubscriberPtr performance_metric_sub_
boost::shared_ptr< ros::AsyncSpinner > async_ros_spin_
A plugin loaded within the gzserver on startup.
bool applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req, gazebo_msgs::ApplyBodyWrench::Response &res)
ros::ServiceServer get_model_state_service_
void onModelStatesDisconnect()
Callback for a subscriber disconnecting from ModelStates ros topic.
void physicsReconfigureCallback(gazebo_ros::PhysicsConfig &config, uint32_t level)
Used for the dynamic reconfigure callback function template.
bool clearJointForces(gazebo_msgs::JointRequest::Request &req, gazebo_msgs::JointRequest::Response &res)
ros::ServiceServer set_joint_properties_service_
gazebo::transport::PublisherPtr factory_pub_
gazebo::event::ConnectionPtr load_gazebo_ros_api_plugin_event_
bool spawnAndConform(TiXmlDocument &gazebo_model_xml, const std::string &model_name, gazebo_msgs::SpawnModel::Response &res)
ros::ServiceServer spawn_sdf_model_service_
ignition::math::Vector3d parseVector3(const std::string &str)
convert xml to Pose
bool getLightProperties(gazebo_msgs::GetLightProperties::Request &req, gazebo_msgs::GetLightProperties::Response &res)
ros::ServiceServer get_world_properties_service_
ros::ServiceServer set_link_state_service_
std::vector< GazeboRosApiPlugin::WrenchBodyJob * > wrench_body_jobs_
gazebo::event::ConnectionPtr pub_link_states_event_
ros::ServiceServer get_link_state_service_
void updateLinkState(const gazebo_msgs::LinkState::ConstPtr &link_state)
gazebo::transport::NodePtr gazebonode_
void gazeboQueueThread()
ros queue thread for this node
bool setLightProperties(gazebo_msgs::SetLightProperties::Request &req, gazebo_msgs::SetLightProperties::Response &res)
bool deleteModel(gazebo_msgs::DeleteModel::Request &req, gazebo_msgs::DeleteModel::Response &res)
delete model given name
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 c...
ros::Publisher pub_link_states_
ros::Subscriber set_model_state_topic_
void onResponse(ConstResponsePtr &response)
Unused.
void stripXmlDeclaration(std::string &model_xml)
ros::ServiceServer pause_physics_service_
bool getLinkState(gazebo_msgs::GetLinkState::Request &req, gazebo_msgs::GetLinkState::Response &res)
void updateURDFName(TiXmlDocument &gazebo_model_xml, const std::string &model_name)
Update the model name of the URDF file before sending to Gazebo.
bool enable_ros_network_
enable the communication of gazebo information using ROS service/topics
~GazeboRosApiPlugin()
Destructor.
ros::ServiceServer get_physics_properties_service_
const std::string response
ros::Publisher pub_model_states_
ignition::math::Vector3d force
bool setModelState(gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
gazebo::transport::PublisherPtr light_modify_pub_
bool physics_reconfigure_initialized_