diff options
author | Ben Wolsieffer | 2019-02-02 00:16:29 -0500 |
---|---|---|
committer | Ben Wolsieffer | 2019-02-02 00:16:29 -0500 |
commit | d3bbe0dbe942cafb99cc5523a70a9773a1b61d12 (patch) | |
tree | ca3f62eba9b7eaced1ecb03404fcc5809377aae1 | |
parent | 24a0c332fe8c9788dbe741e6d925dacedb246731 (diff) | |
download | aur-ros-kinetic-gazebo-plugins.tar.gz |
2.5.14 -> 2.5.18
-rw-r--r-- | .SRCINFO | 13 | ||||
-rw-r--r-- | PKGBUILD | 15 | ||||
-rw-r--r-- | gazebo_9_fixes.patch | 592 | ||||
-rw-r--r-- | opencv-header.patch | 28 |
4 files changed, 44 insertions, 604 deletions
@@ -1,8 +1,8 @@ # Generated by mksrcinfo v8 -# Tue Mar 27 04:34:10 UTC 2018 +# Sat Feb 2 05:16:29 UTC 2019 pkgbase = ros-kinetic-gazebo-plugins pkgdesc = ROS - Robot-independent Gazebo plugins for sensors, motors and dynamic reconfigurable components. - pkgver = 2.5.14 + pkgver = 2.5.18 pkgrel = 2 url = http://gazebosim.org/tutorials?cat=connect_ros arch = any @@ -22,6 +22,7 @@ pkgbase = ros-kinetic-gazebo-plugins makedepends = ros-kinetic-diagnostic-updater makedepends = ros-kinetic-std-msgs makedepends = ros-kinetic-dynamic-reconfigure + makedepends = ros-kinetic-rostest makedepends = ros-kinetic-rosgraph-msgs makedepends = ros-kinetic-image-transport makedepends = ros-kinetic-nav-msgs @@ -58,10 +59,10 @@ pkgbase = ros-kinetic-gazebo-plugins depends = ros-kinetic-polled-camera depends = ros-kinetic-message-runtime depends = ros-kinetic-roscpp - source = ros-kinetic-gazebo-plugins-2.5.14-1.tar.gz::https://github.com/ros-gbp/gazebo_ros_pkgs-release/archive/release/kinetic/gazebo_plugins/2.5.14-1.tar.gz - source = gazebo_9_fixes.patch - sha256sums = 4a36e2f8ddfde9671c23fdaf9d899224483f24dd05d66e5210d879bbee6ba22a - sha256sums = e5d1984874912db38418d3e37be9bc3d117c47a846fd4f42a108f2b60ccb00cf + source = ros-kinetic-gazebo-plugins-2.5.18-1.tar.gz::https://github.com/ros-gbp/gazebo_ros_pkgs-release/archive/release/kinetic/gazebo_plugins/2.5.18-1.tar.gz + source = opencv-header.patch + sha256sums = e5552128bf39a1db90a01d7163507a5557e58d8cf4e9fe70dc5f503aabe557d3 + sha256sums = 5c6f119ad0bbfd5f4f747a292bbbe2eb7b858f49c31c41ef0bb5f7b27cb7906e pkgname = ros-kinetic-gazebo-plugins @@ -4,7 +4,7 @@ pkgdesc="ROS - Robot-independent Gazebo plugins for sensors, motors and dynamic url='http://gazebosim.org/tutorials?cat=connect_ros' pkgname='ros-kinetic-gazebo-plugins' -pkgver='2.5.14' +pkgver='2.5.18' _pkgver_patch=1 arch=('any') pkgrel=2 @@ -23,6 +23,7 @@ ros_makedepends=(ros-kinetic-trajectory-msgs ros-kinetic-diagnostic-updater ros-kinetic-std-msgs ros-kinetic-dynamic-reconfigure + ros-kinetic-rostest ros-kinetic-rosgraph-msgs ros-kinetic-image-transport ros-kinetic-nav-msgs @@ -73,13 +74,13 @@ depends=(${ros_depends[@]}) # Tarball version (faster download) _dir="gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-${pkgver}-${_pkgver_patch}" source=("${pkgname}-${pkgver}-${_pkgver_patch}.tar.gz"::"https://github.com/ros-gbp/gazebo_ros_pkgs-release/archive/release/kinetic/gazebo_plugins/${pkgver}-${_pkgver_patch}.tar.gz" - gazebo_9_fixes.patch) -sha256sums=('4a36e2f8ddfde9671c23fdaf9d899224483f24dd05d66e5210d879bbee6ba22a' - 'e5d1984874912db38418d3e37be9bc3d117c47a846fd4f42a108f2b60ccb00cf') + opencv-header.patch) +sha256sums=('e5552128bf39a1db90a01d7163507a5557e58d8cf4e9fe70dc5f503aabe557d3' + '5c6f119ad0bbfd5f4f747a292bbbe2eb7b858f49c31c41ef0bb5f7b27cb7906e') prepare() { - cd ${srcdir} - patch -p1 < gazebo_9_fixes.patch + cd "${srcdir}/${_dir}" + patch -p2 -i "${srcdir}/opencv-header.patch" } build() { @@ -94,6 +95,8 @@ build() { # Fix Python2/Python3 conflicts /usr/share/ros-build-tools/fix-python-scripts.sh -v 2 ${srcdir}/${_dir} + export PKG_CONFIG_PATH="/opt/OGRE-1.9/lib/pkgconfig" + # Build project cmake ${srcdir}/${_dir} \ -DCMAKE_BUILD_TYPE=Release \ diff --git a/gazebo_9_fixes.patch b/gazebo_9_fixes.patch deleted file mode 100644 index d2178e0d4f80..000000000000 --- a/gazebo_9_fixes.patch +++ /dev/null @@ -1,592 +0,0 @@ ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_block_laser.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_block_laser.cpp 2018-03-26 21:13:04.299093024 -0700 -@@ -82,7 +82,7 @@ - std::string worldName = _parent->WorldName(); - this->world_ = physics::get_world(worldName); - -- last_update_time_ = this->world_->GetSimTime(); -+ last_update_time_ = this->world_->SimTime(); - - this->node_ = transport::NodePtr(new transport::Node()); - this->node_->Init(worldName); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_diff_drive.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_diff_drive.cpp 2018-03-26 21:19:46.343259780 -0700 -@@ -131,7 +131,7 @@ - // Initialize update rate stuff - if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_; - else this->update_period_ = 0.0; -- last_update_time_ = parent->GetWorld()->GetSimTime(); -+ last_update_time_ = parent->GetWorld()->SimTime(); - - // Initialize velocity stuff - wheel_speed_[RIGHT] = 0; -@@ -183,7 +183,7 @@ - - void GazeboRosDiffDrive::Reset() - { -- last_update_time_ = parent->GetWorld()->GetSimTime(); -+ last_update_time_ = parent->GetWorld()->SimTime(); - pose_encoder_.x = 0; - pose_encoder_.y = 0; - pose_encoder_.theta = 0; -@@ -203,7 +203,7 @@ - - for ( int i = 0; i < 2; i++ ) { - physics::JointPtr joint = joints_[i]; -- ignition::math::Angle angle = joint->GetAngle ( 0 ).Ign(); -+ ignition::math::Angle angle = joint->Position ( 0 ); - joint_state_.name[i] = joint->GetName(); - joint_state_.position[i] = angle.Radian () ; - } -@@ -251,7 +251,7 @@ - - - if ( odom_source_ == ENCODER ) UpdateOdometryEncoder(); -- common::Time current_time = parent->GetWorld()->GetSimTime(); -+ common::Time current_time = parent->GetWorld()->SimTime(); - double seconds_since_last_update = ( current_time - last_update_time_ ).Double(); - - if ( seconds_since_last_update > update_period_ ) { -@@ -343,7 +343,7 @@ - { - double vl = joints_[LEFT]->GetVelocity ( 0 ); - double vr = joints_[RIGHT]->GetVelocity ( 0 ); -- common::Time current_time = parent->GetWorld()->GetSimTime(); -+ common::Time current_time = parent->GetWorld()->SimTime(); - double seconds_since_last_update = ( current_time - last_odom_update_ ).Double(); - last_odom_update_ = current_time; - -@@ -413,7 +413,7 @@ - } - if ( odom_source_ == WORLD ) { - // getting data form gazebo world -- ignition::math::Pose3d pose = parent->GetWorldPose().Ign(); -+ ignition::math::Pose3d pose = parent->WorldPose(); - qt = tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() ); - vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() ); - -@@ -428,8 +428,8 @@ - - // get velocity in /odom frame - ignition::math::Vector3d linear; -- linear = parent->GetWorldLinearVel().Ign(); -- odom_.twist.twist.angular.z = parent->GetWorldAngularVel().Ign().Z(); -+ linear = parent->WorldLinearVel(); -+ odom_.twist.twist.angular.z = parent->WorldAngularVel().Z(); - - // convert velocity to child_frame_id (aka base_footprint) - float yaw = pose.Rot().Yaw(); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_f3d.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_f3d.cpp 2018-03-26 21:13:04.329092588 -0700 -@@ -164,8 +164,8 @@ - this->lock_.lock(); - // copy data into wrench message - this->wrench_msg_.header.frame_id = this->frame_name_; -- this->wrench_msg_.header.stamp.sec = (this->world_->GetSimTime()).sec; -- this->wrench_msg_.header.stamp.nsec = (this->world_->GetSimTime()).nsec; -+ this->wrench_msg_.header.stamp.sec = (this->world_->SimTime()).sec; -+ this->wrench_msg_.header.stamp.nsec = (this->world_->SimTime()).nsec; - - this->wrench_msg_.wrench.force.x = force.X(); - this->wrench_msg_.wrench.force.y = force.Y(); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_ft_sensor.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_ft_sensor.cpp 2018-03-26 21:13:04.335092501 -0700 -@@ -157,7 +157,7 @@ - // Update the controller - void GazeboRosFT::UpdateChild() - { -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - - // rate control - if (this->update_rate_ > 0 && -@@ -189,8 +189,8 @@ - this->lock_.lock(); - // copy data into wrench message - this->wrench_msg_.header.frame_id = this->frame_name_; -- this->wrench_msg_.header.stamp.sec = (this->world_->GetSimTime()).sec; -- this->wrench_msg_.header.stamp.nsec = (this->world_->GetSimTime()).nsec; -+ this->wrench_msg_.header.stamp.sec = (this->world_->SimTime()).sec; -+ this->wrench_msg_.header.stamp.nsec = (this->world_->SimTime()).nsec; - - this->wrench_msg_.wrench.force.x = force.X() + this->GaussianKernel(0, this->gaussian_noise_); - this->wrench_msg_.wrench.force.y = force.Y() + this->GaussianKernel(0, this->gaussian_noise_); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_hand_of_god.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_hand_of_god.cpp 2018-03-26 21:13:04.341092414 -0700 -@@ -173,7 +173,7 @@ - ignition::math::Quaterniond not_a_quaternion = err_rot.Log(); - - floating_link_->AddForce( -- kl_ * err_pos - cl_ * floating_link_->GetWorldLinearVel().Ign()); -+ kl_ * err_pos - cl_ * floating_link_->WorldLinearVel()); - - floating_link_->AddRelativeTorque( - ka_ * ignition::math::Vector3d(not_a_quaternion.X(), not_a_quaternion.Y(), not_a_quaternion.Z()) ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_imu.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_imu.cpp 2018-03-26 21:17:19.693386103 -0700 -@@ -147,7 +147,7 @@ - - // assert that the body by link_name_ exists - this->link = boost::dynamic_pointer_cast<physics::Link>( -- this->world_->GetEntity(this->link_name_)); -+ this->world_->EntityByName(this->link_name_)); - if (!this->link) - { - ROS_FATAL_NAMED("imu", "gazebo_ros_imu plugin error: bodyName: %s does not exist\n", -@@ -171,11 +171,11 @@ - } - - // Initialize the controller -- this->last_time_ = this->world_->GetSimTime(); -+ this->last_time_ = this->world_->SimTime(); - - // this->initial_pose_ = this->link->GetPose(); -- this->last_vpos_ = this->link->GetWorldLinearVel().Ign(); -- this->last_veul_ = this->link->GetWorldAngularVel().Ign(); -+ this->last_vpos_ = this->link->WorldLinearVel(); -+ this->last_veul_ = this->link->WorldAngularVel(); - this->apos_ = 0; - this->aeul_ = 0; - -@@ -203,7 +203,7 @@ - // Update the controller - void GazeboRosIMU::UpdateChild() - { -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - - // rate control - if (this->update_rate_ > 0 && -@@ -217,7 +217,7 @@ - ignition::math::Vector3d pos; - - // Get Pose/Orientation ///@todo: verify correctness -- pose = this->link->GetWorldPose().Ign(); -+ pose = this->link->WorldPose(); - // apply xyz offsets and get position and rotation components - pos = pose.Pos() + this->offset_.Pos(); - rot = pose.Rot(); -@@ -227,8 +227,8 @@ - rot.Normalize(); - - // get Rates -- ignition::math::Vector3d vpos = this->link->GetWorldLinearVel().Ign(); -- ignition::math::Vector3d veul = this->link->GetWorldAngularVel().Ign(); -+ ignition::math::Vector3d vpos = this->link->WorldLinearVel(); -+ ignition::math::Vector3d veul = this->link->WorldAngularVel(); - - // differentiate to get accelerations - double tmp_dt = this->last_time_.Double() - cur_time.Double(); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_joint_pose_trajectory.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_joint_pose_trajectory.cpp 2018-03-26 21:18:25.228435694 -0700 -@@ -143,7 +143,7 @@ - } - #endif - -- this->last_time_ = this->world_->GetSimTime(); -+ this->last_time_ = this->world_->SimTime(); - - // start custom queue for joint trajectory plugin ros topics - this->callback_queue_thread_ = -@@ -171,7 +171,7 @@ - this->reference_link_name_ != "map") - { - physics::EntityPtr ent = -- this->world_->GetEntity(this->reference_link_name_); -+ this->world_->EntityByName(this->reference_link_name_); - if (ent) - this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent); - if (!this->reference_link_) -@@ -211,7 +211,7 @@ - // trajectory start time - this->trajectory_start = gazebo::common::Time(trajectory->header.stamp.sec, - trajectory->header.stamp.nsec); -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - if (this->trajectory_start < cur_time) - this->trajectory_start = cur_time; - -@@ -250,7 +250,7 @@ - this->reference_link_name_ != "map") - { - physics::EntityPtr ent = -- this->world_->GetEntity(this->reference_link_name_); -+ this->world_->EntityByName(this->reference_link_name_); - if (ent) - this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent); - if (!this->reference_link_) -@@ -320,7 +320,7 @@ - boost::mutex::scoped_lock lock(this->update_mutex); - if (this->has_trajectory_) - { -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - // roll out trajectory via set model configuration - // gzerr << "i[" << trajectory_index << "] time " - // << trajectory_start << " now: " << cur_time << " : "<< "\n"; -@@ -335,10 +335,10 @@ - cur_time.Double(), this->trajectory_index, this->points_.size()); - - // get reference link pose before updates -- ignition::math::Pose3d reference_pose = this->model_->GetWorldPose().Ign(); -+ ignition::math::Pose3d reference_pose = this->model_->WorldPose(); - if (this->reference_link_) - { -- reference_pose = this->reference_link_->GetWorldPose().Ign(); -+ reference_pose = this->reference_link_->WorldPose(); - } - - // trajectory roll-out based on time: ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_joint_state_publisher.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_joint_state_publisher.cpp 2018-03-26 21:19:31.338477267 -0700 -@@ -78,7 +78,7 @@ - } else { - this->update_period_ = 0.0; - } -- last_update_time_ = this->world_->GetSimTime(); -+ last_update_time_ = this->world_->SimTime(); - - for ( unsigned int i = 0; i< joint_names_.size(); i++ ) { - joints_.push_back ( this->parent_->GetJoint ( joint_names_[i] ) ); -@@ -90,7 +90,7 @@ - tf_prefix_ = tf::getPrefixParam ( *rosnode_ ); - joint_state_publisher_ = rosnode_->advertise<sensor_msgs::JointState> ( "joint_states",1000 ); - -- last_update_time_ = this->world_->GetSimTime(); -+ last_update_time_ = this->world_->SimTime(); - // Listen to the update event. This event is broadcast every - // simulation iteration. - this->updateConnection = event::Events::ConnectWorldUpdateBegin ( -@@ -99,7 +99,7 @@ - - void GazeboRosJointStatePublisher::OnUpdate ( const common::UpdateInfo & _info ) { - // Apply a small linear velocity to the model. -- common::Time current_time = this->world_->GetSimTime(); -+ common::Time current_time = this->world_->SimTime(); - double seconds_since_last_update = ( current_time - last_update_time_ ).Double(); - if ( seconds_since_last_update > update_period_ ) { - -@@ -120,7 +120,7 @@ - - for ( int i = 0; i < joints_.size(); i++ ) { - physics::JointPtr joint = joints_[i]; -- ignition::math::Angle angle = joint->GetAngle ( 0 ).Ign(); -+ ignition::math::Angle angle = joint->Position ( 0 ); - joint_state_.name[i] = joint->GetName(); - joint_state_.position[i] = angle.Radian () ; - } ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_joint_trajectory.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_joint_trajectory.cpp 2018-03-26 21:17:56.601850806 -0700 -@@ -145,7 +145,7 @@ - } - #endif - -- this->last_time_ = this->world_->GetSimTime(); -+ this->last_time_ = this->world_->SimTime(); - - // start custom queue for joint trajectory plugin ros topics - this->callback_queue_thread_ = -@@ -173,7 +173,7 @@ - this->reference_link_name_ != "map") - { - physics::EntityPtr ent = -- this->world_->GetEntity(this->reference_link_name_); -+ this->world_->EntityByName(this->reference_link_name_); - if (ent) - this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent); - if (!this->reference_link_) -@@ -213,7 +213,7 @@ - // trajectory start time - this->trajectory_start = gazebo::common::Time(trajectory->header.stamp.sec, - trajectory->header.stamp.nsec); -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - if (this->trajectory_start < cur_time) - this->trajectory_start = cur_time; - -@@ -252,7 +252,7 @@ - this->reference_link_name_ != "map") - { - physics::EntityPtr ent = -- this->world_->GetEntity(this->reference_link_name_); -+ this->world_->EntityByName(this->reference_link_name_); - if (ent) - this->reference_link_ = boost::shared_dynamic_cast<physics::Link>(ent); - if (!this->reference_link_) -@@ -322,7 +322,7 @@ - boost::mutex::scoped_lock lock(this->update_mutex); - if (this->has_trajectory_) - { -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - // roll out trajectory via set model configuration - // gzerr << "i[" << trajectory_index << "] time " - // << trajectory_start << " now: " << cur_time << " : "<< "\n"; -@@ -337,10 +337,10 @@ - cur_time.Double(), this->trajectory_index, this->points_.size()); - - // get reference link pose before updates -- ignition::math::Pose3d reference_pose = this->model_->GetWorldPose().Ign(); -+ ignition::math::Pose3d reference_pose = this->model_->WorldPose(); - if (this->reference_link_) - { -- reference_pose = this->reference_link_->GetWorldPose().Ign(); -+ reference_pose = this->reference_link_->WorldPose(); - } - - // trajectory roll-out based on time: ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_openni_kinect.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_openni_kinect.cpp 2018-03-26 21:13:04.367092036 -0700 -@@ -435,7 +435,7 @@ - if (this->depth_info_connect_count_ > 0) - { - this->sensor_update_time_ = this->parentSensor_->LastMeasurementTime(); -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - if (this->sensor_update_time_ - this->last_depth_image_camera_info_update_time_ >= this->update_period_) - { - this->PublishCameraInfo(this->depth_image_camera_info_pub_); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_p3d.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_p3d.cpp 2018-03-26 21:13:04.371091978 -0700 -@@ -149,10 +149,10 @@ - this->rosnode_->advertise<nav_msgs::Odometry>(this->topic_name_, 1); - } - -- this->last_time_ = this->world_->GetSimTime(); -+ this->last_time_ = this->world_->SimTime(); - // initialize body -- this->last_vpos_ = this->link_->GetWorldLinearVel().Ign(); -- this->last_veul_ = this->link_->GetWorldAngularVel().Ign(); -+ this->last_vpos_ = this->link_->WorldLinearVel(); -+ this->last_veul_ = this->link_->WorldAngularVel(); - this->apos_ = 0; - this->aeul_ = 0; - -@@ -178,8 +178,8 @@ - ROS_DEBUG_NAMED("p3d", "got body %s", this->reference_link_->GetName().c_str()); - this->frame_apos_ = 0; - this->frame_aeul_ = 0; -- this->last_frame_vpos_ = this->reference_link_->GetWorldLinearVel().Ign(); -- this->last_frame_veul_ = this->reference_link_->GetWorldAngularVel().Ign(); -+ this->last_frame_vpos_ = this->reference_link_->WorldLinearVel(); -+ this->last_frame_veul_ = this->reference_link_->WorldAngularVel(); - } - - -@@ -201,7 +201,7 @@ - if (!this->link_) - return; - -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - - // rate control - if (this->update_rate_ > 0 && -@@ -230,23 +230,23 @@ - ignition::math::Vector3d frame_veul; - - // get inertial Rates -- ignition::math::Vector3d vpos = this->link_->GetWorldLinearVel().Ign(); -- ignition::math::Vector3d veul = this->link_->GetWorldAngularVel().Ign(); -+ ignition::math::Vector3d vpos = this->link_->WorldLinearVel(); -+ ignition::math::Vector3d veul = this->link_->WorldAngularVel(); - - // Get Pose/Orientation -- pose = this->link_->GetWorldPose().Ign(); -+ pose = this->link_->WorldPose(); - - // Apply Reference Frame - if (this->reference_link_) - { - // convert to relative pose -- frame_pose = this->reference_link_->GetWorldPose().Ign(); -+ frame_pose = this->reference_link_->WorldPose(); - pose.Pos() = pose.Pos() - frame_pose.Pos(); - pose.Pos() = frame_pose.Rot().RotateVectorReverse(pose.Pos()); - pose.Rot() *= frame_pose.Rot().Inverse(); - // convert to relative rates -- frame_vpos = this->reference_link_->GetWorldLinearVel().Ign(); -- frame_veul = this->reference_link_->GetWorldAngularVel().Ign(); -+ frame_vpos = this->reference_link_->WorldLinearVel(); -+ frame_veul = this->reference_link_->WorldAngularVel(); - vpos = frame_pose.Rot().RotateVector(vpos - frame_vpos); - veul = frame_pose.Rot().RotateVector(veul - frame_veul); - } ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_planar_move.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_planar_move.cpp 2018-03-26 21:13:04.374091935 -0700 -@@ -112,8 +112,8 @@ - odometry_rate_ = sdf->GetElement("odometryRate")->Get<double>(); - } - -- last_odom_publish_time_ = parent_->GetWorld()->GetSimTime(); -- last_odom_pose_ = parent_->GetWorldPose().Ign(); -+ last_odom_publish_time_ = parent_->GetWorld()->SimTime(); -+ last_odom_pose_ = parent_->WorldPose(); - x_ = 0; - y_ = 0; - rot_ = 0; -@@ -160,7 +160,7 @@ - void GazeboRosPlanarMove::UpdateChild() - { - boost::mutex::scoped_lock scoped_lock(lock); -- ignition::math::Pose3d pose = parent_->GetWorldPose().Ign(); -+ ignition::math::Pose3d pose = parent_->WorldPose(); - float yaw = pose.Rot().Yaw(); - parent_->SetLinearVel(ignition::math::Vector3d( - x_ * cosf(yaw) - y_ * sinf(yaw), -@@ -168,7 +168,7 @@ - 0)); - parent_->SetAngularVel(ignition::math::Vector3d(0, 0, rot_)); - if (odometry_rate_ > 0.0) { -- common::Time current_time = parent_->GetWorld()->GetSimTime(); -+ common::Time current_time = parent_->GetWorld()->SimTime(); - double seconds_since_last_update = - (current_time - last_odom_publish_time_).Double(); - if (seconds_since_last_update > (1.0 / odometry_rate_)) { -@@ -214,7 +214,7 @@ - tf::resolve(tf_prefix_, robot_base_frame_); - - // getting data for base_footprint to odom transform -- ignition::math::Pose3d pose = this->parent_->GetWorldPose().Ign(); -+ ignition::math::Pose3d pose = this->parent_->WorldPose(); - - tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W()); - tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z()); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_range.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_range.cpp 2018-03-26 21:13:04.386091760 -0700 -@@ -243,7 +243,7 @@ - { - if (this->topic_name_ != "") - { -- common::Time cur_time = this->world_->GetSimTime(); -+ common::Time cur_time = this->world_->SimTime(); - if (cur_time - this->last_update_time_ >= this->update_period_) - { - common::Time sensor_update_time = ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_skid_steer_drive.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_skid_steer_drive.cpp 2018-03-26 21:13:04.391091688 -0700 -@@ -232,7 +232,7 @@ - } else { - this->update_period_ = 0.0; - } -- last_update_time_ = this->world->GetSimTime(); -+ last_update_time_ = this->world->SimTime(); - - // Initialize velocity stuff - wheel_speed_[RIGHT_FRONT] = 0; -@@ -331,7 +331,7 @@ - - // Update the controller - void GazeboRosSkidSteerDrive::UpdateChild() { -- common::Time current_time = this->world->GetSimTime(); -+ common::Time current_time = this->world->SimTime(); - double seconds_since_last_update = - (current_time - last_update_time_).Double(); - if (seconds_since_last_update > update_period_) { -@@ -405,7 +405,7 @@ - - // TODO create some non-perfect odometry! - // getting data for base_footprint to odom transform -- ignition::math::Pose3d pose = this->parent->GetWorldPose().Ign(); -+ ignition::math::Pose3d pose = this->parent->WorldPose(); - - tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W()); - tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z()); -@@ -436,8 +436,8 @@ - - // get velocity in /odom frame - ignition::math::Vector3d linear; -- linear = this->parent->GetWorldLinearVel().Ign(); -- odom_.twist.twist.angular.z = this->parent->GetWorldAngularVel().Ign().Z(); -+ linear = this->parent->WorldLinearVel(); -+ odom_.twist.twist.angular.z = this->parent->WorldAngularVel().Z(); - - // convert velocity to child_frame_id (aka base_footprint) - float yaw = pose.Rot().Yaw(); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_tricycle_drive.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_tricycle_drive.cpp 2018-03-26 21:15:28.421000548 -0700 -@@ -116,7 +116,7 @@ - // Initialize update rate stuff - if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_; - else this->update_period_ = 0.0; -- last_actuator_update_ = parent->GetWorld()->GetSimTime(); -+ last_actuator_update_ = parent->GetWorld()->SimTime(); - - // Initialize velocity stuff - alive_ = true; -@@ -166,7 +166,7 @@ - joint_state_.effort.resize ( joints.size() ); - for ( std::size_t i = 0; i < joints.size(); i++ ) { - joint_state_.name[i] = joints[i]->GetName(); -- joint_state_.position[i] = joints[i]->GetAngle ( 0 ).Radian(); -+ joint_state_.position[i] = joints[i]->Position ( 0 ); - joint_state_.velocity[i] = joints[i]->GetVelocity ( 0 ); - joint_state_.effort[i] = joints[i]->GetForce ( 0 ); - } -@@ -203,7 +203,7 @@ - void GazeboRosTricycleDrive::UpdateChild() - { - if ( odom_source_ == ENCODER ) UpdateOdometryEncoder(); -- common::Time current_time = parent->GetWorld()->GetSimTime(); -+ common::Time current_time = parent->GetWorld()->SimTime(); - double seconds_since_last_update = ( current_time - last_actuator_update_ ).Double(); - if ( seconds_since_last_update > update_period_ ) { - -@@ -250,7 +250,7 @@ - } - joint_wheel_actuated_->SetParam ( "vel", 0, applied_speed ); - -- double current_angle = joint_steering_->GetAngle ( 0 ).Radian(); -+ double current_angle = joint_steering_->Position ( 0 ); - - // truncate target angle - if (target_angle > +M_PI / 2.0) -@@ -337,7 +337,7 @@ - { - double vl = joint_wheel_encoder_left_->GetVelocity ( 0 ); - double vr = joint_wheel_encoder_right_->GetVelocity ( 0 ); -- common::Time current_time = parent->GetWorld()->GetSimTime(); -+ common::Time current_time = parent->GetWorld()->SimTime(); - double seconds_since_last_update = ( current_time - last_odom_update_ ).Double(); - last_odom_update_ = current_time; - -@@ -397,7 +397,7 @@ - } - if ( odom_source_ == WORLD ) { - // getting data form gazebo world -- ignition::math::Pose3d pose = parent->GetWorldPose().Ign(); -+ ignition::math::Pose3d pose = parent->WorldPose(); - qt = tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() ); - vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() ); - -@@ -412,8 +412,8 @@ - - // get velocity in /odom frame - ignition::math::Vector3d linear; -- linear = parent->GetWorldLinearVel().Ign(); -- odom_.twist.twist.angular.z = parent->GetWorldAngularVel().Ign().Z(); -+ linear = parent->WorldLinearVel(); -+ odom_.twist.twist.angular.z = parent->WorldAngularVel().Z(); - - // convert velocity to child_frame_id (aka base_footprint) - float yaw = pose.Rot().Yaw(); ---- sro/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_vacuum_gripper.cpp 2017-12-21 14:56:25.000000000 -0800 -+++ src/gazebo_ros_pkgs-release-release-kinetic-gazebo_plugins-2.5.14-1/src/gazebo_ros_vacuum_gripper.cpp 2018-03-26 21:13:04.410091412 -0700 -@@ -183,7 +183,7 @@ - ignition::math::Pose3d parent_pose = link_->WorldPose(); - physics::Model_V models = world_->Models(); - #else -- ignition::math::Pose3d parent_pose = link_->GetWorldPose().Ign(); -+ ignition::math::Pose3d parent_pose = link_->WorldPose(); - physics::Model_V models = world_->GetModels(); - #endif - for (size_t i = 0; i < models.size(); i++) { -@@ -194,7 +194,7 @@ - } - physics::Link_V links = models[i]->GetLinks(); - for (size_t j = 0; j < links.size(); j++) { -- ignition::math::Pose3d link_pose = links[j]->GetWorldPose().Ign(); -+ ignition::math::Pose3d link_pose = links[j]->WorldPose(); - ignition::math::Pose3d diff = parent_pose - link_pose; - double norm = diff.Pos().Length(); - if (norm < 0.05) { diff --git a/opencv-header.patch b/opencv-header.patch new file mode 100644 index 000000000000..816432c36411 --- /dev/null +++ b/opencv-header.patch @@ -0,0 +1,28 @@ +From 3819c073c74667996359e6a4ac9d8e8f477fedc1 Mon Sep 17 00:00:00 2001 +From: Ben Wolsieffer <benwolsieffer@gmail.com> +Date: Sat, 2 Feb 2019 00:09:45 -0500 +Subject: [PATCH] Remove old OpenCV header. + +--- + gazebo_plugins/src/gazebo_ros_prosilica.cpp | 5 +---- + 1 file changed, 1 insertion(+), 4 deletions(-) + +diff --git a/gazebo_plugins/src/gazebo_ros_prosilica.cpp b/gazebo_plugins/src/gazebo_ros_prosilica.cpp +index cb25c41..9fee4b3 100644 +--- a/gazebo_plugins/src/gazebo_ros_prosilica.cpp ++++ b/gazebo_plugins/src/gazebo_ros_prosilica.cpp +@@ -44,10 +44,7 @@ + #include <diagnostic_updater/diagnostic_updater.h> + #include <sensor_msgs/RegionOfInterest.h> + +-#include <opencv/cv.h> +-#include <opencv/highgui.h> +- +-#include <opencv/cvwimage.h> ++#include <opencv2/opencv.hpp> + + #include <boost/scoped_ptr.hpp> + #include <boost/bind.hpp> +-- +2.20.1 + |