Static Public Member Functions | Static Protected Member Functions | List of all members
pilz::JointLimitsAggregator Class Reference

Unifies the joint limits from the given joint models with joint limits from the parameter server. More...

#include <joint_limits_aggregator.h>

Static Public Member Functions

static JointLimitsContainer getAggregatedLimits (const ros::NodeHandle &nh, const std::vector< const moveit::core::JointModel * > &joint_models)
 Aggregates(combines) the joint limits from joint model and parameter server. The rules for the combination are: More...
 

Static Protected Member Functions

static void checkPositionBoundsThrowing (const moveit::core::JointModel *joint_model, const pilz_extensions::JointLimit &joint_limit)
 Checks if the position limits from the given joint_limit are stricter than the limits of the joint_model. Throws AggregationBoundsViolationException on violation. More...
 
static void checkVelocityBoundsThrowing (const moveit::core::JointModel *joint_model, const pilz_extensions::JointLimit &joint_limit)
 Checks if the velocity limit from the given joint_limit are stricter than the limit of the joint_model. Throws AggregationBoundsViolationException on violation. More...
 
static void updatePositionLimitFromJointModel (const moveit::core::JointModel *joint_model, pilz_extensions::JointLimit &joint_limit)
 Update the position limits with the ones from the joint_model. More...
 
static void updateVelocityLimitFromJointModel (const moveit::core::JointModel *joint_model, pilz_extensions::JointLimit &joint_limit)
 Update the velocity limit with the one from the joint_model. More...
 

Detailed Description

Unifies the joint limits from the given joint models with joint limits from the parameter server.

Does not support MultiDOF joints.

Definition at line 39 of file joint_limits_aggregator.h.

Member Function Documentation

void pilz::JointLimitsAggregator::checkPositionBoundsThrowing ( const moveit::core::JointModel joint_model,
const pilz_extensions::JointLimit joint_limit 
)
staticprotected

Checks if the position limits from the given joint_limit are stricter than the limits of the joint_model. Throws AggregationBoundsViolationException on violation.

Parameters
joint_modelThe joint_model
joint_limitThe joint_limit

Definition at line 137 of file joint_limits_aggregator.cpp.

void pilz::JointLimitsAggregator::checkVelocityBoundsThrowing ( const moveit::core::JointModel joint_model,
const pilz_extensions::JointLimit joint_limit 
)
staticprotected

Checks if the velocity limit from the given joint_limit are stricter than the limit of the joint_model. Throws AggregationBoundsViolationException on violation.

Parameters
joint_modelThe joint_model
joint_limitThe joint_limit

Definition at line 155 of file joint_limits_aggregator.cpp.

pilz::JointLimitsContainer pilz::JointLimitsAggregator::getAggregatedLimits ( const ros::NodeHandle nh,
const std::vector< const moveit::core::JointModel * > &  joint_models 
)
static

Aggregates(combines) the joint limits from joint model and parameter server. The rules for the combination are:

  1. Position and velocity limits on the parameter server must be stricter or equal if they are defined.
  2. Limits on the parameter server where the corresponding has_<position|velocity|acceleration|deceleration>_limits are „false“ are considered undefined(see point 1).
  3. Not all joints have to be limited by the parameter server. Selective limitation is possible.
  4. If max_deceleration is unset, it will be set to: max_deceleration = - max_acceleration.
    Note
    The acceleration/deceleration can only be set via the parameter server since they are not supported in the urdf so far.
    Parameters
    nhNode handle in whose namespace the joint limit parameters are expected.
    joint_modelsThe joint models
    Returns
    Container containing the limits

Definition at line 29 of file joint_limits_aggregator.cpp.

void pilz::JointLimitsAggregator::updatePositionLimitFromJointModel ( const moveit::core::JointModel joint_model,
pilz_extensions::JointLimit joint_limit 
)
staticprotected

Update the position limits with the ones from the joint_model.

If the joint model has no position limit, the value is unchanged.

Parameters
joint_modelThe joint model
joint_limitThe joint_limit to be filled with new values.

Definition at line 85 of file joint_limits_aggregator.cpp.

void pilz::JointLimitsAggregator::updateVelocityLimitFromJointModel ( const moveit::core::JointModel joint_model,
pilz_extensions::JointLimit joint_limit 
)
staticprotected

Update the velocity limit with the one from the joint_model.

If the joint model has no velocity limit, the value is unchanged.

Parameters
joint_modelThe joint model
joint_limitThe joint_limit to be filled with new values.

Definition at line 113 of file joint_limits_aggregator.cpp.


The documentation for this class was generated from the following files:


pilz_trajectory_generation
Author(s):
autogenerated on Mon Apr 6 2020 03:17:33