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

[JTC] Process tolerances sent with action goal #716

Merged
merged 32 commits into from
Jul 3, 2024
Merged
Show file tree
Hide file tree
Changes from 28 commits
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
c3acc81
Process tolerances sent with action goal
christophfroehlich Jul 24, 2023
c168ab3
Merge branch 'master' into jtc/action_tolerances
destogl Jul 24, 2023
0328c94
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Aug 3, 2023
880b87b
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Aug 15, 2023
57d6b32
Remove whitespaces
christophfroehlich Aug 15, 2023
ac0e871
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Aug 16, 2023
2c717d0
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Sep 12, 2023
31afb42
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Sep 14, 2023
16a8828
Fix merge conflict
christophfroehlich Sep 14, 2023
6a95acb
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Oct 9, 2023
4a3ba8b
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Nov 15, 2023
bf6d034
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Nov 19, 2023
22543a9
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Nov 28, 2023
fcaa1b9
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Dec 22, 2023
534746c
Fix format
christophfroehlich Dec 22, 2023
06400fa
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Jan 31, 2024
7e8fa9f
Merge branch 'master' into jtc/action_tolerances
bmagyar Jun 10, 2024
ae5efec
Apply suggestions from code review
christophfroehlich Jun 18, 2024
cb0e733
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Jun 18, 2024
597a2b8
Use ERASE_CONSTANT
christophfroehlich Jun 18, 2024
88666eb
Don't compare double with == -1
christophfroehlich Jun 18, 2024
7cc1244
Don't accept negative tolerances
christophfroehlich Jun 20, 2024
6d21d3a
Fix tests and improve error messages.
christophfroehlich Jun 20, 2024
a5d548c
Add a test for wrong joints too
christophfroehlich Jun 20, 2024
e48ca7b
Merge branch 'master' into jtc/action_tolerances
christophfroehlich Jun 20, 2024
4f1b755
Move tolerances tests to own file
christophfroehlich Jun 20, 2024
ec87dc0
Apply suggestions from code review
christophfroehlich Jun 21, 2024
54d279c
Remove duplicate check
christophfroehlich Jun 22, 2024
1a592ab
Pass std::vector instead of parameter struct
christophfroehlich Jun 24, 2024
2bdc0c2
Use a static child logger
christophfroehlich Jun 24, 2024
36ecdda
Remove test_tolerances_utils
christophfroehlich Jun 24, 2024
34ca300
Update docs
christophfroehlich Jun 24, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,10 @@ if(BUILD_TESTING)
target_link_libraries(test_trajectory joint_trajectory_controller)
target_compile_definitions(test_trajectory PRIVATE _USE_MATH_DEFINES)

ament_add_gmock(test_tolerances test/test_tolerances.cpp)
target_link_libraries(test_tolerances joint_trajectory_controller)
target_compile_definitions(test_tolerances PRIVATE _USE_MATH_DEFINES)

ament_add_gmock(test_trajectory_controller
test/test_trajectory_controller.cpp)
set_tests_properties(test_trajectory_controller PROPERTIES TIMEOUT 220)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
size_t joint_names_size, const std::vector<double> & vector_field,
const std::string & string_for_vector_field, size_t i, bool allow_empty) const;

// the tolerances from the node parameter
SegmentTolerances default_tolerances_;
// the tolerances used for the current goal
realtime_tools::RealtimeBuffer<SegmentTolerances> active_tolerances_;

JOINT_TRAJECTORY_CONTROLLER_PUBLIC
void preempt_active_goal();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,12 +30,14 @@
#ifndef JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
#define JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_

#include <limits>
#include <vector>

#include "control_msgs/action/follow_joint_trajectory.hpp"
#include "joint_trajectory_controller_parameters.hpp"

#include "rclcpp/node.hpp"
#include "rclcpp/time.hpp"

