Skip to content

Commit

Permalink
rename to JointSaturationLimiter
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth committed Dec 8, 2023
1 parent 9ed9b01 commit bcf42aa
Show file tree
Hide file tree
Showing 6 changed files with 35 additions and 35 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@
#ifndef HARDWARE_INTERFACE__TYPES__HARDWARE_INTERFACE_TYPE_VALUES_HPP_
#define HARDWARE_INTERFACE__TYPES__HARDWARE_INTERFACE_TYPE_VALUES_HPP_

#include <vector>

namespace hardware_interface
{
/// Constant defining position interface name
Expand Down
10 changes: 5 additions & 5 deletions joint_limits/include/joint_limits/simple_joint_limiter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,14 @@
namespace joint_limits
{
template <typename LimitsType>
class SimpleJointLimiter : public JointLimiterInterface<LimitsType>
class JointSaturationLimiter : public JointLimiterInterface<LimitsType>
{
public:
/** \brief Constructor */
JOINT_LIMITS_PUBLIC SimpleJointLimiter();
JOINT_LIMITS_PUBLIC JointSaturationLimiter();

/** \brief Destructor */
JOINT_LIMITS_PUBLIC ~SimpleJointLimiter();
JOINT_LIMITS_PUBLIC ~JointSaturationLimiter();

JOINT_LIMITS_PUBLIC bool on_enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
Expand All @@ -46,13 +46,13 @@ class SimpleJointLimiter : public JointLimiterInterface<LimitsType>
};

template <typename LimitsType>
SimpleJointLimiter<LimitsType>::SimpleJointLimiter() : JointLimiterInterface<LimitsType>()
JointSaturationLimiter<LimitsType>::JointSaturationLimiter() : JointLimiterInterface<LimitsType>()
{
clock_ = std::make_shared<rclcpp::Clock>(rclcpp::Clock(RCL_ROS_TIME));
}

template <typename LimitsType>
SimpleJointLimiter<LimitsType>::~SimpleJointLimiter()
JointSaturationLimiter<LimitsType>::~JointSaturationLimiter()
{
}

Expand Down
4 changes: 2 additions & 2 deletions joint_limits/joint_limiters.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<class_libraries>
<library path="simple_joint_limiter">
<class name="joint_limits/SimpleJointLimiter"
type="joint_limits::SimpleJointLimiter&lt;joint_limits::JointLimits&gt;"
<class name="joint_limits/JointSaturationLimiter"
type="joint_limits::JointSaturationLimiter&lt;joint_limits::JointLimits&gt;"
base_class_type="joint_limits::JointLimiterInterface&lt;joint_limits::JointLimits&gt;">
<description>
Simple joint limiter using clamping approach. Warning: clamping can cause discontinuities.
Expand Down
4 changes: 2 additions & 2 deletions joint_limits/src/simple_joint_limiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ constexpr double VALUE_CONSIDERED_ZERO = 1e-10;
namespace joint_limits
{
template <>
bool SimpleJointLimiter<JointLimits>::on_enforce(
bool JointSaturationLimiter<JointLimits>::on_enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states, const rclcpp::Duration & dt)
{
Expand Down Expand Up @@ -396,5 +396,5 @@ bool SimpleJointLimiter<JointLimits>::on_enforce(
#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(
joint_limits::SimpleJointLimiter<joint_limits::JointLimits>,
joint_limits::JointSaturationLimiter<joint_limits::JointLimits>,
joint_limits::JointLimiterInterface<joint_limits::JointLimits>)
44 changes: 23 additions & 21 deletions joint_limits/test/test_simple_joint_limiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,17 +16,17 @@

#include "test_simple_joint_limiter.hpp"

TEST_F(SimpleJointLimiterTest, when_loading_limiter_plugin_expect_loaded)
TEST_F(JointSaturationLimiterTest, when_loading_limiter_plugin_expect_loaded)
{
// Test SimpleJointLimiter loading
// Test JointSaturationLimiter loading
ASSERT_NO_THROW(
joint_limiter_ = std::unique_ptr<JointLimiter>(
joint_limiter_loader_.createUnmanagedInstance(joint_limiter_type_)));
ASSERT_NE(joint_limiter_, nullptr);
}

/* FIXME: currently init does not check if limit parameters exist for the requested joint
TEST_F(SimpleJointLimiterTest, when_joint_not_found_expect_init_fail)
TEST_F(JointSaturationLimiterTest, when_joint_not_found_expect_init_fail)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -40,7 +40,7 @@ TEST_F(SimpleJointLimiterTest, when_joint_not_found_expect_init_fail)
}
*/

TEST_F(SimpleJointLimiterTest, when_invalid_dt_expect_enforce_fail)
TEST_F(JointSaturationLimiterTest, when_invalid_dt_expect_enforce_fail)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -54,7 +54,7 @@ TEST_F(SimpleJointLimiterTest, when_invalid_dt_expect_enforce_fail)
}
}

TEST_F(SimpleJointLimiterTest, when_neigher_poscmd_nor_velcmd_expect_enforce_fail)
TEST_F(JointSaturationLimiterTest, when_neigher_poscmd_nor_velcmd_expect_enforce_fail)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -74,7 +74,7 @@ TEST_F(SimpleJointLimiterTest, when_neigher_poscmd_nor_velcmd_expect_enforce_fai
}
}

TEST_F(SimpleJointLimiterTest, when_no_posstate_expect_enforce_false)
TEST_F(JointSaturationLimiterTest, when_no_posstate_expect_enforce_false)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -89,13 +89,13 @@ TEST_F(SimpleJointLimiterTest, when_no_posstate_expect_enforce_false)
current_joint_states_.positions.clear();
ASSERT_FALSE(joint_limiter_->enforce(current_joint_states_, desired_joint_states_, period));

// also fail if out fo limits
// also fail if out of limits
desired_joint_states_.positions[0] = 20.0;
ASSERT_FALSE(joint_limiter_->enforce(current_joint_states_, desired_joint_states_, period));
}
}

