moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
message_checks.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2019, Universitaet Hamburg.
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 Hamburg University 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: Michael Goerner */
36
38
39namespace moveit
40{
41namespace core
42{
43bool isEmpty(const moveit_msgs::msg::PlanningScene& msg)
44{
45 return msg.name.empty() && msg.fixed_frame_transforms.empty() && msg.allowed_collision_matrix.entry_names.empty() &&
46 msg.link_padding.empty() && msg.link_scale.empty() && isEmpty(msg.robot_state) && isEmpty(msg.world);
47}
48
49bool isEmpty(const moveit_msgs::msg::PlanningSceneWorld& msg)
50{
51 return msg.collision_objects.empty() && msg.octomap.octomap.data.empty();
52}
53
54bool isEmpty(const moveit_msgs::msg::RobotState& msg)
55{
56 // a state is empty if it includes no information and it is a diff; if the state is not a diff, then the implicit
57 // information is
58 // that the set of attached bodies is empty, so they must be cleared from the state to be updated
59 return static_cast<bool>(msg.is_diff) && msg.multi_dof_joint_state.joint_names.empty() &&
60 msg.joint_state.name.empty() && msg.attached_collision_objects.empty() && msg.joint_state.position.empty() &&
61 msg.joint_state.velocity.empty() && msg.joint_state.effort.empty() &&
62 msg.multi_dof_joint_state.transforms.empty() && msg.multi_dof_joint_state.twist.empty() &&
63 msg.multi_dof_joint_state.wrench.empty();
64}
65
66bool isEmpty(const moveit_msgs::msg::Constraints& constr)
67{
68 return constr.position_constraints.empty() && constr.orientation_constraints.empty() &&
69 constr.visibility_constraints.empty() && constr.joint_constraints.empty();
70}
71
72bool isEmpty(const geometry_msgs::msg::Quaternion& msg)
73{
74 return msg.x == 0.0 && msg.y == 0.0 && msg.z == 0.0 && msg.w == 1.0;
75}
76
77bool isEmpty(const geometry_msgs::msg::Pose& msg)
78{
79 return msg.position.x == 0.0 && msg.position.y == 0.0 && msg.position.z == 0.0 && isEmpty(msg.orientation);
80}
81
82} // namespace core
83} // namespace moveit
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
Main namespace for MoveIt.
Definition exceptions.h:43