Skip to content

Commit f17d510

Browse files
authored
Merge pull request ros-industrial-attic#129 from mpowelson/jade-devel
Fix C++11 Build Error
2 parents c665199 + a591d89 commit f17d510

File tree

2 files changed

+5
-4
lines changed

2 files changed

+5
-4
lines changed

robotiq_s_model_articulated_gazebo_plugins/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
cmake_minimum_required(VERSION 2.8.3)
22
project(robotiq_s_model_articulated_gazebo_plugins)
3+
add_compile_options(-std=c++11)
34

45
find_package(catkin REQUIRED COMPONENTS std_msgs gazebo_plugins actionlib tf image_transport control_msgs trajectory_msgs geometry_msgs sensor_msgs roscpp gazebo_ros robotiq_s_model_articulated_msgs)
56

robotiq_s_model_articulated_gazebo_plugins/include/robotiq_s_model_articulated_gazebo_plugins/RobotiqHandPlugin.h

+4-4
Original file line numberDiff line numberDiff line change
@@ -173,18 +173,18 @@ class RobotiqHandPlugin : public gazebo::ModelPlugin
173173

174174
/// \brief Velocity tolerance. Below this value we assume that the joint is
175175
/// stopped (rad/s).
176-
private: static const double VelTolerance = 0.002;
176+
private: static constexpr double VelTolerance = 0.002;
177177

178178
/// \brief Position tolerance. If the difference between target position and
179179
/// current position is within this value we'll conclude that the joint
180180
/// reached its target (rad).
181-
private: static const double PoseTolerance = 0.002;
181+
private: static constexpr double PoseTolerance = 0.002;
182182

183183
/// \brief Min. joint speed (rad/s). Finger is 125mm and tip speed is 22mm/s.
184-
private: static const double MinVelocity = 0.176;
184+
private: static constexpr double MinVelocity = 0.176;
185185

186186
/// \brief Max. joint speed (rad/s). Finger is 125mm and tip speed is 110mm/s.
187-
private: static const double MaxVelocity = 0.88;
187+
private: static constexpr double MaxVelocity = 0.88;
188188

189189
/// \brief Default topic name for sending control updates to the left hand.
190190
private: static const std::string DefaultLeftTopicCommand;

0 commit comments

Comments
 (0)