dev-ros/gazebo_plugins: backport upstream fixes to build with gazebo7
authorAlexis Ballier <aballier@gentoo.org>
Thu, 28 Jan 2016 20:25:34 +0000 (21:25 +0100)
committerAlexis Ballier <aballier@gentoo.org>
Thu, 28 Jan 2016 20:25:43 +0000 (21:25 +0100)
Package-Manager: portage-2.2.27
Signed-off-by: Alexis Ballier <aballier@gentoo.org>
dev-ros/gazebo_plugins/files/gazebo6.patch [new file with mode: 0644]
dev-ros/gazebo_plugins/files/gazebo7-2.patch [new file with mode: 0644]
dev-ros/gazebo_plugins/files/gazebo7-3.patch [new file with mode: 0644]
dev-ros/gazebo_plugins/files/gazebo7-4.patch [new file with mode: 0644]
dev-ros/gazebo_plugins/files/gazebo7-5.patch [new file with mode: 0644]
dev-ros/gazebo_plugins/files/gazebo7.patch [new file with mode: 0644]
dev-ros/gazebo_plugins/gazebo_plugins-2.5.1.ebuild
dev-ros/gazebo_plugins/gazebo_plugins-9999.ebuild

diff --git a/dev-ros/gazebo_plugins/files/gazebo6.patch b/dev-ros/gazebo_plugins/files/gazebo6.patch
new file mode 100644 (file)
index 0000000..43dd2d7
--- /dev/null
@@ -0,0 +1,44 @@
+commit 04855dc0fd2d82d6fe72c0b54ae66a5f86c5ceb4
+Author: Steven Peters <scpeters@osrfoundation.org>
+Date:   Tue Jan 12 17:36:06 2016 -0800
+
+    Fix gazebo6 deprecation warnings
+    
+    Several RaySensor functions are deprecated in gazebo6
+    and are removed in gazebo7.
+    The return type is changed to use ignition math
+    and the function name is changed.
+    This adds ifdef's to handle the changes.
+
+diff --git a/gazebo_plugins/src/gazebo_ros_block_laser.cpp b/gazebo_plugins/src/gazebo_ros_block_laser.cpp
+index d8f40bc..76e0206 100644
+--- a/gazebo_plugins/src/gazebo_ros_block_laser.cpp
++++ b/gazebo_plugins/src/gazebo_ros_block_laser.cpp
+@@ -230,8 +230,13 @@ void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime)
+   this->parent_ray_sensor_->SetActive(false);
++#if GAZEBO_MAJOR_VERSION >= 6
++  auto maxAngle = this->parent_ray_sensor_->AngleMax();
++  auto minAngle = this->parent_ray_sensor_->AngleMin();
++#else
+   math::Angle maxAngle = this->parent_ray_sensor_->GetAngleMax();
+   math::Angle minAngle = this->parent_ray_sensor_->GetAngleMin();
++#endif
+   double maxRange = this->parent_ray_sensor_->GetRangeMax();
+   double minRange = this->parent_ray_sensor_->GetRangeMin();
+@@ -240,8 +245,13 @@ void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime)
+   int verticalRayCount = this->parent_ray_sensor_->GetVerticalRayCount();
+   int verticalRangeCount = this->parent_ray_sensor_->GetVerticalRangeCount();
++#if GAZEBO_MAJOR_VERSION >= 6
++  auto verticalMaxAngle = this->parent_ray_sensor_->VerticalAngleMax();
++  auto verticalMinAngle = this->parent_ray_sensor_->VerticalAngleMin();
++#else
+   math::Angle verticalMaxAngle = this->parent_ray_sensor_->GetVerticalAngleMax();
+   math::Angle verticalMinAngle = this->parent_ray_sensor_->GetVerticalAngleMin();
++#endif
+   double yDiff = maxAngle.Radian() - minAngle.Radian();
+   double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
diff --git a/dev-ros/gazebo_plugins/files/gazebo7-2.patch b/dev-ros/gazebo_plugins/files/gazebo7-2.patch
new file mode 100644 (file)
index 0000000..09af84e
--- /dev/null
@@ -0,0 +1,22 @@
+commit a27311b3b37a661aadb9815346d26e2970441bef
+Author: Steven Peters <scpeters@osrfoundation.org>
+Date:   Wed Jan 13 11:29:32 2016 -0800
+
+    Add missing boost header
+    
+    Some boost headers were remove from gazebo7 header files
+    and gazebo_ros_joint_state_publisher.cpp was using it
+    implicitly.
+
+diff --git a/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp b/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp
+index 6c1ede1..d78b3d8 100644
+--- a/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp
++++ b/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp
+@@ -25,6 +25,7 @@
+  *  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+  *
+  **/
++#include <boost/algorithm/string.hpp>
+ #include <gazebo_plugins/gazebo_ros_joint_state_publisher.h>
+ #include <tf/transform_broadcaster.h>
+ #include <tf/transform_listener.h>
diff --git a/dev-ros/gazebo_plugins/files/gazebo7-3.patch b/dev-ros/gazebo_plugins/files/gazebo7-3.patch
new file mode 100644 (file)
index 0000000..895033d
--- /dev/null
@@ -0,0 +1,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
+ }
+ ////////////////////////////////////////////////////////////////////////////////
diff --git a/dev-ros/gazebo_plugins/files/gazebo7-4.patch b/dev-ros/gazebo_plugins/files/gazebo7-4.patch
new file mode 100644 (file)
index 0000000..0dab70d
--- /dev/null
@@ -0,0 +1,21 @@
+commit d7580215c9e39eddc33196b32b05219fcea707fd
+Author: Steven Peters <scpeters@osrfoundation.org>
+Date:   Fri Jan 15 16:29:37 2016 -0800
+
+    gazebo_ros_utils.h: include gazebo_config.h
+    
+    Make sure to include gazebo_config.h,
+    which defines the GAZEBO_MAJOR_VERSION macro
+
+diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h b/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
+index 6cdc4a8..6b016b8 100644
+--- a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
++++ b/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
+@@ -39,6 +39,7 @@
+ #include <gazebo/common/common.hh>
+ #include <gazebo/physics/physics.hh>
+ #include <gazebo/sensors/Sensor.hh>
++#include <gazebo/gazebo_config.h>
+ #include <ros/ros.h>
+ #ifndef GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
diff --git a/dev-ros/gazebo_plugins/files/gazebo7-5.patch b/dev-ros/gazebo_plugins/files/gazebo7-5.patch
new file mode 100644 (file)
index 0000000..d83fdc2
--- /dev/null
@@ -0,0 +1,146 @@
+commit 19f5f19f48def0a2c5808a7266151eb8e06d7b63
+Author: Steven Peters <scpeters@osrfoundation.org>
+Date:   Tue Apr 14 18:10:36 2015 -0700
+
+    Use Joint::SetParam for joint velocity motors
+    
+    Before gazebo5, Joint::SetVelocity and SetMaxForce
+    were used to set joint velocity motors.
+    The API has changed in gazebo5, to use Joint::SetParam
+    instead.
+    The functionality is still available through the SetParam API.
+
+diff --git a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp b/gazebo_plugins/src/gazebo_ros_diff_drive.cpp
+index 004fb90..68265a8 100644
+--- a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp
++++ b/gazebo_plugins/src/gazebo_ros_diff_drive.cpp
+@@ -100,8 +100,8 @@ void GazeboRosDiffDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf
+     joints_.resize ( 2 );
+     joints_[LEFT] = gazebo_ros_->getJoint ( parent, "leftJoint", "left_joint" );
+     joints_[RIGHT] = gazebo_ros_->getJoint ( parent, "rightJoint", "right_joint" );
+-    joints_[LEFT]->SetMaxForce ( 0, wheel_torque );
+-    joints_[RIGHT]->SetMaxForce ( 0, wheel_torque );
++    joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
++    joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
+@@ -170,8 +170,8 @@ void GazeboRosDiffDrive::Reset()
+   pose_encoder_.theta = 0;
+   x_ = 0;
+   rot_ = 0;
+-  joints_[LEFT]->SetMaxForce ( 0, wheel_torque );
+-  joints_[RIGHT]->SetMaxForce ( 0, wheel_torque );
++  joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
++  joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
+ }
+ void GazeboRosDiffDrive::publishWheelJointState()
+@@ -214,15 +214,15 @@ void GazeboRosDiffDrive::publishWheelTF()
+ void GazeboRosDiffDrive::UpdateChild()
+ {
+   
+-    /* force reset SetMaxForce since Joint::Reset reset MaxForce to zero at
++    /* force reset SetParam("fmax") since Joint::Reset reset MaxForce to zero at
+        https://bitbucket.org/osrf/gazebo/src/8091da8b3c529a362f39b042095e12c94656a5d1/gazebo/physics/Joint.cc?at=gazebo2_2.2.5#cl-331
+        (this has been solved in https://bitbucket.org/osrf/gazebo/diff/gazebo/physics/Joint.cc?diff2=b64ff1b7b6ff&at=issue_964 )
+        and Joint::Reset is called after ModelPlugin::Reset, so we need to set maxForce to wheel_torque other than GazeboRosDiffDrive::Reset
+        (this seems to be solved in https://bitbucket.org/osrf/gazebo/commits/ec8801d8683160eccae22c74bf865d59fac81f1e)
+     */
+     for ( int i = 0; i < 2; i++ ) {
+-      if ( fabs(wheel_torque -joints_[i]->GetMaxForce ( 0 )) > 1e-6 ) {
+-        joints_[i]->SetMaxForce ( 0, wheel_torque );
++      if ( fabs(wheel_torque -joints_[i]->GetParam ( "fmax", 0 )) > 1e-6 ) {
++        joints_[i]->SetParam ( "fmax", 0, wheel_torque );
+       }
+     }
+@@ -248,8 +248,8 @@ void GazeboRosDiffDrive::UpdateChild()
+                 ( fabs ( wheel_speed_[LEFT] - current_speed[LEFT] ) < 0.01 ) ||
+                 ( fabs ( wheel_speed_[RIGHT] - current_speed[RIGHT] ) < 0.01 ) ) {
+             //if max_accel == 0, or target speed is reached
+-            joints_[LEFT]->SetVelocity ( 0, wheel_speed_[LEFT]/ ( wheel_diameter_ / 2.0 ) );
+-            joints_[RIGHT]->SetVelocity ( 0, wheel_speed_[RIGHT]/ ( wheel_diameter_ / 2.0 ) );
++            joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_[LEFT]/ ( wheel_diameter_ / 2.0 ) );
++            joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_[RIGHT]/ ( wheel_diameter_ / 2.0 ) );
+         } else {
+             if ( wheel_speed_[LEFT]>=current_speed[LEFT] )
+                 wheel_speed_instr_[LEFT]+=fmin ( wheel_speed_[LEFT]-current_speed[LEFT],  wheel_accel * seconds_since_last_update );
+@@ -264,8 +264,8 @@ void GazeboRosDiffDrive::UpdateChild()
+             // ROS_INFO("actual wheel speed = %lf, issued wheel speed= %lf", current_speed[LEFT], wheel_speed_[LEFT]);
+             // ROS_INFO("actual wheel speed = %lf, issued wheel speed= %lf", current_speed[RIGHT],wheel_speed_[RIGHT]);
+-            joints_[LEFT]->SetVelocity ( 0,wheel_speed_instr_[LEFT] / ( wheel_diameter_ / 2.0 ) );
+-            joints_[RIGHT]->SetVelocity ( 0,wheel_speed_instr_[RIGHT] / ( wheel_diameter_ / 2.0 ) );
++            joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_instr_[LEFT] / ( wheel_diameter_ / 2.0 ) );
++            joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_instr_[RIGHT] / ( wheel_diameter_ / 2.0 ) );
+         }
+         last_update_time_+= common::Time ( update_period_ );
+     }
+diff --git a/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp b/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp
+index fdaf61f..a24aba5 100644
+--- a/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp
++++ b/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp
+@@ -256,10 +256,10 @@ namespace gazebo {
+        gzthrow(error);
+    }
+-    joints[LEFT_FRONT]->SetMaxForce(0, torque);
+-    joints[RIGHT_FRONT]->SetMaxForce(0, torque);
+-    joints[LEFT_REAR]->SetMaxForce(0, torque);
+-    joints[RIGHT_REAR]->SetMaxForce(0, torque);
++    joints[LEFT_FRONT]->SetParam("fmax", 0, torque);
++    joints[RIGHT_FRONT]->SetParam("fmax", 0, torque);
++    joints[LEFT_REAR]->SetParam("fmax", 0, torque);
++    joints[RIGHT_REAR]->SetParam("fmax", 0, torque);
+     // Make sure the ROS node for Gazebo has already been initialized
+     if (!ros::isInitialized())
+@@ -308,10 +308,10 @@ namespace gazebo {
+       // Update robot in case new velocities have been requested
+       getWheelVelocities();
+-      joints[LEFT_FRONT]->SetVelocity(0, wheel_speed_[LEFT_FRONT] / (wheel_diameter_ / 2.0));
+-      joints[RIGHT_FRONT]->SetVelocity(0, wheel_speed_[RIGHT_FRONT] / (wheel_diameter_ / 2.0));
+-      joints[LEFT_REAR]->SetVelocity(0, wheel_speed_[LEFT_REAR] / (wheel_diameter_ / 2.0));
+-      joints[RIGHT_REAR]->SetVelocity(0, wheel_speed_[RIGHT_REAR] / (wheel_diameter_ / 2.0));
++      joints[LEFT_FRONT]->SetParam("vel", 0, wheel_speed_[LEFT_FRONT] / (wheel_diameter_ / 2.0));
++      joints[RIGHT_FRONT]->SetParam("vel", 0, wheel_speed_[RIGHT_FRONT] / (wheel_diameter_ / 2.0));
++      joints[LEFT_REAR]->SetParam("vel", 0, wheel_speed_[LEFT_REAR] / (wheel_diameter_ / 2.0));
++      joints[RIGHT_REAR]->SetParam("vel", 0, wheel_speed_[RIGHT_REAR] / (wheel_diameter_ / 2.0));
+       last_update_time_+= common::Time(update_period_);
+diff --git a/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp b/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp
+index 97c5ebb..0e83d2a 100644
+--- a/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp
++++ b/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp
+@@ -108,8 +108,8 @@ void GazeboRosTricycleDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _
+     odomOptions["world"] = WORLD;
+     gazebo_ros_->getParameter<OdomSource> ( odom_source_, "odometrySource", odomOptions, WORLD );
+-    joint_wheel_actuated_->SetMaxForce ( 0, wheel_torque_ );
+-    joint_steering_->SetMaxForce ( 0, wheel_torque_ );
++    joint_wheel_actuated_->SetParam ( "fmax", 0, wheel_torque_ );
++    joint_steering_->SetParam ( "fmax", 0, wheel_torque_ );
+     // Initialize update rate stuff
+@@ -235,7 +235,7 @@ void GazeboRosTricycleDrive::motorController ( double target_speed, double targe
+             applied_speed = current_speed - wheel_deceleration_ * dt;
+         }
+     }
+-    joint_wheel_actuated_->SetVelocity ( 0, applied_speed );
++    joint_wheel_actuated_->SetParam ( "vel", 0, applied_speed );
+     
+     double current_angle = joint_steering_->GetAngle ( 0 ).Radian();
+     if(target_angle > +M_PI / 2.0) target_angle =  +M_PI / 2.0;
+@@ -249,7 +249,7 @@ void GazeboRosTricycleDrive::motorController ( double target_speed, double targe
+         } else {
+             applied_steering_speed = -steering_speed_;
+         }
+-      joint_steering_->SetVelocity ( 0, applied_steering_speed );
++      joint_steering_->SetParam ( "vel", 0, applied_steering_speed );
+     }else {
+ #if GAZEBO_MAJOR_VERSION >= 4
+       joint_steering_->SetPosition ( 0, applied_angle );
diff --git a/dev-ros/gazebo_plugins/files/gazebo7.patch b/dev-ros/gazebo_plugins/files/gazebo7.patch
new file mode 100644 (file)
index 0000000..7b10e18
--- /dev/null
@@ -0,0 +1,176 @@
+commit 194ebf81f025c450555ec8cf3a98653bb1307c4c
+Author: Steven Peters <scpeters@osrfoundation.org>
+Date:   Wed Jan 13 11:25:52 2016 -0800
+
+    Fix gazebo7 build errors
+    
+    The SensorPtr types have changed from boost:: pointers
+    to std:: pointers,
+    which requires boost::dynamic_pointer_cast to change to
+    std::dynamic_pointer_cast.
+    A helper macro is added that adds a `using` statement
+    corresponding to the correct type of dynamic_pointer_cast.
+    This macro should be narrowly scoped to protect
+    other code.
+
+diff --git a/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h b/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h
+index ff38ef6..b3092d0 100644
+--- a/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h
++++ b/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h
+@@ -43,7 +43,7 @@ namespace gazebo
+                               unsigned int _width, unsigned int _height,
+                               unsigned int _depth, const std::string &_format);
+-    protected: boost::shared_ptr<sensors::MultiCameraSensor> parentSensor;
++    protected: sensors::MultiCameraSensorPtr parentSensor;
+     protected: std::vector<unsigned int> width, height, depth;
+     protected: std::vector<std::string> format;
+diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h b/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
+index 3db4c45..6cdc4a8 100644
+--- a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
++++ b/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h
+@@ -41,6 +41,14 @@
+ #include <gazebo/sensors/Sensor.hh>
+ #include <ros/ros.h>
++#ifndef GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
++# if GAZEBO_MAJOR_VERSION >= 7
++#define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST using std::dynamic_pointer_cast
++# else
++#define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST using boost::dynamic_pointer_cast
++# endif
++#endif
++
+ namespace gazebo
+ {
+diff --git a/gazebo_plugins/src/MultiCameraPlugin.cpp b/gazebo_plugins/src/MultiCameraPlugin.cpp
+index 8001a22..11f663c 100644
+--- a/gazebo_plugins/src/MultiCameraPlugin.cpp
++++ b/gazebo_plugins/src/MultiCameraPlugin.cpp
+@@ -17,6 +17,7 @@
+ #include <gazebo/sensors/DepthCameraSensor.hh>
+ #include <gazebo/sensors/CameraSensor.hh>
+ #include <gazebo_plugins/MultiCameraPlugin.h>
++#include <gazebo_plugins/gazebo_ros_utils.h>
+ using namespace gazebo;
+ GZ_REGISTER_SENSOR_PLUGIN(MultiCameraPlugin)
+@@ -40,15 +41,16 @@ void MultiCameraPlugin::Load(sensors::SensorPtr _sensor,
+   if (!_sensor)
+     gzerr << "Invalid sensor pointer.\n";
++  GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
+   this->parentSensor =
+-    boost::dynamic_pointer_cast<sensors::MultiCameraSensor>(_sensor);
++    dynamic_pointer_cast<sensors::MultiCameraSensor>(_sensor);
+   if (!this->parentSensor)
+   {
+     gzerr << "MultiCameraPlugin requires a CameraSensor.\n";
+-    if (boost::dynamic_pointer_cast<sensors::DepthCameraSensor>(_sensor))
++    if (dynamic_pointer_cast<sensors::DepthCameraSensor>(_sensor))
+       gzmsg << "It is a depth camera sensor\n";
+-    if (boost::dynamic_pointer_cast<sensors::CameraSensor>(_sensor))
++    if (dynamic_pointer_cast<sensors::CameraSensor>(_sensor))
+       gzmsg << "It is a camera sensor\n";
+   }
+diff --git a/gazebo_plugins/src/gazebo_ros_block_laser.cpp b/gazebo_plugins/src/gazebo_ros_block_laser.cpp
+index 76e0206..d03b9f1 100644
+--- a/gazebo_plugins/src/gazebo_ros_block_laser.cpp
++++ b/gazebo_plugins/src/gazebo_ros_block_laser.cpp
+@@ -24,6 +24,7 @@
+ #include <assert.h>
+ #include <gazebo_plugins/gazebo_ros_block_laser.h>
++#include <gazebo_plugins/gazebo_ros_utils.h>
+ #include <gazebo/physics/World.hh>
+ #include <gazebo/physics/HingeJoint.hh>
+@@ -86,7 +87,8 @@ void GazeboRosBlockLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
+   this->node_ = transport::NodePtr(new transport::Node());
+   this->node_->Init(worldName);
+-  this->parent_ray_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
++  GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
++  this->parent_ray_sensor_ = dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
+   if (!this->parent_ray_sensor_)
+     gzthrow("GazeboRosBlockLaser controller requires a Ray Sensor as its parent");
+diff --git a/gazebo_plugins/src/gazebo_ros_bumper.cpp b/gazebo_plugins/src/gazebo_ros_bumper.cpp
+index 059f1d9..f8dbdd0 100644
+--- a/gazebo_plugins/src/gazebo_ros_bumper.cpp
++++ b/gazebo_plugins/src/gazebo_ros_bumper.cpp
+@@ -39,6 +39,7 @@
+ #include <tf/tf.h>
+ #include <gazebo_plugins/gazebo_ros_bumper.h>
++#include <gazebo_plugins/gazebo_ros_utils.h>
+ namespace gazebo
+ {
+@@ -65,7 +66,8 @@ GazeboRosBumper::~GazeboRosBumper()
+ // Load the controller
+ void GazeboRosBumper::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
+ {
+-  this->parentSensor = boost::dynamic_pointer_cast<sensors::ContactSensor>(_parent);
++  GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
++  this->parentSensor = dynamic_pointer_cast<sensors::ContactSensor>(_parent);
+   if (!this->parentSensor)
+   {
+     ROS_ERROR("Contact sensor parent is not of type ContactSensor");
+diff --git a/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp b/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp
+index 811fc81..6b36c48 100644
+--- a/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp
++++ b/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp
+@@ -75,8 +75,9 @@ void GazeboRosLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
+   // save pointers
+   this->sdf = _sdf;
++  GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
+   this->parent_ray_sensor_ =
+-    boost::dynamic_pointer_cast<sensors::GpuRaySensor>(_parent);
++    dynamic_pointer_cast<sensors::GpuRaySensor>(_parent);
+   if (!this->parent_ray_sensor_)
+     gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent");
+diff --git a/gazebo_plugins/src/gazebo_ros_laser.cpp b/gazebo_plugins/src/gazebo_ros_laser.cpp
+index 815c456..80e60a2 100644
+--- a/gazebo_plugins/src/gazebo_ros_laser.cpp
++++ b/gazebo_plugins/src/gazebo_ros_laser.cpp
+@@ -72,8 +72,9 @@ void GazeboRosLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
+   // save pointers
+   this->sdf = _sdf;
++  GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
+   this->parent_ray_sensor_ =
+-    boost::dynamic_pointer_cast<sensors::RaySensor>(_parent);
++    dynamic_pointer_cast<sensors::RaySensor>(_parent);
+   if (!this->parent_ray_sensor_)
+     gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent");
+diff --git a/gazebo_plugins/src/gazebo_ros_range.cpp b/gazebo_plugins/src/gazebo_ros_range.cpp
+index 9387dde..cb229fe 100644
+--- a/gazebo_plugins/src/gazebo_ros_range.cpp
++++ b/gazebo_plugins/src/gazebo_ros_range.cpp
+@@ -35,6 +35,7 @@
+ /** \author Jose Capriles, Bence Magyar. */
+ #include "gazebo_plugins/gazebo_ros_range.h"
++#include "gazebo_plugins/gazebo_ros_utils.h"
+ #include <algorithm>
+ #include <string>
+@@ -92,8 +93,9 @@ void GazeboRosRange::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
+   this->last_update_time_ = common::Time(0);
++  GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
+   this->parent_ray_sensor_ =
+-    boost::dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
++    dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
+   if (!this->parent_ray_sensor_)
+     gzthrow("GazeboRosRange controller requires a Ray Sensor as its parent");
index 45c19f28d45fb2ac80e2d110e3724d02691d077f..5a965c4ad09b8b463fe0b6a90d8ac0ddd017b3e6 100644 (file)
@@ -42,7 +42,7 @@ RDEPEND="
        dev-ros/camera_info_manager
        dev-ros/moveit_msgs[${CATKIN_MESSAGES_CXX_USEDEP}]
        dev-libs/libxml2
-       sci-electronics/gazebo
+       >=sci-electronics/gazebo-7:=
        dev-games/ogre
        sci-libs/pcl
        dev-libs/boost:=
@@ -51,3 +51,11 @@ RDEPEND="
        dev-ros/roslib[${PYTHON_USEDEP}]
 "
 DEPEND="${RDEPEND}"
+PATCHES=(
+       "${FILESDIR}/gazebo6.patch"
+       "${FILESDIR}/gazebo7.patch"
+       "${FILESDIR}/gazebo7-2.patch"
+       "${FILESDIR}/gazebo7-3.patch"
+       "${FILESDIR}/gazebo7-4.patch"
+       "${FILESDIR}/gazebo7-5.patch"
+)
index 45c19f28d45fb2ac80e2d110e3724d02691d077f..2c0abf6a639e4ea11d08c8f8bdf8f78a2266ea49 100644 (file)
@@ -42,7 +42,7 @@ RDEPEND="
        dev-ros/camera_info_manager
        dev-ros/moveit_msgs[${CATKIN_MESSAGES_CXX_USEDEP}]
        dev-libs/libxml2
-       sci-electronics/gazebo
+       >=sci-electronics/gazebo-7:=
        dev-games/ogre
        sci-libs/pcl
        dev-libs/boost:=