4 #include <gazebo/gazebo.hh>
5 #include <gazebo/physics/physics.hh>
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"
38 public:
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
41 std_srvs::Empty::Response &_res);
50 private: physics::WorldPtr
world;
53 private: std::unique_ptr<ros::NodeHandle>
rosNode;
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.
void ProcessQueueThread()
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
ros::ServiceClient tetrapodResetService
void InitRosQueueThreads()
bool ResetSimulation(const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)