28
28
29
29
using namespace gazebo ;
30
30
31
+ template <typename T>
32
+ std::shared_ptr<T> GetAndCheckSensor (sensors::SensorManager *smanager, std::string name) {
33
+ const gazebo::sensors::SensorPtr s = smanager->GetSensor (name);
34
+ if (s == NULL ) {
35
+ std::cerr << " RealSensePlugin: Sensor '" << name << " ' not found. Available sensor are:" << std::endl;
36
+ const auto sensors = smanager->GetSensors ();
37
+ for (const auto & sensor : sensors) {
38
+ std::cerr << " \t " << sensor->Name () << std::endl;
39
+ }
40
+ return NULL ;
41
+ }
42
+ return std::dynamic_pointer_cast<T>(s);
43
+ }
44
+
45
+
31
46
// ///////////////////////////////////////////////
32
47
RealSensePlugin::RealSensePlugin () {
33
48
this ->depthCam = nullptr ;
@@ -117,7 +132,7 @@ void RealSensePlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) {
117
132
else if (name == " robotNamespace" )
118
133
break ;
119
134
else
120
- throw std::runtime_error (" Ivalid parameter for ReakSensePlugin " );
135
+ throw std::runtime_error (" Invalid parameter for RealSensePlugin " );
121
136
122
137
_sdf = _sdf->GetNextElement ();
123
138
} while (_sdf);
@@ -132,39 +147,47 @@ void RealSensePlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) {
132
147
sensors::SensorManager *smanager = sensors::SensorManager::Instance ();
133
148
134
149
// Get Cameras Renderers
135
- this ->depthCam = std::dynamic_pointer_cast<sensors::DepthCameraSensor>(
136
- smanager->GetSensor (prefix + DEPTH_CAMERA_NAME))
137
- ->DepthCamera ();
138
-
139
- this ->ired1Cam = std::dynamic_pointer_cast<sensors::CameraSensor>(
140
- smanager->GetSensor (prefix + IRED1_CAMERA_NAME))
141
- ->Camera ();
142
- this ->ired2Cam = std::dynamic_pointer_cast<sensors::CameraSensor>(
143
- smanager->GetSensor (prefix + IRED2_CAMERA_NAME))
144
- ->Camera ();
145
- this ->colorCam = std::dynamic_pointer_cast<sensors::CameraSensor>(
146
- smanager->GetSensor (prefix + COLOR_CAMERA_NAME))
147
- ->Camera ();
150
+ sensors::DepthCameraSensorPtr depth_cs = GetAndCheckSensor<sensors::DepthCameraSensor>(smanager, std::string (prefix + DEPTH_CAMERA_NAME));
151
+ if (depth_cs) {
152
+ this ->depthCam = depth_cs->DepthCamera ();
153
+ }
154
+ sensors::CameraSensorPtr ired1_cs = GetAndCheckSensor<sensors::CameraSensor>(smanager, std::string (prefix + IRED1_CAMERA_NAME));
155
+ if (ired1_cs) {
156
+ this ->ired1Cam = ired1_cs->Camera ();
157
+ }
158
+ sensors::CameraSensorPtr ired2_cs = GetAndCheckSensor<sensors::CameraSensor>(smanager, std::string (prefix + IRED2_CAMERA_NAME));
159
+ if (ired2_cs) {
160
+ this ->ired2Cam = ired2_cs->Camera ();
161
+ }
162
+ sensors::CameraSensorPtr color_cs = GetAndCheckSensor<sensors::CameraSensor>(smanager, std::string (prefix + COLOR_CAMERA_NAME));
163
+ if (color_cs) {
164
+ this ->colorCam = color_cs->Camera ();
165
+ }
148
166
167
+ bool abort{false };
149
168
// Check if camera renderers have been found successfuly
150
169
if (!this ->depthCam ) {
151
170
std::cerr << " RealSensePlugin: Depth Camera has not been found"
152
171
<< std::endl;
153
- return ;
172
+ abort = true ;
154
173
}
155
174
if (!this ->ired1Cam ) {
156
175
std::cerr << " RealSensePlugin: InfraRed Camera 1 has not been found"
157
176
<< std::endl;
158
- return ;
177
+ abort = true ;
159
178
}
160
179
if (!this ->ired2Cam ) {
161
180
std::cerr << " RealSensePlugin: InfraRed Camera 2 has not been found"
162
181
<< std::endl;
163
- return ;
182
+ abort = true ;
164
183
}
165
184
if (!this ->colorCam ) {
166
185
std::cerr << " RealSensePlugin: Color Camera has not been found"
167
186
<< std::endl;
187
+ abort = true ;
188
+ }
189
+ if (abort) {
190
+ std:cerr << " RealSensePlugin: Aborting loading"
168
191
return ;
169
192
}
170
193
0 commit comments