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/Constraints.h>
40 #include <geometry_msgs/PointStamped.h>
41 #include <geometry_msgs/PoseStamped.h>
42 #include <geometry_msgs/QuaternionStamped.h>
44 #include <limits>
45 
46 namespace XmlRpc
47 {
48 class XmlRpcValue;
49 }
50 
51 namespace kinematic_constraints
52 {
66 moveit_msgs::Constraints mergeConstraints(const moveit_msgs::Constraints& first, const moveit_msgs::Constraints& second);
67 
69 [[deprecated("Use moveit/utils/message_checks.h instead")]] bool isEmpty(const moveit_msgs::Constraints& constr);
70 
71 std::size_t countIndividualConstraints(const moveit_msgs::Constraints& constr);
72 
85 moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState& state,
86  const moveit::core::JointModelGroup* jmg, double tolerance_below,
87  double tolerance_above);
88 
100 moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState& state,
102  double tolerance = std::numeric_limits<double>::epsilon());
103 
119 moveit_msgs::Constraints constructGoalConstraints(const std::string& link_name, const geometry_msgs::PoseStamped& pose,
120  double tolerance_pos = 1e-3, double tolerance_angle = 1e-2);
121 
137 moveit_msgs::Constraints constructGoalConstraints(const std::string& link_name, const geometry_msgs::PoseStamped& pose,
138  const std::vector<double>& tolerance_pos,
139  const std::vector<double>& tolerance_angle);
140 
152 moveit_msgs::Constraints constructGoalConstraints(const std::string& link_name,
153  const geometry_msgs::QuaternionStamped& quat,
154  double tolerance = 1e-2);
155 
169 moveit_msgs::Constraints constructGoalConstraints(const std::string& link_name,
170  const geometry_msgs::Point& reference_point,
171  const geometry_msgs::PointStamped& goal_point,
172  double tolerance = 1e-3);
173 
186 moveit_msgs::Constraints constructGoalConstraints(const std::string& link_name,
187  const geometry_msgs::PointStamped& goal_point,
188  double tolerance = 1e-3);
189 
201 bool constructConstraints(XmlRpc::XmlRpcValue& params, moveit_msgs::Constraints& constraints);
202 
215 bool resolveConstraintFrames(const moveit::core::RobotState& state, moveit_msgs::Constraints& constraints);
216 } // namespace kinematic_constraints
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
kinematic_constraints::resolveConstraintFrames
bool resolveConstraintFrames(const moveit::core::RobotState &state, moveit_msgs::Constraints &constraints)
Resolves frames used in constraints to links in the robot model.
Definition: utils.cpp:533
kinematic_constraints
Representation and evaluation of kinematic constraints.
Definition: kinematic_constraint.h:52
kinematic_constraints::constructConstraints
bool constructConstraints(XmlRpc::XmlRpcValue &params, moveit_msgs::Constraints &constraints)
extract constraint message from XmlRpc node.
Definition: utils.cpp:524
XmlRpc
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
kinematic_constraints::mergeConstraints
moveit_msgs::Constraints mergeConstraints(const moveit_msgs::Constraints &first, const moveit_msgs::Constraints &second)
Merge two sets of constraints into one.
Definition: utils.cpp:50
kinematic_constraints::isEmpty
bool isEmpty(const moveit_msgs::Constraints &constr)
Check if any constraints were specified.
Definition: utils.cpp:119
kinematic_constraints::countIndividualConstraints
std::size_t countIndividualConstraints(const moveit_msgs::Constraints &constr)
Definition: utils.cpp:124
kinematic_constraints::constructGoalConstraints
moveit_msgs::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:136
robot_state.h
XmlRpc::XmlRpcValue


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15