moveit2
The MoveIt Motion Planning Framework for ROS 2.
limits_container.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 #include <rclcpp/logger.hpp>
37 #include <moveit/utils/logger.hpp>
38 
40 {
41 namespace
42 {
43 rclcpp::Logger getLogger()
44 {
45  return moveit::getLogger("moveit.planners.pilz.limits_container");
46 }
47 } // namespace
48 
49 LimitsContainer::LimitsContainer() : has_joint_limits_(false), has_cartesian_limits_(false)
50 {
51 }
52 
54 {
55  return has_joint_limits_;
56 }
57 
59 {
60  has_joint_limits_ = true;
61  joint_limits_ = joint_limits;
62 }
63 
65 {
66  return joint_limits_;
67 }
68 
70 {
71  RCLCPP_DEBUG(getLogger(),
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);
75 }
76 
77 void LimitsContainer::setCartesianLimits(cartesian_limits::Params& cartesian_limits)
78 {
79  has_cartesian_limits_ = true;
80  cartesian_limits_ = cartesian_limits;
81 }
82 
83 const cartesian_limits::Params& LimitsContainer::getCartesianLimits() const
84 {
85  return cartesian_limits_;
86 }
87 
88 } // namespace pilz_industrial_motion_planner
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(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79