Go to the documentation of this file.
17 #include <gazebo/physics/World.hh>
18 #include <gazebo/physics/Model.hh>
19 #ifdef ENABLE_PROFILER
20 #include <ignition/common/Profiler.hh>
53 HarnessPlugin::Load(_parent, _sdf);
56 if (_sdf->HasElement(
"robotNamespace"))
63 <<
"properly initialized. Try starting gazebo with ros plugin:\n"
64 <<
" gazebo -s libgazebo_ros_api_plugin.so\n");
71 "/" + _parent->GetName() +
"/harness/velocity", 1,
76 so = ros::SubscribeOptions::create<std_msgs::Bool>(
77 "/" + _parent->GetName() +
"/harness/detach", 1,
90 #ifdef ENABLE_PROFILER
91 IGN_PROFILE(
"GazeboRosHarness::OnVelocity");
92 IGN_PROFILE_BEGIN(
"process ROS message");
95 this->SetWinchVelocity(
msg->data);
96 #ifdef ENABLE_PROFILER
112 static const double timeout = 0.01;
ros::CallbackQueue queue_
virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg)
Receive winch velocity control messages.
ros::Subscriber detachSub_
Subscriber to detach control messages.
ros::NodeHandle * rosnode_
pointer to ros node
boost::thread callbackQueueThread_
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
std::string robotNamespace_
for setting ROS name space
#define ROS_FATAL_STREAM_NAMED(name, args)
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ROSCPP_DECL bool isInitialized()
virtual ~GazeboRosHarness()
Destructor.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber velocitySub_
Subscriber to velocity control messages.
virtual void OnDetach(const std_msgs::Bool::ConstPtr &msg)
Receive detach messages.
GazeboRosHarness()
Constructor.
void QueueThread()
Custom callback queue thread.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55