TEST_F(SimpleJointLimiterTest, when_no_velstate_expect_limiting)
TEST_F(JointSaturationLimiterTest, when_no_velstate_expect_limiting)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -109,13 +109,13 @@ TEST_F(SimpleJointLimiterTest, when_no_velstate_expect_limiting)
// test no vel interface
current_joint_states_.velocities.clear();
ASSERT_FALSE(joint_limiter_->enforce(current_joint_states_, desired_joint_states_, period));
// also fail if out fo limits
// also fail if out of limits
desired_joint_states_.positions[0] = 20.0;
ASSERT_TRUE(joint_limiter_->enforce(current_joint_states_, desired_joint_states_, period));
}
}

TEST_F(SimpleJointLimiterTest, when_within_limits_expect_no_limits_applied)
TEST_F(JointSaturationLimiterTest, when_within_limits_expect_no_limits_applied)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -143,7 +143,7 @@ TEST_F(SimpleJointLimiterTest, when_within_limits_expect_no_limits_applied)
}
}

TEST_F(SimpleJointLimiterTest, when_posvel_leads_to_vel_exceeded_expect_limits_enforced)
TEST_F(JointSaturationLimiterTest, when_posvel_leads_to_vel_exceeded_expect_limits_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -187,7 +187,7 @@ TEST_F(SimpleJointLimiterTest, when_posvel_leads_to_vel_exceeded_expect_limits_e
}
}

TEST_F(SimpleJointLimiterTest, when_posonly_leads_to_vel_exceeded_expect_pos_acc_enforced)
TEST_F(JointSaturationLimiterTest, when_posonly_leads_to_vel_exceeded_expect_pos_acc_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -227,7 +227,7 @@ TEST_F(SimpleJointLimiterTest, when_posonly_leads_to_vel_exceeded_expect_pos_acc
}
}

TEST_F(SimpleJointLimiterTest, when_velonly_leads_to_vel_exceeded_expect_vel_acc_enforced)
TEST_F(JointSaturationLimiterTest, when_velonly_leads_to_vel_exceeded_expect_vel_acc_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -273,7 +273,7 @@ TEST_F(SimpleJointLimiterTest, when_velonly_leads_to_vel_exceeded_expect_vel_acc
}
}

