diff --git a/robotiq_control/package.xml b/robotiq_control/package.xml index 4ccab84..b2ca7a1 100644 --- a/robotiq_control/package.xml +++ b/robotiq_control/package.xml @@ -13,7 +13,7 @@ catkin rospy - python-pymodbus + python3-pymodbus robotiq_description robotiq_msgs diff --git a/robotiq_description/CMakeLists.txt b/robotiq_description/CMakeLists.txt index a214fd9..108ed58 100644 --- a/robotiq_description/CMakeLists.txt +++ b/robotiq_description/CMakeLists.txt @@ -1,17 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(robotiq_description) -find_package(catkin REQUIRED COMPONENTS - openrave_catkin -) +find_package(catkin REQUIRED) catkin_package() -install(DIRECTORY launch meshes urdf DESTINATION - ${CATKIN_PACKAGE_SHARE_DESTINATION}) - -# Add the meshes to the OpenRAVE path -install(DIRECTORY meshes - DESTINATION ${OpenRAVE_DEVEL_DIR}/${OpenRAVE_DATA_DIR}/robots) -install(DIRECTORY meshes - DESTINATION ${OpenRAVE_INSTALL_DIR}/${OpenRAVE_DATA_DIR}/robots) +install(DIRECTORY meshes models urdf worlds + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/robotiq_description/package.xml b/robotiq_description/package.xml index 4910067..440697b 100755 --- a/robotiq_description/package.xml +++ b/robotiq_description/package.xml @@ -13,7 +13,6 @@ catkin rospy - openrave_catkin robot_state_publisher urdf diff --git a/robotiq_gazebo/src/mimic_joint_plugin.cpp b/robotiq_gazebo/src/mimic_joint_plugin.cpp index dc34a73..0298245 100644 --- a/robotiq_gazebo/src/mimic_joint_plugin.cpp +++ b/robotiq_gazebo/src/mimic_joint_plugin.cpp @@ -47,7 +47,7 @@ MimicJointPlugin::MimicJointPlugin() MimicJointPlugin::~MimicJointPlugin() { - event::Events::DisconnectWorldUpdateBegin(this->updateConnection); + this->updateConnection.reset(); kill_sim = true; } @@ -167,20 +167,20 @@ void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf ) void MimicJointPlugin::UpdateChild() { - static ros::Duration period(world_->GetPhysicsEngine()->GetMaxStepSize()); + static ros::Duration period(world_->Physics()->GetMaxStepSize()); // Set mimic joint's angle based on joint's angle - double angle = joint_->GetAngle(0).Radian()*multiplier_+offset_; + double angle = joint_->Position(0)*multiplier_+offset_; - if(abs(angle-mimic_joint_->GetAngle(0).Radian())>=sensitiveness_) + if(abs(angle-mimic_joint_->Position(0))>=sensitiveness_) { if(has_pid_) { - double a = mimic_joint_->GetAngle(0).Radian(); + double a = mimic_joint_->Position(0); if(a!=a) a = angle; double error = angle-a; - double effort = gazebo::math::clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_); + double effort = ignition::math::clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_); } else {