namespace joint_trajectory_controller
{
Expand Down Expand Up @@ -95,6 +97,8 @@ SegmentTolerances get_segment_tolerances(Params const & params)

SegmentTolerances tolerances;
tolerances.goal_time_tolerance = constraints.goal_time;
auto logger = rclcpp::get_logger("tolerance");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe might be better to have a logger object and initialize child tolerances here of the JTC node.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I haven't had a better idea as passing the JTC logger as argument to the get_segment_tolerances methods. There is no persistent class with a configuration/constructor method to pass the logger only once.

RCLCPP_DEBUG(logger, "goal_time %f", constraints.goal_time);

// State and goal state tolerances
tolerances.state_tolerance.resize(n_joints);
Expand All @@ -106,16 +110,219 @@ SegmentTolerances get_segment_tolerances(Params const & params)
tolerances.goal_state_tolerance[i].position = constraints.joints_map.at(joint).goal;
tolerances.goal_state_tolerance[i].velocity = constraints.stopped_velocity_tolerance;

auto logger = rclcpp::get_logger("tolerance");
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".trajectory").c_str(), tolerances.state_tolerance[i].position);
logger, "%s %f", (joint + ".trajectory.position").c_str(),
tolerances.state_tolerance[i].position);
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".goal").c_str(), tolerances.goal_state_tolerance[i].position);
logger, "%s %f", (joint + ".goal.position").c_str(),
tolerances.goal_state_tolerance[i].position);
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".goal.velocity").c_str(),
tolerances.goal_state_tolerance[i].velocity);
}

return tolerances;
}

/**
* \brief Populate trajectory segment tolerances using data from an action goal.
*
* \param default_tolerances The default tolerances to use if the action goal does not specify any.
* \param goal The new action goal
* \param params The ROS Parameters
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am not sure why do we need ROS parameters because the default tolerances should be added through parameters, isn't it?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The only field we need is the params.joints actually, I can change it to have a std::vector as argument instead?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

* \return Trajectory segment tolerances.
*/
SegmentTolerances get_segment_tolerances(
const SegmentTolerances & default_tolerances,
const control_msgs::action::FollowJointTrajectory::Goal & goal, const Params & params)
{
SegmentTolerances active_tolerances(default_tolerances);

active_tolerances.goal_time_tolerance = rclcpp::Duration(goal.goal_time_tolerance).seconds();
auto logger = rclcpp::get_logger("tolerance");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be great to have a static object for this, as mentioned above because we are creating objects all the time.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

see above

RCLCPP_DEBUG(logger, "%s %f", "goal_time", active_tolerances.goal_time_tolerance);

// from
// https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/JointTolerance.msg
// There are two special values for tolerances:
// * 0 - The tolerance is unspecified and will remain at whatever the default is
// * -1 - The tolerance is "erased".
// If there was a default, the joint will be allowed to move without restriction.
constexpr double ERASE_VALUE = -1.0;
auto is_erase_value = [](double value)
{ return fabs(value - ERASE_VALUE) < std::numeric_limits<float>::epsilon(); };

// State and goal state tolerances
for (auto joint_tol : goal.path_tolerance)
{
auto const joint = joint_tol.name;
// map joint names from goal to active_tolerances
auto it = std::find(params.joints.begin(), params.joints.end(), joint);
if (it == params.joints.end())
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.path_tolerance does not exist. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}
auto i = std::distance(params.joints.cbegin(), it);
if (joint_tol.position > 0.0)
{
active_tolerances.state_tolerance[i].position = joint_tol.position;
}
else if (is_erase_value(joint_tol.position))
{
active_tolerances.state_tolerance[i].position = 0.0;
}
else if (joint_tol.position < 0.0)
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.path_tolerance has a invalid position tolerance. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}

if (joint_tol.velocity > 0.0)
{
active_tolerances.state_tolerance[i].velocity = joint_tol.velocity;
}
else if (is_erase_value(joint_tol.velocity))
{
active_tolerances.state_tolerance[i].velocity = 0.0;
}
else if (joint_tol.velocity < 0.0)
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.path_tolerance has a invalid velocity tolerance. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}

if (joint_tol.acceleration > 0.0)
{
active_tolerances.state_tolerance[i].acceleration = joint_tol.acceleration;
}
else if (is_erase_value(joint_tol.acceleration))
{
active_tolerances.state_tolerance[i].acceleration = 0.0;
}
else if (joint_tol.acceleration < 0.0)
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.path_tolerance has a invalid acceleration tolerance. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}

RCLCPP_DEBUG(
logger, "%s %f", (joint + ".state_tolerance.position").c_str(),
active_tolerances.state_tolerance[i].position);
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".state_tolerance.velocity").c_str(),
active_tolerances.state_tolerance[i].velocity);
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".state_tolerance.acceleration").c_str(),
active_tolerances.state_tolerance[i].acceleration);
}
for (auto goal_tol : goal.goal_tolerance)
{
auto const joint = goal_tol.name;
// map joint names from goal to active_tolerances
auto it = std::find(params.joints.begin(), params.joints.end(), joint);
if (it == params.joints.end())
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.goal_tolerance does not exist. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}
auto i = std::distance(params.joints.cbegin(), it);
if (goal_tol.position > 0.0)
{
active_tolerances.goal_state_tolerance[i].position = goal_tol.position;
}
else if (is_erase_value(goal_tol.position))
{
active_tolerances.goal_state_tolerance[i].position = 0.0;
}
else if (goal_tol.position < 0.0)
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.goal_tolerance has a invalid position tolerance. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}

