Skip to content

Commit

Permalink
Remove test_tolerances_utils
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jun 24, 2024
1 parent 2bdc0c2 commit 36ecdda
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 61 deletions.
6 changes: 3 additions & 3 deletions joint_trajectory_controller/test/test_tolerances.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include "gmock/gmock.h"
#include "rclcpp/duration.hpp"
#include "rclcpp/logger.hpp"

#include "joint_trajectory_controller/tolerances.hpp"
#include "test_tolerances_utils.hpp"
#include "trajectory_msgs/msg/joint_trajectory.hpp"
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"

#include "joint_trajectory_controller/tolerances.hpp"
#include "test_trajectory_controller_utils.hpp"

using joint_trajectory_controller::SegmentTolerances;
using trajectory_msgs::msg::JointTrajectoryPoint;

Expand Down
57 changes: 0 additions & 57 deletions joint_trajectory_controller/test/test_tolerances_utils.hpp

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"

#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "test_tolerances_utils.hpp"
#include "test_trajectory_controller_utils.hpp"

using std::placeholders::_1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@

#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "joint_trajectory_controller/tolerances.hpp"

namespace
{
Expand All @@ -38,6 +39,40 @@ const std::vector<double> INITIAL_VEL_JOINTS = {0.0, 0.0, 0.0};
const std::vector<double> INITIAL_ACC_JOINTS = {0.0, 0.0, 0.0};
const std::vector<double> INITIAL_EFF_JOINTS = {0.0, 0.0, 0.0};

const double default_goal_time = 0.1;
const double stopped_velocity_tolerance = 0.1;

[[maybe_unused]] void expectDefaultTolerances(
joint_trajectory_controller::SegmentTolerances active_tolerances)
{
// acceleration is never set, and goal_state_tolerance.velocity from stopped_velocity_tolerance

ASSERT_EQ(active_tolerances.state_tolerance.size(), 3);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).position, 0.1);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(0).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).position, 0.1);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(1).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).position, 0.1);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).velocity, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.state_tolerance.at(2).acceleration, 0.0);

ASSERT_EQ(active_tolerances.goal_state_tolerance.size(), 3);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).position, 0.1);
EXPECT_DOUBLE_EQ(
active_tolerances.goal_state_tolerance.at(0).velocity, stopped_velocity_tolerance);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(0).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).position, 0.1);
EXPECT_DOUBLE_EQ(
active_tolerances.goal_state_tolerance.at(1).velocity, stopped_velocity_tolerance);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(1).acceleration, 0.0);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).position, 0.1);
EXPECT_DOUBLE_EQ(
active_tolerances.goal_state_tolerance.at(2).velocity, stopped_velocity_tolerance);
EXPECT_DOUBLE_EQ(active_tolerances.goal_state_tolerance.at(2).acceleration, 0.0);
}

bool is_same_sign_or_zero(double val1, double val2)
{
return val1 * val2 > 0.0 || (val1 == 0.0 && val2 == 0.0);
Expand Down

0 comments on commit 36ecdda

Please sign in to comment.