47 #include <flatland_msgs/DeleteModel.h> 48 #include <flatland_msgs/MoveModel.h> 49 #include <flatland_msgs/SpawnModel.h> 50 #include <flatland_server/simulation_manager.h> 51 #include <flatland_server/world.h> 53 #include <std_srvs/Empty.h> 55 #ifndef FLATLAND_PLUGIN_SERVICE_MANAGER_H 56 #define FLATLAND_PLUGIN_SERVICE_MANAGER_H 60 class SimulationManager;
91 bool SpawnModel(flatland_msgs::SpawnModel::Request &request,
92 flatland_msgs::SpawnModel::Response &response);
99 bool DeleteModel(flatland_msgs::DeleteModel::Request &request,
100 flatland_msgs::DeleteModel::Response &response);
107 bool MoveModel(flatland_msgs::MoveModel::Request &request,
108 flatland_msgs::MoveModel::Response &response);
113 bool Pause(std_srvs::Empty::Request &request,
114 std_srvs::Empty::Response &response);
119 bool Resume(std_srvs::Empty::Request &request,
120 std_srvs::Empty::Response &response);
125 bool TogglePause(std_srvs::Empty::Request &request,
126 std_srvs::Empty::Response &response);
bool Pause(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback for the pause service.
Definition: service_manager.cpp:150
bool TogglePause(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback for the pause toggle service.
Definition: service_manager.cpp:162
bool DeleteModel(flatland_msgs::DeleteModel::Request &request, flatland_msgs::DeleteModel::Response &response)
Callback for the delete model service.
Definition: service_manager.cpp:113
bool SpawnModel(flatland_msgs::SpawnModel::Request &request, flatland_msgs::SpawnModel::Response &response)
Callback for the spawn model service.
Definition: service_manager.cpp:88
bool Resume(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback for the resume service.
Definition: service_manager.cpp:156
ros::ServiceServer spawn_model_service_
service for spawning models
Definition: service_manager.h:71
ros::ServiceServer move_model_service_
service for moving models
Definition: service_manager.h:73
ros::ServiceServer resume_service_
service for resuming the simulation
Definition: service_manager.h:75
Definition: service_manager.h:66
World * world_
aaa handle to the simulation world
Definition: service_manager.h:68
ros::ServiceServer pause_service_
service for pausing the simulation
Definition: service_manager.h:74
ServiceManager(SimulationManager *sim_man, World *world)
Service manager constructor.
Definition: service_manager.cpp:53
SimulationManager * sim_man_
a handle to the simulation manager
Definition: service_manager.h:69
bool MoveModel(flatland_msgs::MoveModel::Request &request, flatland_msgs::MoveModel::Response &response)
Callback for the move model service.
Definition: service_manager.cpp:131
ros::ServiceServer toggle_pause_service_
Definition: service_manager.h:76
Definition: simulation_manager.h:58
ros::ServiceServer delete_model_service_
service for deleting models
Definition: service_manager.h:72