36 #include <rclcpp/logger.hpp>
55 return has_joint_limits_;
60 has_joint_limits_ =
true;
72 "Pilz Cartesian Limits - Max Trans Vel : %f, Max Trans Acc : %f, Max Trans Dec : %f, Max Rot Vel : %f",
73 cartesian_limits_.max_trans_vel, cartesian_limits_.max_trans_acc, cartesian_limits_.max_trans_dec,
74 cartesian_limits_.max_rot_vel);
79 has_cartesian_limits_ =
true;
80 cartesian_limits_ = cartesian_limits;
85 return cartesian_limits_;
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
void printCartesianLimits() const
Prints the cartesian limits set by user. Default values for limits are 0.0.
void setCartesianLimits(cartesian_limits::Params &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
const cartesian_limits::Params & getCartesianLimits() const
Return the cartesian limits.
bool hasJointLimits() const
Return if this LimitsContainer has defined joint limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.