moveit2
The MoveIt Motion Planning Framework for ROS 2.
utils.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
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 Willow Garage 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 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <moveit_msgs/msg/constraints.hpp>
40 #include <geometry_msgs/msg/point_stamped.hpp>
41 #include <geometry_msgs/msg/pose_stamped.hpp>
42 #include <geometry_msgs/msg/quaternion_stamped.hpp>
44 #include <limits>
45 
46 namespace XmlRpc
47 {
48 class XmlRpcValue;
49 }
50 
51 namespace kinematic_constraints
52 {
66 moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints& first,
67  const moveit_msgs::msg::Constraints& second);
68 
70 [[deprecated("Use moveit/utils/message_checks.h instead")]] bool isEmpty(const moveit_msgs::msg::Constraints& constr);
71 
72 std::size_t countIndividualConstraints(const moveit_msgs::msg::Constraints& constr);
73 
86 moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState& state,
87  const moveit::core::JointModelGroup* jmg, double tolerance_below,
88  double tolerance_above);
89 
101 moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState& state,
103  double tolerance = std::numeric_limits<double>::epsilon());
104 
120 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
121  const geometry_msgs::msg::PoseStamped& pose,
122  double tolerance_pos = 1e-3, double tolerance_angle = 1e-2);
123 
139 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
140  const geometry_msgs::msg::PoseStamped& pose,
141  const std::vector<double>& tolerance_pos,
142  const std::vector<double>& tolerance_angle);
143 
155 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
156  const geometry_msgs::msg::QuaternionStamped& quat,
157  double tolerance = 1e-2);
158 
172 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
173  const geometry_msgs::msg::Point& reference_point,
174  const geometry_msgs::msg::PointStamped& goal_point,
175  double tolerance = 1e-3);
176 
189 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
190  const geometry_msgs::msg::PointStamped& goal_point,
191  double tolerance = 1e-3);
192 
228 bool constructConstraints(const rclcpp::Node::SharedPtr& node, const std::string& constraints_param,
229  moveit_msgs::msg::Constraints& constraints);
230 
243 bool resolveConstraintFrames(const moveit::core::RobotState& state, moveit_msgs::msg::Constraints& constraints);
244 } // namespace kinematic_constraints
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Definition: utils.h:47
Representation and evaluation of kinematic constraints.
bool isEmpty(const moveit_msgs::msg::Constraints &constr)
Check if any constraints were specified.
Definition: utils.cpp:127
std::size_t countIndividualConstraints(const moveit_msgs::msg::Constraints &constr)
Definition: utils.cpp:132
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition: utils.cpp:144
bool resolveConstraintFrames(const moveit::core::RobotState &state, moveit_msgs::msg::Constraints &constraints)
Resolves frames used in constraints to links in the robot model.
bool constructConstraints(const rclcpp::Node::SharedPtr &node, const std::string &constraints_param, moveit_msgs::msg::Constraints &constraints)
extract constraint message from node parameters.
Definition: utils.cpp:521
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
Definition: utils.cpp:56