TEST_F(SimpleJointLimiterTest, when_posonly_exceeded_expect_pos_enforced)
TEST_F(JointSaturationLimiterTest, when_posonly_exceeded_expect_pos_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -300,7 +300,7 @@ TEST_F(SimpleJointLimiterTest, when_posonly_exceeded_expect_pos_enforced)
}
}

TEST_F(SimpleJointLimiterTest, when_position_close_to_pos_limit_expect_deceleration_enforced)
TEST_F(JointSaturationLimiterTest, when_position_close_to_pos_limit_expect_deceleration_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -325,7 +325,9 @@ TEST_F(SimpleJointLimiterTest, when_position_close_to_pos_limit_expect_decelerat
{
auto previous_vel_request = desired_joint_states_.velocities[0];
// expect limits applied until the end stop
ASSERT_EQ(joint_limiter_->enforce(current_joint_states_, desired_joint_states_, period), expected_ret[i]);
ASSERT_EQ(
joint_limiter_->enforce(current_joint_states_, desired_joint_states_, period),
expected_ret[i]);

ASSERT_LE(
desired_joint_states_.velocities[0],
Expand All @@ -344,7 +346,7 @@ TEST_F(SimpleJointLimiterTest, when_position_close_to_pos_limit_expect_decelerat
}
}

TEST_F(SimpleJointLimiterTest, when_posvel_leads_to_acc_exceeded_expect_limits_enforced)
TEST_F(JointSaturationLimiterTest, when_posvel_leads_to_acc_exceeded_expect_limits_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -373,7 +375,7 @@ TEST_F(SimpleJointLimiterTest, when_posvel_leads_to_acc_exceeded_expect_limits_e
}
}

TEST_F(SimpleJointLimiterTest, when_posonly_leads_to_acc_exceeded_expect_limits_enforced)
TEST_F(JointSaturationLimiterTest, when_posonly_leads_to_acc_exceeded_expect_limits_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -402,7 +404,7 @@ TEST_F(SimpleJointLimiterTest, when_posonly_leads_to_acc_exceeded_expect_limits_
}
}

TEST_F(SimpleJointLimiterTest, when_velonly_leads_to_acc_exceeded_expect_limits_enforced)
TEST_F(JointSaturationLimiterTest, when_velonly_leads_to_acc_exceeded_expect_limits_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand All @@ -428,7 +430,7 @@ TEST_F(SimpleJointLimiterTest, when_velonly_leads_to_acc_exceeded_expect_limits_
}
}

TEST_F(SimpleJointLimiterTest, when_deceleration_exceeded_expect_dec_enforced)
TEST_F(JointSaturationLimiterTest, when_deceleration_exceeded_expect_dec_enforced)
{
SetupNode("simple_joint_limiter");
Load();
Expand Down Expand Up @@ -458,7 +460,7 @@ TEST_F(SimpleJointLimiterTest, when_deceleration_exceeded_expect_dec_enforced)
}
}

TEST_F(SimpleJointLimiterTest, when_deceleration_exceeded_with_no_maxdec_expect_acc_enforced)
TEST_F(JointSaturationLimiterTest, when_deceleration_exceeded_with_no_maxdec_expect_acc_enforced)
{
SetupNode("simple_joint_limiter_nodeclimit");
Load();
Expand Down
6 changes: 3 additions & 3 deletions joint_limits/test/test_simple_joint_limiter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ const double COMMON_THRESHOLD = 0.0011;

using JointLimiter = joint_limits::JointLimiterInterface<joint_limits::JointLimits>;

class SimpleJointLimiterTest : public ::testing::Test
class JointSaturationLimiterTest : public ::testing::Test
{
public:
void SetUp() override
Expand Down Expand Up @@ -77,8 +77,8 @@ class SimpleJointLimiterTest : public ::testing::Test
current_joint_states_.velocities[0] += desired_joint_states_.accelerations[0] * dt;
}

SimpleJointLimiterTest()
: joint_limiter_type_("joint_limits/SimpleJointLimiter"),
JointSaturationLimiterTest()
: joint_limiter_type_("joint_limits/JointSaturationLimiter"),
joint_limiter_loader_(
"joint_limits", "joint_limits::JointLimiterInterface<joint_limits::JointLimits>")
{
Expand Down

0 comments on commit bcf42aa

Please sign in to comment.