# Depend on system install of Gazebo
find_package(gazebo REQUIRED)
+if(${GAZEBO_MAJOR_VERSION} GREATER "5")
+ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=gnu++11")
+endif()
+
find_package(Boost REQUIRED)
catkin_package(
}
// Set max effort
- if(!has_pid_)
+ if(!has_pid_) {
+#if GAZEBO_MAJOR_VERSION > 2
+ mimic_joint_->SetEffortLimit(0,max_effort_);
+#else
mimic_joint_->SetMaxForce(0,max_effort_);
+#endif
+ }
// Listen to the update event. This event is broadcast every
// simulation iteration.
double effort = gazebo::math::clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_);
mimic_joint_->SetForce(0, effort);
}
- else
+ else {
+#if GAZEBO_MAJOR_VERSION > 2
+ mimic_joint_->SetPosition(0, angle );
+#else
mimic_joint_->SetAngle(0, math::Angle(angle));
+#endif
+ }
}
}