Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix cmake warnings #690

Merged
merged 10 commits into from
Sep 22, 2021
Original file line number Diff line number Diff line change
Expand Up @@ -56,12 +56,12 @@ namespace
void checkFCLCapabilities(const DistanceRequest& req)
{
#if MOVEIT_FCL_VERSION < FCL_VERSION_CHECK(0, 6, 0)
static rclcpp::Clock steady_clock(RCL_STEADY_TIME);
if (req.enable_nearest_points)
{
// Known issues:
// https://github.com/flexible-collision-library/fcl/issues/171,
// https://github.com/flexible-collision-library/fcl/pull/288
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 2000,
"You requested a distance check with enable_nearest_points=true, "
"but the FCL version MoveIt was compiled against (%d.%d.%d) "
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/profiler/src/profiler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ void Profiler::console()
std::stringstream ss;
ss << std::endl;
status(ss, true);
RCLCPP_INFO(LOGGER, ss.str().c_str());
RCLCPP_INFO(LOGGER, "%s", ss.str().c_str());
}

/// @cond IGNORE
Expand Down
19 changes: 9 additions & 10 deletions moveit_kinematics/test/test_kinematics_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("test_kinematics_plugin"
const std::string ROBOT_DESCRIPTION_PARAM = "robot_description";
const double DEFAULT_SEARCH_DISCRETIZATION = 0.01f;
const double EXPECTED_SUCCESS_RATE = 0.8;
const double DEFAULT_TOLERANCE = 1e-5;
static const std::string UNDEFINED = "<undefined>";

// As loading of parameters is quite slow, we share them across all tests
Expand Down Expand Up @@ -477,8 +476,8 @@ TEST_F(KinematicsTest, unitIK)
};

std::vector<double> ground_truth, pose_values;
constexpr char POSE_TYPE_RELATIVE[] = "relative";
constexpr char POSE_TYPE_ABSOLUTE[] = "absolute";
constexpr char pose_type_relative[] = "relative";
constexpr char pose_type_absolute[] = "absolute";

/* process tests definitions on parameter server of the form
pose_1:
Expand All @@ -493,8 +492,8 @@ TEST_F(KinematicsTest, unitIK)
for (size_t i = 0; i < expected_test_poses; ++i) // NOLINT(modernize-loop-convert)
{
const std::string pose_name = "pose_" + std::to_string(i);
const std::string pose_param = TEST_POSES_PARAM + "." + pose_name;
goal = initial; // reset goal to initial
const std::string pose_param = TEST_POSES_PARAM + "." + pose_name; // NOLINT
goal = initial; // reset goal to initial
ground_truth.clear();

node_->get_parameter_or(pose_param + ".joints", ground_truth, ground_truth);
Expand All @@ -511,15 +510,15 @@ TEST_F(KinematicsTest, unitIK)

Eigen::Isometry3d pose;
ASSERT_TRUE(parsePose(pose_values, pose)) << "Failed to parse 'pose' vector in: " << pose_name;
std::string pose_type = "POSE_TYPE_RELATIVE";
std::string pose_type = "pose_type_relative";
node_->get_parameter_or(pose_param + ".type", pose_type, pose_type);
if (pose_type == POSE_TYPE_RELATIVE)
if (pose_type == pose_type_relative)
goal = goal * pose;
else if (pose_type == POSE_TYPE_ABSOLUTE)
else if (pose_type == pose_type_absolute)
goal = pose;
else
FAIL() << "Found invalid 'type' in " << pose_name << ": should be one of '" << POSE_TYPE_RELATIVE << "' or '"
<< POSE_TYPE_ABSOLUTE << "'";
FAIL() << "Found invalid 'type' in " << pose_name << ": should be one of '" << pose_type_relative << "' or '"
<< pose_type_absolute << "'";

std::string desc;
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,6 @@ The skeleton of this test was taken from test_state_validity_checker.cpp by Jero
#include <moveit/ompl_interface/detail/threadsafe_state_storage.h>
#include <gtest/gtest.h>

/** \brief This flag sets the verbosity level for the state validity checker. **/
constexpr bool VERBOSE = false;

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_thread_safe_storage");

/** \brief Generic implementation of the tests that can be executed on different robots. **/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ class ActionBasedControllerHandle : public ActionBasedControllerHandleBase
virtual void
controllerDoneCallback(const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult& wrapped_result) = 0;

bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(-1)) override
bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration::from_seconds(-1.0)) override
{
auto result_callback_done = std::make_shared<std::promise<bool>>();
auto result_future = controller_action_client_->async_get_result(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,11 +110,6 @@ class CollisionCheck
bool paused_ = false;

// Variables for stop-distance-based collision checking
double current_collision_distance_ = 0;
double derivative_of_collision_distance_ = 0;
double prev_collision_distance_ = 0;
double est_time_to_collision_ = 0;
double safety_factor_ = 1000;
double worst_case_stop_time_ = std::numeric_limits<double>::max();

const double self_velocity_scale_coefficient_;
Expand Down
1 change: 0 additions & 1 deletion moveit_ros/moveit_servo/src/collision_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.collision_check");
static const double MIN_RECOMMENDED_COLLISION_RATE = 10;
constexpr double EPSILON = 1e-6; // For very small numeric comparisons
constexpr size_t ROS_LOG_THROTTLE_PERIOD = 30 * 1000; // Milliseconds to throttle logs inside loops

namespace moveit_servo
Expand Down
2 changes: 0 additions & 2 deletions moveit_ros/moveit_servo/test/enforce_limits_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@

namespace
{
constexpr double EPSILON = 5e-3;
constexpr double PANDA_MAX_JOINT_VEL = 2.610; // rad/s
constexpr double PUBLISH_PERIOD = 0.01;

void checkVelocityLimits(const moveit::core::JointModelGroup* joint_model_group, const Eigen::ArrayXd& delta_theta)
Expand Down