Tetrapod Project
terrain_plugin.h
Go to the documentation of this file.
1 #pragma once
2 
3 // Gazebo
4 #include <gazebo/gazebo.hh>
5 #include <gazebo/physics/physics.hh>
6 
7 // ROS
8 #include "ros/ros.h"
9 #include "ros/package.h"
10 #include "ros/console.h"
11 #include "ros/callback_queue.h"
12 #include "ros/subscribe_options.h"
13 #include "eigen_conversions/eigen_msg.h"
14 #include "std_msgs/Float32.h"
15 #include "std_msgs/Float64MultiArray.h"
16 #include "sensor_msgs/JointState.h"
17 #include "std_srvs/Empty.h"
18 
19 
20 #include<string>
21 #include<vector>
22 #include<iostream>
23 
24 namespace gazebo{
25 
26 
27 class TerrainPlugin : public WorldPlugin
28 {
29  public: TerrainPlugin();
30 
31  public: virtual ~TerrainPlugin();
32 
38  public: virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
39 
40  public: bool ResetSimulation(const std_srvs::Empty::Request &_req,
41  std_srvs::Empty::Response &_res);
42 
43  public: void InitRos();
44 
45  public: void InitRosQueueThreads();
46 
47  public: void ProcessQueueThread();
48 
50  private: physics::WorldPtr world;
51 
53  private: std::unique_ptr<ros::NodeHandle> rosNode;
54 
56  private: ros::ServiceServer resetSimService;
57 
58  private: ros::ServiceClient tetrapodResetService;
59 
61  private: ros::CallbackQueue rosProcessQueue;
62 
64  private: std::thread rosProcessQueueThread;
65 
66 };
67 
68  // Tell Gazebo about this plugin, so that Gazebo can call Load on this plugin.
69 GZ_REGISTER_WORLD_PLUGIN(TerrainPlugin)
70 }
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
The Load function is called by Gazebo when the plugin is inserted into simulation.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
ros::ServiceServer resetSimService
ROS Reset Simulation Service.
physics::WorldPtr world
Pointer to the world.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
ros::ServiceClient tetrapodResetService
bool ResetSimulation(const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)