Go to the documentation of this file.
25 #ifdef ENABLE_PROFILER
26 #include <ignition/common/Profiler.hh>
59 this->
world_ = _parent->GetWorld();
63 if (_sdf->HasElement(
"robotNamespace"))
64 this->
robot_namespace_ = _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
66 if (!_sdf->HasElement(
"bodyName"))
68 ROS_FATAL_NAMED(
"f3d",
"f3d plugin missing <bodyName>, cannot proceed");
72 this->
link_name_ = _sdf->GetElement(
"bodyName")->Get<std::string>();
81 if (!_sdf->HasElement(
"topicName"))
83 ROS_FATAL_NAMED(
"f3d",
"f3d plugin missing <topicName>, cannot proceed");
87 this->
topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
89 if (!_sdf->HasElement(
"frameName"))
91 ROS_INFO_NAMED(
"f3d",
"f3d plugin missing <frameName>, defaults to world");
96 this->
frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
106 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
152 #ifdef ENABLE_PROFILER
153 IGN_PROFILE(
"GazeboRosF3D::UpdateChild");
158 #ifdef ENABLE_PROFILER
159 IGN_PROFILE_BEGIN(
"fill ROS message");
161 ignition::math::Vector3d torque;
162 ignition::math::Vector3d force;
165 #if GAZEBO_MAJOR_VERSION >= 8
166 force = this->
link_->WorldForce();
167 torque = this->
link_->WorldTorque();
169 force = this->
link_->GetWorldForce().Ign();
170 torque = this->
link_->GetWorldTorque().Ign();
176 #if GAZEBO_MAJOR_VERSION >= 8
190 #ifdef ENABLE_PROFILER
192 IGN_PROFILE_BEGIN(
"publish");
195 #ifdef ENABLE_PROFILER
198 this->
lock_.unlock();
206 static const double timeout = 0.01;
std::string robot_namespace_
for setting ROS name space
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string link_name_
store bodyname
bool getParam(const std::string &key, bool &b) const
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
std::string resolve(const std::string &prefix, const std::string &frame_name)
#define ROS_FATAL_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
virtual ~GazeboRosF3D()
Destructor.
#define ROS_INFO_NAMED(name,...)
#define ROS_FATAL_STREAM_NAMED(name, args)
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ROSCPP_DECL bool isInitialized()
boost::thread callback_queue_thread_
std::string topic_name_
ROS WrenchStamped topic name.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
int f3d_connect_count_
: keep track of number of connections
std::string frame_name_
ROS frame transform name to use in the image message header. This should be simply map since the retu...
virtual void UpdateChild()
Update the controller.
physics::LinkPtr link_
A pointer to the Gazebo Body.
event::ConnectionPtr update_connection_
ros::CallbackQueue queue_
GazeboRosF3D()
Constructor.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55