gazebo_ros_api_plugin.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 /*
18  * Desc: External interfaces for Gazebo
19  * Author: Nate Koenig, John Hsu, Dave Coleman
20  * Date: 25 Apr 2010
21  */
22 
23 #ifndef __GAZEBO_ROS_API_PLUGIN_HH__
24 #define __GAZEBO_ROS_API_PLUGIN_HH__
25 
26 #include <stdio.h>
27 #include <stdlib.h>
28 #include <signal.h>
29 #include <errno.h>
30 #include <iostream>
31 
32 #include <tinyxml.h>
33 
34 #include <gazebo/physics/physics.hh>
35 #include <gazebo/common/common.hh>
36 #include <gazebo/transport/transport.hh>
37 
38 // ROS
39 #include <ros/ros.h>
40 #include <ros/callback_queue.h>
41 #include <ros/subscribe_options.h>
42 #include <ros/package.h>
43 #include <rosgraph_msgs/Clock.h>
44 
45 // Services
46 #include "std_srvs/Empty.h"
47 
48 #include "gazebo_msgs/JointRequest.h"
49 #include "gazebo_msgs/BodyRequest.h"
50 
51 #include "gazebo_msgs/SpawnModel.h"
52 #include "gazebo_msgs/DeleteModel.h"
53 #include "gazebo_msgs/DeleteLight.h"
54 
55 #include "gazebo_msgs/ApplyBodyWrench.h"
56 
57 #include "gazebo_msgs/SetPhysicsProperties.h"
58 #include "gazebo_msgs/GetPhysicsProperties.h"
59 
60 #include "gazebo_msgs/SetJointProperties.h"
61 
62 #include "gazebo_msgs/GetWorldProperties.h"
63 
64 #include "gazebo_msgs/GetModelProperties.h"
65 #include "gazebo_msgs/GetModelState.h"
66 #include "gazebo_msgs/SetModelState.h"
67 
68 #include "gazebo_msgs/GetJointProperties.h"
69 #include "gazebo_msgs/ApplyJointEffort.h"
70 
71 #include "gazebo_msgs/GetLinkProperties.h"
72 #include "gazebo_msgs/SetLinkProperties.h"
73 #include "gazebo_msgs/SetLinkState.h"
74 #include "gazebo_msgs/GetLinkState.h"
75 
76 #include "gazebo_msgs/GetLightProperties.h"
77 #include "gazebo_msgs/SetLightProperties.h"
78 
79 // Topics
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 
85 #include "geometry_msgs/Vector3.h"
86 #include "geometry_msgs/Wrench.h"
87 #include "geometry_msgs/Pose.h"
88 #include "geometry_msgs/Twist.h"
89 
90 // For model pose transform to set custom joint angles
91 #include <ros/ros.h>
92 #include <gazebo_msgs/SetModelConfiguration.h>
93 #include <boost/shared_ptr.hpp>
94 
95 // For physics dynamics reconfigure
96 #include <dynamic_reconfigure/server.h>
97 #include <gazebo_ros/PhysicsConfig.h>
98 #include "gazebo_msgs/SetPhysicsProperties.h"
99 #include "gazebo_msgs/GetPhysicsProperties.h"
100 
101 #include <boost/algorithm/string.hpp>
102 
103 namespace gazebo
104 {
105 
107 class GazeboRosApiPlugin : public SystemPlugin
108 {
109 public:
112 
115 
117  void shutdownSignal();
118 
125  void Load(int argc, char** argv);
126 
128  void gazeboQueueThread();
129 
131  void advertiseServices();
132 
134  void onLinkStatesConnect();
135 
137  void onModelStatesConnect();
138 
140  void onLinkStatesDisconnect();
141 
144 
146  bool spawnURDFModel(gazebo_msgs::SpawnModel::Request &req,
147  gazebo_msgs::SpawnModel::Response &res);
148 
150  bool spawnSDFModel(gazebo_msgs::SpawnModel::Request &req,
151  gazebo_msgs::SpawnModel::Response &res);
152 
154  bool deleteModel(gazebo_msgs::DeleteModel::Request &req,gazebo_msgs::DeleteModel::Response &res);
155 
157  bool deleteLight(gazebo_msgs::DeleteLight::Request &req,gazebo_msgs::DeleteLight::Response &res);
158 
160  bool getModelState(gazebo_msgs::GetModelState::Request &req,gazebo_msgs::GetModelState::Response &res);
161 
163  bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req,gazebo_msgs::GetModelProperties::Response &res);
164 
166  bool getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,gazebo_msgs::GetWorldProperties::Response &res);
167 
169  bool getJointProperties(gazebo_msgs::GetJointProperties::Request &req,gazebo_msgs::GetJointProperties::Response &res);
170 
172  bool getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,gazebo_msgs::GetLinkProperties::Response &res);
173 
175  bool getLinkState(gazebo_msgs::GetLinkState::Request &req,gazebo_msgs::GetLinkState::Response &res);
176 
178  bool getLightProperties(gazebo_msgs::GetLightProperties::Request &req,gazebo_msgs::GetLightProperties::Response &res);
179 
181  bool setLightProperties(gazebo_msgs::SetLightProperties::Request &req,gazebo_msgs::SetLightProperties::Response &res);
182 
184  bool setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req,gazebo_msgs::SetLinkProperties::Response &res);
185 
187  bool setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req,gazebo_msgs::SetPhysicsProperties::Response &res);
188 
190  bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req,gazebo_msgs::GetPhysicsProperties::Response &res);
191 
193  bool setJointProperties(gazebo_msgs::SetJointProperties::Request &req,gazebo_msgs::SetJointProperties::Response &res);
194 
196  bool setModelState(gazebo_msgs::SetModelState::Request &req,gazebo_msgs::SetModelState::Response &res);
197 
199  void updateModelState(const gazebo_msgs::ModelState::ConstPtr& model_state);
200 
202  bool applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req,gazebo_msgs::ApplyJointEffort::Response &res);
203 
205  bool resetSimulation(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
206 
208  bool resetWorld(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
209 
211  bool pausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
212 
214  bool unpausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
215 
217  bool clearJointForces(gazebo_msgs::JointRequest::Request &req,gazebo_msgs::JointRequest::Response &res);
218  bool clearJointForces(std::string joint_name);
219 
221  bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req,gazebo_msgs::BodyRequest::Response &res);
222  bool clearBodyWrenches(std::string body_name);
223 
225  bool setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req,gazebo_msgs::SetModelConfiguration::Response &res);
226 
228  bool setLinkState(gazebo_msgs::SetLinkState::Request &req,gazebo_msgs::SetLinkState::Response &res);
229 
231  void updateLinkState(const gazebo_msgs::LinkState::ConstPtr& link_state);
232 
234  bool applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req,gazebo_msgs::ApplyBodyWrench::Response &res);
235 
236 private:
237 
240 
243 
246  void publishSimTime();
247 
249  void publishLinkStates();
250 
252  void publishModelStates();
253 
255  void stripXmlDeclaration(std::string &model_xml);
256 
258  void updateSDFAttributes(TiXmlDocument &gazebo_model_xml,
259  const std::string &model_name,
260  const ignition::math::Vector3d &initial_xyz,
261  const ignition::math::Quaterniond &initial_q);
262 
264  void updateURDFModelPose(TiXmlDocument &gazebo_model_xml,
265  const ignition::math::Vector3d &initial_xyz,
266  const ignition::math::Quaterniond &initial_q);
267 
269  void updateURDFName(TiXmlDocument &gazebo_model_xml, const std::string &model_name);
270 
272  void walkChildAddRobotNamespace(TiXmlNode* model_xml);
273 
275  bool spawnAndConform(TiXmlDocument &gazebo_model_xml, const std::string &model_name,
276  gazebo_msgs::SpawnModel::Response &res);
277 
280  void transformWrench(ignition::math::Vector3d &target_force, ignition::math::Vector3d &target_torque,
281  const ignition::math::Vector3d &reference_force,
282  const ignition::math::Vector3d &reference_torque,
283  const ignition::math::Pose3d &target_to_reference );
284 
286  void physicsReconfigureCallback(gazebo_ros::PhysicsConfig &config, uint32_t level);
287 
290 
292  void onResponse(ConstResponsePtr &response);
293 
295  bool isURDF(std::string model_xml);
296 
298  bool isSDF(std::string model_xml);
299 
301  void loadGazeboRosApiPlugin(std::string world_name);
302 
304  ignition::math::Pose3d parsePose(const std::string &str);
305 
307  ignition::math::Vector3d parseVector3(const std::string &str);
308 
309  // track if the desconstructor event needs to occur
311 
312  // detect if sigint event occurs
313  bool stop_;
314  gazebo::event::ConnectionPtr sigint_event_;
315 
316  std::string robot_namespace_;
317 
318  gazebo::transport::NodePtr gazebonode_;
319  gazebo::transport::SubscriberPtr stat_sub_;
320  gazebo::transport::PublisherPtr factory_pub_;
321  gazebo::transport::PublisherPtr factory_light_pub_;
322  gazebo::transport::PublisherPtr light_modify_pub_;
323  gazebo::transport::PublisherPtr request_pub_;
324  gazebo::transport::SubscriberPtr response_sub_;
325 
329 
330  gazebo::physics::WorldPtr world_;
331  gazebo::event::ConnectionPtr wrench_update_event_;
332  gazebo::event::ConnectionPtr force_update_event_;
333  gazebo::event::ConnectionPtr time_update_event_;
334  gazebo::event::ConnectionPtr pub_link_states_event_;
335  gazebo::event::ConnectionPtr pub_model_states_event_;
336  gazebo::event::ConnectionPtr load_gazebo_ros_api_plugin_event_;
337 
371 
372  // ROS comm
374 
375  // physics dynamic reconfigure
381  dynamic_reconfigure::Server<gazebo_ros::PhysicsConfig>::CallbackType physics_reconfigure_callback_;
382 
385  gazebo::common::Time last_pub_clock_time_;
386 
388  boost::mutex lock_;
389 
391 
393  {
394  public:
395  gazebo::physics::LinkPtr body;
396  ignition::math::Vector3d force;
397  ignition::math::Vector3d torque;
400  };
401 
403  {
404  public:
405  gazebo::physics::JointPtr joint;
406  double force; // should this be a array?
409  };
410 
411  std::vector<GazeboRosApiPlugin::WrenchBodyJob*> wrench_body_jobs_;
412  std::vector<GazeboRosApiPlugin::ForceJointJob*> force_joint_jobs_;
413 
415  std::map<std::string, unsigned int> access_count_get_model_state_;
416 
419 };
420 }
421 #endif
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_
bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req, gazebo_msgs::GetPhysicsProperties::Response &res)
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_
ros::ServiceServer get_model_properties_service_
ros::ServiceServer unpause_physics_service_
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_
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_
ignition::math::Pose3d parsePose(const std::string &str)
convert xml to Pose
gazebo::transport::SubscriberPtr stat_sub_
ros::ServiceServer get_link_properties_service_
ros::ServiceServer set_model_configuration_service_
void advertiseServices()
advertise services
gazebo::physics::WorldPtr world_
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_
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)
gazebo::event::ConnectionPtr sigint_event_
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_
bool pausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer set_link_properties_service_
ros::ServiceServer set_light_properties_service_
bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req, gazebo_msgs::BodyRequest::Response &res)
gazebo::transport::SubscriberPtr response_sub_
bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req, gazebo_msgs::GetModelProperties::Response &res)
boost::shared_ptr< boost::thread > gazebo_callback_queue_thread_
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)
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
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 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...
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
ros::ServiceServer get_physics_properties_service_
const std::string response
bool setModelState(gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
gazebo::transport::PublisherPtr light_modify_pub_


gazebo_ros
Author(s): John Hsu, Nate Koenig, Dave Coleman
autogenerated on Tue Mar 26 2019 02:31:35