if (goal_tol.velocity > 0.0)
{
active_tolerances.goal_state_tolerance[i].velocity = goal_tol.velocity;
}
else if (is_erase_value(goal_tol.velocity))
{
active_tolerances.goal_state_tolerance[i].velocity = 0.0;
}
else if (goal_tol.velocity < 0.0)
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.goal_tolerance has a invalid velocity tolerance. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}

if (goal_tol.acceleration > 0.0)
{
active_tolerances.goal_state_tolerance[i].acceleration = goal_tol.acceleration;
}
else if (is_erase_value(goal_tol.acceleration))
{
active_tolerances.goal_state_tolerance[i].acceleration = 0.0;
}
else if (goal_tol.acceleration < 0.0)
{
RCLCPP_ERROR(
logger, "%s",
("joint '" + joint +
"' specified in goal.goal_tolerance has a invalid acceleration tolerance. "
"Using default tolerances.")
.c_str());
return default_tolerances;
}

RCLCPP_DEBUG(
logger, "%s %f", (joint + ".goal_state_tolerance.position").c_str(),
active_tolerances.goal_state_tolerance[i].position);
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".goal_state_tolerance.velocity").c_str(),
active_tolerances.goal_state_tolerance[i].velocity);
RCLCPP_DEBUG(
logger, "%s %f", (joint + ".goal_state_tolerance.acceleration").c_str(),
active_tolerances.goal_state_tolerance[i].acceleration);
}

return active_tolerances;
}

/**
* \param state_error State error to check.
* \param joint_idx Joint index for the state error
Expand Down
18 changes: 12 additions & 6 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,7 @@ controller_interface::return_type JointTrajectoryController::update(
bool outside_goal_tolerance = false;
bool within_goal_time = true;
const bool before_last_point = end_segment_itr != traj_external_point_ptr_->end();
auto active_tol = active_tolerances_.readFromRT();

// have we reached the end, are not holding position, and is a timeout configured?
// Check independently of other tolerances
Expand All @@ -224,23 +225,22 @@ controller_interface::return_type JointTrajectoryController::update(
if (
(before_last_point || first_sample) && *(rt_is_holding_.readFromRT()) == false &&
!check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.state_tolerance[index],
true /* show_errors */))
state_error_, index, active_tol->state_tolerance[index], true /* show_errors */))
{
tolerance_violated_while_moving = true;
}
// past the final point, check that we end up inside goal tolerance
if (
!before_last_point && *(rt_is_holding_.readFromRT()) == false &&
!check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.goal_state_tolerance[index],
false /* show_errors */))
state_error_, index, active_tol->goal_state_tolerance[index], false /* show_errors */))
{
outside_goal_tolerance = true;

if (default_tolerances_.goal_time_tolerance != 0.0)
if (active_tol->goal_time_tolerance != 0.0)
{
if (time_difference > default_tolerances_.goal_time_tolerance)
// if we exceed goal_time_tolerance set it to aborted
if (time_difference > active_tol->goal_time_tolerance)
{
within_goal_time = false;
// print once, goal will be aborted afterwards
Expand Down Expand Up @@ -782,6 +782,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
get_interface_list(params_.state_interfaces).c_str());

// parse remaining parameters
default_tolerances_ = get_segment_tolerances(params_);
active_tolerances_.initRT(default_tolerances_);
const std::string interpolation_string =
get_node()->get_parameter("interpolation_method").as_string();
interpolation_method_ = interpolation_methods::from_string(interpolation_string);
Expand Down Expand Up @@ -1173,6 +1175,10 @@ void JointTrajectoryController::goal_accepted_callback(
rt_goal->execute();
rt_active_goal_.writeFromNonRT(rt_goal);

// Update tolerances if specified in the goal
active_tolerances_.writeFromNonRT(
get_segment_tolerances(default_tolerances_, *(goal_handle->get_goal()), params_));

// Set smartpointer to expire for create_wall_timer to delete previous entry from timer list
goal_handle_timer_.reset();

Expand Down
Loading
Loading