30 #include <gazebo/common/Events.hh> 31 #include <gazebo/physics/physics.hh> 32 #include <gazebo/sensors/RaySensor.hh> 36 #include <gazebo/gazebo_config.h> 62 #if (GAZEBO_MAJOR_VERSION > 6) 63 sensor_ = std::dynamic_pointer_cast<sensors::RaySensor>(_sensor);
65 sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(_sensor);
69 gzthrow(
"GazeboRosSonar requires a Ray Sensor as its parent");
74 #if (GAZEBO_MAJOR_VERSION > 6) 75 std::string worldName = sensor_->WorldName();
77 std::string worldName = sensor_->GetWorldName();
79 world = physics::get_world(worldName);
87 if (_sdf->HasElement(
"robotNamespace"))
88 namespace_ = _sdf->GetElement(
"robotNamespace")->GetValue()->GetAsString();
90 if (_sdf->HasElement(
"frameId"))
91 frame_id_ = _sdf->GetElement(
"frameId")->GetValue()->GetAsString();
93 if (_sdf->HasElement(
"topicName"))
94 topic_ = _sdf->GetElement(
"topicName")->GetValue()->GetAsString();
99 range_.radiation_type = sensor_msgs::Range::ULTRASOUND;
100 #if (GAZEBO_MAJOR_VERSION > 6) 101 range_.field_of_view = std::min(fabs((sensor_->AngleMax() - sensor_->AngleMin()).Radian()), fabs((sensor_->VerticalAngleMax() - sensor_->VerticalAngleMin()).Radian()));
102 range_.max_range = sensor_->RangeMax();
103 range_.min_range = sensor_->RangeMin();
105 range_.field_of_view = std::min(fabs((sensor_->GetAngleMax() - sensor_->GetAngleMin()).Radian()), fabs((sensor_->GetVerticalAngleMax() - sensor_->GetVerticalAngleMin()).Radian()));
106 range_.max_range = sensor_->GetRangeMax();
107 range_.min_range = sensor_->GetRangeMin();
113 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 114 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
133 sensor_->SetActive(
true);
146 #if (GAZEBO_MAJOR_VERSION >= 8) 147 common::Time sim_time =
world->SimTime();
149 common::Time sim_time =
world->GetSimTime();
156 #if (GAZEBO_MAJOR_VERSION >= 8) 158 range_.header.stamp.nsec = (
world->SimTime()).nsec;
160 range_.header.stamp.sec = (
world->GetSimTime()).sec;
161 range_.header.stamp.nsec = (
world->GetSimTime()).nsec;
165 range_.range = std::numeric_limits<sensor_msgs::Range::_range_type>::max();
166 #if (GAZEBO_MAJOR_VERSION > 6) 167 int num_ranges =
sensor_->LaserShape()->GetSampleCount() *
sensor_->LaserShape()->GetVerticalSampleCount();
169 int num_ranges =
sensor_->GetLaserShape()->GetSampleCount() *
sensor_->GetLaserShape()->GetVerticalSampleCount();
171 for(
int i = 0; i < num_ranges; ++i) {
172 #if (GAZEBO_MAJOR_VERSION > 6) 173 double ray =
sensor_->LaserShape()->GetRange(i);
175 double ray =
sensor_->GetLaserShape()->GetRange(i);
sensors::RaySensorPtr sensor_
ros::NodeHandle * node_handle_
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf, const std::string &_prefix="update")
void publish(const boost::shared_ptr< M > &message) const
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix=std::string())
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
ros::Publisher publisher_
ROSCPP_DECL bool isInitialized()
virtual event::ConnectionPtr Connect(const boost::function< void()> &_subscriber, bool connectToWorldUpdateBegin=true)
SensorModel sensor_model_
#define ROS_FATAL_STREAM(args)
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)
event::ConnectionPtr updateConnection
virtual ~GazeboRosSonar()
physics::WorldPtr world
The parent World.
sensor_msgs::Range range_
void setUpdateRate(double rate)
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_