ROSProximityRayPlugin.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include "ROSProximityRayPlugin.hh"
19 
20 #include <string>
21 
22 using namespace gazebo;
23 // Register this plugin with the simulator
24 GZ_REGISTER_SENSOR_PLUGIN(ROSProximityRayPlugin)
25 
26 // Constructor
29 {
30 }
31 
33 // Destructor
35 {
36  this->rosnode->shutdown();
37 }
38 
39 void ROSProximityRayPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
40 {
41  // Make sure the ROS node for Gazebo has already been initialized
42  if (!ros::isInitialized())
43  {
44  ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
45  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
46  return;
47  }
48 
49  ProximityRayPlugin::Load(_parent, _sdf);
50 
51  // Read ROS-specific sdf tags
52  this->robotNamespace = "";
53  if (_sdf->HasElement("robotNamespace"))
54  {
55  this->robotNamespace = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
56  }
57 
58  // Over-ride topics from the ProximityRayPlugin which may contain ~s
59  this->stateTopic = _parent->Name();
60  if (_sdf->HasElement("output_state_topic"))
61  {
62  this->stateTopic = _sdf->Get<std::string>("output_state_topic");
63  }
64 
65  this->stateChangeTopic = _parent->Name() + "_change";
66  if (_sdf->HasElement("output_change_topic"))
67  {
68  this->stateChangeTopic = _sdf->Get<std::string>("output_change_topic");
69  }
70 
71  this->frameId = _parent->Name() + "_frame";
72  if (_sdf->HasElement("frame_id"))
73  {
74  this->frameId = _sdf->Get<std::string>("frame_id");
75  }
76  this->state_msg.header.frame_id = this->frameId;
77 
78  this->rosnode = new ros::NodeHandle(this->robotNamespace);
79 
80  // Initialize the publishers
81  this->statePub = this->rosnode->advertise<osrf_gear::Proximity>(
82  this->stateTopic, 1, true);
83  this->stateChangePub = this->rosnode->advertise<osrf_gear::Proximity>(
84  this->stateChangeTopic, 1, true);
85 
86  // Callback for laser scans
88  this->parentSensor->LaserShape()->ConnectNewLaserScans(
89  std::bind(&ROSProximityRayPlugin::OnNewLaserScans, this));
90 
91 }
92 
94 // Update the controller
96 {
97  auto now = this->world->GetSimTime();
98  bool stateChanged = this->ProcessScan();
99  this->state_msg.header.stamp.sec = now.sec;
100  this->state_msg.header.stamp.nsec = now.nsec;
101  this->state_msg.object_detected = this->objectDetected;
102  this->state_msg.min_range = this->sensingRangeMin;
103  this->state_msg.max_range = this->sensingRangeMax;
104  this->statePub.publish(this->state_msg);
105  if (stateChanged)
106  {
107  gzdbg << this->parentSensor->Name() << ": change in sensor state\n";
108  this->stateChangePub.publish(this->state_msg);
109  }
110 }
111 
virtual void OnNewLaserScans()
Update callback.
osrf_gear::Proximity state_msg
ROS message for the sensor state.
ROS interface for the ProximityRayPlugin plugin.
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL bool isInitialized()
physics::WorldPtr world
Pointer to world.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
virtual bool ProcessScan()
Process the scan data and update state.
event::ConnectionPtr newLaserScansConnection
The connection tied to ROSProximityRayPlugin::OnNewLaserScans()
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
virtual ~ROSProximityRayPlugin()
Destructor.
std::string frameId
for setting ROS frame id
ros::Publisher stateChangePub
ROS publisher for the sensor state changes.
#define ROS_FATAL_STREAM(args)
double sensingRangeMin
Minimum sensing range in meters.
bool objectDetected
Sensor detection state.
sensors::RaySensorPtr parentSensor
The parent sensor.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string stateTopic
Topic name for state message.
ros::NodeHandle * rosnode
A pointer to the ROS node. A node will be instantiated if it does not exist.
double sensingRangeMax
Maximum sensing range in meters.
std::string stateChangeTopic
Topic name for state change message.
ros::Publisher statePub
ROS publisher for the sensor state.
std::string robotNamespace
for setting ROS namespace


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:12