38#include <rclcpp/logger.hpp>
39#include <rclcpp/logging.hpp>
57 RCLCPP_ERROR_STREAM(getLogger(),
"joint_limit.max_deceleration MUST be negative!");
60 const auto& insertion_result{
container_.insert(std::pair<std::string, JointLimit>(joint_name, joint_limit)) };
61 if (!insertion_result.second)
63 RCLCPP_ERROR_STREAM(getLogger(),
"joint_limit for joint " << joint_name <<
" already contained.");
89 updateCommonLimit(limit.second, common_limit);
97 for (
const auto& joint_name : joint_names)
99 updateCommonLimit(
container_.at(joint_name), common_limit);
143void JointLimitsContainer::updateCommonLimit(
const JointLimit& joint_limit,
JointLimit& common_limit)
152 (!common_limit.
has_position_limits) ? min_position : std::max(common_limit.min_position, min_position);
154 (!common_limit.
has_position_limits) ? max_position : std::min(common_limit.max_position, max_position);
163 (!common_limit.
has_velocity_limits) ? max_velocity : std::min(common_limit.max_velocity, max_velocity);
JointLimit getLimit(const std::string &joint_name) const
getLimit get the limit for the given joint name
bool hasLimit(const std::string &joint_name) const
Check if there is a limit for a joint with the given name in this container.
std::map< std::string, JointLimit >::const_iterator end() const
ConstIterator to the underlying data structure.
std::map< std::string, JointLimit > container_
Actual container object containing the data.
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
std::map< std::string, JointLimit >::const_iterator begin() const
ConstIterator to the underlying data structure.
size_t getCount() const
Get Number of limits in the container.
bool empty() const
Returns whether the container is empty.
bool verifyVelocityLimit(const std::string &joint_name, double joint_velocity) const
verify velocity limit of single joint
bool verifyPositionLimit(const std::string &joint_name, double joint_position) const
verify position limit of single joint
bool verifyAccelerationLimit(const std::string &joint_name, double joint_acceleration) const
verify acceleration limit of single joint
bool verifyDecelerationLimit(const std::string &joint_name, double joint_acceleration) const
verify deceleration limit of single joint
JointLimit getCommonLimit() const
Returns joint limit fusion of all(position, velocity, acceleration, deceleration) limits for all join...
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
bool has_acceleration_limits
Extends joint_limits_interface::JointLimits with a deceleration parameter.
bool has_deceleration_limits
double max_deceleration
maximum deceleration MUST(!) be negative