30 #include <gazebo/common/Events.hh> 31 #include <gazebo/physics/physics.hh> 60 world = _model->GetWorld();
63 if (_sdf->HasElement(
"robotNamespace"))
64 namespace_ = _sdf->GetElement(
"robotNamespace")->GetValue()->GetAsString();
68 if (!_sdf->HasElement(
"topicName"))
71 topic_ = _sdf->GetElement(
"topicName")->Get<std::string>();
74 if (_sdf->HasElement(
"bodyName"))
76 link_name_ = _sdf->GetElement(
"bodyName")->GetValue()->GetAsString();
81 link = _model->GetLink();
87 ROS_FATAL(
"GazeboRosMagnetic plugin error: bodyName: %s does not exist\n",
link_name_.c_str());
98 if (_sdf->HasElement(
"frameId"))
99 frame_id_ = _sdf->GetElement(
"frameId")->GetValue()->GetAsString();
101 if (_sdf->HasElement(
"magnitude"))
102 _sdf->GetElement(
"magnitude")->GetValue()->Get(
magnitude_);
104 if (_sdf->HasElement(
"referenceHeading"))
108 if (_sdf->HasElement(
"declination"))
109 if (_sdf->GetElement(
"declination")->GetValue()->Get(
declination_))
112 if (_sdf->HasElement(
"inclination"))
113 if (_sdf->GetElement(
"inclination")->GetValue()->Get(
inclination_))
116 if (_sdf->HasElement(
"useMagneticFieldMsgs"))
122 #if (GAZEBO_MAJOR_VERSION >= 8) 169 #if (GAZEBO_MAJOR_VERSION >= 8) 170 common::Time sim_time =
world->SimTime();
172 ignition::math::Pose3d pose =
link->WorldPose();
175 common::Time sim_time =
world->GetSimTime();
178 math::Pose pose =
link->GetWorldPose();
184 sensor_msgs::MagneticField magnetic_field;
186 magnetic_field.header.stamp =
ros::Time(sim_time.sec, sim_time.nsec);
187 magnetic_field.header.frame_id =
frame_id_;
188 #if (GAZEBO_MAJOR_VERSION >= 8) 189 magnetic_field.magnetic_field.x = field.X();
190 magnetic_field.magnetic_field.y = field.Y();
191 magnetic_field.magnetic_field.z = field.Z();
193 magnetic_field.magnetic_field.x = field.x;
194 magnetic_field.magnetic_field.y = field.y;
195 magnetic_field.magnetic_field.z = field.z;
206 geometry_msgs::Vector3Stamped magnetic_field;
208 magnetic_field.header.stamp =
ros::Time(sim_time.sec, sim_time.nsec);
209 magnetic_field.header.frame_id =
frame_id_;
210 #if (GAZEBO_MAJOR_VERSION >= 8) 211 magnetic_field.vector.x = field.X();
212 magnetic_field.vector.y = field.Y();
213 magnetic_field.vector.z = field.Z();
215 magnetic_field.vector.x = field.x;
216 magnetic_field.vector.y = field.y;
217 magnetic_field.vector.z = field.z;
double reference_heading_
event::ConnectionPtr updateConnection
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf, const std::string &_prefix="update")
static const double DEFAULT_DECLINATION
void publish(const boost::shared_ptr< M > &message) const
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix=std::string())
physics::LinkPtr link
The link referred to by this plugin.
ROSCPP_DECL bool isInitialized()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual event::ConnectionPtr Connect(const boost::function< void()> &_subscriber, bool connectToWorldUpdateBegin=true)
static const double DEFAULT_MAGNITUDE
ros::Publisher publisher_
bool use_magnetic_field_msgs_
gazebo::math::Vector3 magnetic_field_world_
physics::WorldPtr world
The parent World.
SensorModel3 sensor_model_
virtual ~GazeboRosMagnetic()
virtual void Disconnect(event::ConnectionPtr const &_c=event::ConnectionPtr())
virtual void dynamicReconfigureCallback(SensorModelConfig &config, uint32_t level)
common::Time getTimeSinceLastUpdate() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static const double DEFAULT_REFERENCE_HEADING
static const double DEFAULT_INCLINATION
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_
ros::NodeHandle * node_handle_