Go to the documentation of this file.
17 #ifndef GAZEBO_ROS_WHEEL_SLIP_H
18 #define GAZEBO_ROS_WHEEL_SLIP_H
25 #include <std_msgs/Bool.h>
28 #include <gazebo_plugins/WheelSlipConfig.h>
29 #include <dynamic_reconfigure/server.h>
31 #include <gazebo/plugins/WheelSlipPlugin.hh>
58 public:
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
65 gazebo_plugins::WheelSlipConfig &config,
72 private: dynamic_reconfigure::Server<gazebo_plugins::WheelSlipConfig>
virtual ~GazeboRosWheelSlip()
Destructor.
ros::CallbackQueue queue_
void QueueThread()
Custom callback queue thread.
std::string robotNamespace_
for setting ROS name space
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
ros::NodeHandle * rosnode_
pointer to ros node
GazeboRosWheelSlip()
Constructor.
dynamic_reconfigure::Server< gazebo_plugins::WheelSlipConfig > * dyn_srv_
Dynamic reconfigure server.
void configCallback(gazebo_plugins::WheelSlipConfig &config, uint32_t level)
See the Gazebo documentation about the WheelSlipPlugin. This ROS wrapper exposes two parameters via d...
boost::thread callbackQueueThread_
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55