moveit2
The MoveIt Motion Planning Framework for ROS 2.
datatypes.hpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Los Alamos National Security, LLC
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 /* Title : datatypes.hpp
35  * Project : moveit_servo
36  * Created : 06/05/2023
37  * Author : Andy Zelenak, V Mohammed Ibrahim
38  *
39  * Description : The custom datatypes used by Moveit Servo.
40  */
41 
42 #pragma once
43 
44 #include <string>
45 #include <tf2_eigen/tf2_eigen.hpp>
46 #include <unordered_map>
47 
48 namespace moveit_servo
49 {
50 
51 enum class StatusCode : int8_t
52 {
53  INVALID = -1,
54  NO_WARNING = 0,
60  JOINT_BOUND = 6
61 };
62 
63 const std::unordered_map<StatusCode, std::string> SERVO_STATUS_CODE_MAP(
64  { { StatusCode::INVALID, "Invalid" },
65  { StatusCode::NO_WARNING, "No warnings" },
66  { StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY, "Moving closer to a singularity, decelerating" },
67  { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" },
68  { StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY, "Moving away from a singularity, decelerating" },
69  { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" },
70  { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" },
71  { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } });
72 
73 // The datatype that specifies the type of command that servo should expect.
74 enum class CommandType : int8_t
75 {
76  JOINT_JOG = 0,
77  TWIST = 1,
78  POSE = 2,
79 
80  // Range of allowed values used for validation.
81  MIN = JOINT_JOG,
82  MAX = POSE
83 };
84 
85 typedef std::pair<StatusCode, Eigen::VectorXd> JointDeltaResult;
86 
87 // The joint jog command, this will be vector of length equal to the number of joints of the robot.
89 {
90  std::vector<std::string> names;
91  std::vector<double> velocities;
92 };
93 
94 // The twist command, frame_id is the name of the frame in which the command is specified in.
95 // frame_id must always be specified.
97 {
98  std::string frame_id;
99  Eigen::Vector<double, 6> velocities;
100 };
101 
102 // The Pose command, frame_id is the name of the frame in which the command is specified in.
103 // frame_id must always be specified.
105 {
106  std::string frame_id;
107  Eigen::Isometry3d pose;
108 };
109 
110 // The generic input type for servo that can be JointJog, Twist or Pose.
111 typedef std::variant<JointJogCommand, TwistCommand, PoseCommand> ServoInput;
112 
113 // The output datatype of servo, this structure contains the names of the joints along with their positions, velocities and accelerations.
115 {
116  std::vector<std::string> joint_names;
117  Eigen::VectorXd positions, velocities, accelerations;
118  rclcpp::Time time_stamp;
119 
120  KinematicState(const int num_joints)
121  {
122  joint_names.resize(num_joints);
123  positions = Eigen::VectorXd::Zero(num_joints);
124  velocities = Eigen::VectorXd::Zero(num_joints);
125  accelerations = Eigen::VectorXd::Zero(num_joints);
126  }
127 
129  {
130  }
131 };
132 
133 // Mapping joint names and their position in the move group vector
134 typedef std::unordered_map<std::string, std::size_t> JointNameToMoveGroupIndexMap;
135 
136 } // namespace moveit_servo
std::variant< JointJogCommand, TwistCommand, PoseCommand > ServoInput
Definition: datatypes.hpp:111
std::pair< StatusCode, Eigen::VectorXd > JointDeltaResult
Definition: datatypes.hpp:85
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY, "Moving closer to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY, "Moving away from a singularity, decelerating" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } })
std::unordered_map< std::string, std::size_t > JointNameToMoveGroupIndexMap
Definition: datatypes.hpp:134
std::vector< std::string > names
Definition: datatypes.hpp:90
std::vector< double > velocities
Definition: datatypes.hpp:91
std::vector< std::string > joint_names
Definition: datatypes.hpp:116
KinematicState(const int num_joints)
Definition: datatypes.hpp:120
Eigen::VectorXd accelerations
Definition: datatypes.hpp:117
Eigen::VectorXd velocities
Definition: datatypes.hpp:117
Eigen::Isometry3d pose
Definition: datatypes.hpp:107
Eigen::Vector< double, 6 > velocities
Definition: datatypes.hpp:99