38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
44 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner.joint_limits_container");
50 RCLCPP_ERROR_STREAM(LOGGER,
"joint_limit.max_deceleration MUST be negative!");
53 const auto& insertion_result{
container_.insert(std::pair<std::string, JointLimit>(joint_name, joint_limit)) };
54 if (!insertion_result.second)
56 RCLCPP_ERROR_STREAM(LOGGER,
"joint_limit for joint " << joint_name <<
" already contained.");
82 updateCommonLimit(limit.second, common_limit);
90 for (
const auto& joint_name : joint_names)
92 updateCommonLimit(
container_.at(joint_name), common_limit);
114 return (!(
hasLimit(joint_name) &&
getLimit(joint_name).has_velocity_limits &&
115 fabs(joint_velocity) >
getLimit(joint_name).max_velocity));
120 return (!(
hasLimit(joint_name) &&
getLimit(joint_name).has_position_limits &&
121 (joint_position <
getLimit(joint_name).min_position || joint_position >
getLimit(joint_name).max_position)));
124 void JointLimitsContainer::updateCommonLimit(
const JointLimit& joint_limit,
JointLimit& common_limit)
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.
bool verifyVelocityLimit(const std::string &joint_name, const double &joint_velocity) const
verify position limit of single joint
bool verifyPositionLimit(const std::string &joint_name, const double &joint_position) const
verify position limit of single joint
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.
JointLimit getCommonLimit() const
Returns joint limit fusion of all(position, velocity, acceleration, deceleration) limits for all join...
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