Skip to content

Commit

Permalink
Polish out some stuff using "GH Programming"
Browse files Browse the repository at this point in the history
Co-authored-by: AndyZe <[email protected]>
  • Loading branch information
destogl and AndyZe authored Apr 13, 2023
1 parent d7db070 commit 4054b04
Show file tree
Hide file tree
Showing 12 changed files with 19 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ constexpr char HW_IF_VELOCITY[] = "velocity";
constexpr char HW_IF_ACCELERATION[] = "acceleration";
/// Constant defining effort interface name
constexpr char HW_IF_EFFORT[] = "effort";

} // namespace hardware_interface

#endif // HARDWARE_INTERFACE__TYPES__HARDWARE_INTERFACE_TYPE_VALUES_HPP_
1 change: 0 additions & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
<depend>control_msgs</depend>
<depend>lifecycle_msgs</depend>
<depend>pluginlib</depend>
Expand Down
9 changes: 4 additions & 5 deletions joint_limits/include/joint_limits/joint_limiter_interface.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -49,7 +49,7 @@ class JointLimiterInterface
*
*/
JOINT_LIMITS_PUBLIC virtual bool init(
const std::vector<std::string> joint_names, const rclcpp::Node::SharedPtr & node,
const std::vector<std::string> & joint_names, const rclcpp::Node::SharedPtr & node,
const std::string & robot_description_topic = "/robot_description");

JOINT_LIMITS_PUBLIC virtual bool configure(
Expand All @@ -67,7 +67,7 @@ class JointLimiterInterface
return on_enforce(current_joint_states, desired_joint_states, dt);
}

// TODO(destogl): Make those protected?
protected:
// Methods that each limiter implementation has to implement
JOINT_LIMITS_PUBLIC virtual bool on_init() { return true; }

Expand All @@ -78,11 +78,10 @@ class JointLimiterInterface
}

JOINT_LIMITS_PUBLIC virtual bool on_enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states,
const rclcpp::Duration & dt) = 0;

protected:
size_t number_of_joints_;
std::vector<std::string> joint_names_;
std::vector<LimitsType> joint_limits_;
Expand Down
6 changes: 3 additions & 3 deletions joint_limits/include/joint_limits/simple_joint_limiter.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2021, PickNik Inc.
// Copyright (c) 2023, PickNik Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

/// \author Denis Stogl
/// \author Dr. Denis Stogl

#ifndef JOINT_LIMITS__SIMPLE_JOINT_LIMITER_HPP_
#define JOINT_LIMITS__SIMPLE_JOINT_LIMITER_HPP_
Expand All @@ -31,7 +31,7 @@ class SimpleJointLimiter : public JointLimiterInterface<JointLimits>
JOINT_LIMITS_PUBLIC SimpleJointLimiter();

JOINT_LIMITS_PUBLIC bool on_enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states,
const rclcpp::Duration & dt) override;
};
Expand Down
2 changes: 1 addition & 1 deletion joint_limits/include/joint_limits/visibility_control.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion joint_limits/joint_limiters.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
type="joint_limits::SimpleJointLimiter&lt;joint_limits::JointLimits&gt;"
base_class_type="joint_limits::JointLimiterInterface&lt;joint_limits::JointLimits&gt;">
<description>
Simple joint limiter using clamping approach.
Simple joint limiter using clamping approach. Warning: clamping can cause discontinuities.
</description>
</class>
</library>
2 changes: 1 addition & 1 deletion joint_limits/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<package format="3">
<name>joint_limits</name>
<version>3.12.0</version>
<description>Package for with interfaces for handling of joint limits for use in controllers or in hardware. The package also implements a simple, default joint limit strategy by clamping the values.</description>
<description>Package with interfaces for handling of joint limits in controllers or in hardware. The package also implements a simple, default joint limit strategy by clamping the values.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
6 changes: 3 additions & 3 deletions joint_limits/src/joint_limiter_interface.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

/// \author Denis Stogl
/// \author Dr. Denis Stogl

#include "joint_limits/joint_limiter_interface.hpp"

Expand All @@ -39,7 +39,7 @@ bool JointLimiterInterface<JointLimits>::init(
// TODO(destogl): get limits from URDF

// Initialize and get joint limits from parameter server
for (auto i = 0ul; i < number_of_joints_; ++i)
for (size_t i = 0; i < number_of_joints_; ++i)
{
if (!declare_parameters(joint_names[i], node))
{
Expand Down
9 changes: 4 additions & 5 deletions joint_limits/src/simple_joint_limiter.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2021, PickNik Inc.
// Copyright (c) 2023, PickNik Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -62,7 +62,7 @@ bool SimpleJointLimiter<JointLimits>::on_enforce(

bool position_limit_triggered = false;

for (auto index = 0u; index < num_joints; ++index)
for (size_t index = 0; index < num_joints; ++index)
{
desired_pos[index] = desired_joint_states.positions[index];

Expand Down Expand Up @@ -143,8 +143,7 @@ bool SimpleJointLimiter<JointLimits>::on_enforce(

if (position_limit_triggered)
{
std::ostringstream ostr;
for (auto index = 0u; index < num_joints; ++index)
for (size_t index = 0; index < num_joints; ++index)
{
// Compute accel to stop
// Here we aren't explicitly maximally decelerating, but for joints near their limits this
Expand All @@ -171,7 +170,7 @@ bool SimpleJointLimiter<JointLimits>::on_enforce(
pos_limit_trig_jnts.begin(), pos_limit_trig_jnts.end(), [](bool trig) { return trig; }) > 0)
{
std::ostringstream ostr;
for (auto index = 0u; index < num_joints; ++index)
for (size_t index = 0; index < num_joints; ++index)
{
if (pos_limit_trig_jnts[index]) ostr << joint_names_[index] << " ";
}
Expand Down
4 changes: 2 additions & 2 deletions joint_limits/test/test_simple_joint_limiter.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

/// \author Denis Stogl
/// \author Dr. Denis Stogl

#include <gmock/gmock.h>

Expand Down
1 change: 0 additions & 1 deletion joint_limits_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@ find_package(ament_cmake REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(rclcpp REQUIRED)
find_package(urdf REQUIRED)
find_package(backward_ros REQUIRED)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
Expand Down
1 change: 0 additions & 1 deletion joint_limits_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

<depend>rclcpp</depend>
<depend>urdf</depend>
<depend>backward_ros</depend>

<build_depend>hardware_interface</build_depend>

Expand Down

0 comments on commit 4054b04

Please sign in to comment.