blob: 895033d01d4730690134a8508398ec7e6378d155 (
plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
|
commit ce0ab101b272c4933f31945e2edaf215c4342772
Author: Steven Peters <scpeters@osrfoundation.org>
Date: Wed Jan 13 11:30:57 2016 -0800
Fix compiler error with SetHFOV
In gazebo7, the rendering::Camera::SetHFOV function
is overloaded with a potential for ambiguity,
as reported in the following issue:
https://bitbucket.org/osrf/gazebo/issues/1830
This fixes the build by explicitly defining the
Angle type.
diff --git a/gazebo_plugins/src/gazebo_ros_camera_utils.cpp b/gazebo_plugins/src/gazebo_ros_camera_utils.cpp
index 2129b65..4574e8d 100644
--- a/gazebo_plugins/src/gazebo_ros_camera_utils.cpp
+++ b/gazebo_plugins/src/gazebo_ros_camera_utils.cpp
@@ -360,7 +360,11 @@ void GazeboRosCameraUtils::LoadThread()
// Set Horizontal Field of View
void GazeboRosCameraUtils::SetHFOV(const std_msgs::Float64::ConstPtr& hfov)
{
- this->camera_->SetHFOV(hfov->data);
+#if GAZEBO_MAJOR_VERSION >= 7
+ this->camera_->SetHFOV(ignition::math::Angle(hfov->data));
+#else
+ this->camera_->SetHFOV(gazebo::math::Angle(hfov->data));
+#endif
}
////////////////////////////////////////////////////////////////////////////////
|