motion_primitives.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2025 Universal Robots A/S
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 //
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 //
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 //
14 // * Neither the name of the {copyright_holder} nor the names of its
15 // contributors may be used to endorse or promote products derived from
16 // this software without specific prior written permission.
17 //
18 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 // POSSIBILITY OF SUCH DAMAGE.
29 // -- END LICENSE BLOCK ------------------------------------------------
30 
31 #ifndef UR_CLIENT_LIBRARY_MOTION_PRIMITIVES_H_INCLUDED
32 #define UR_CLIENT_LIBRARY_MOTION_PRIMITIVES_H_INCLUDED
33 
34 #include <chrono>
35 #include <optional>
37 
38 namespace urcl
39 {
40 namespace control
41 {
42 
43 enum class MotionType : uint8_t
44 {
45  MOVEJ = 0,
46  MOVEL = 1,
47  MOVEP = 2,
48  MOVEC = 3,
49  SPLINE = 51,
50  UNKNOWN = 255
51 };
52 
56 enum class TrajectorySplineType : int32_t
57 {
58  SPLINE_CUBIC = 1,
59  SPLINE_QUINTIC = 2
60 };
61 
63 {
65  std::chrono::duration<double> duration;
66  double acceleration;
67  double velocity;
68  double blend_radius;
69 };
70 
72 {
73  MoveJPrimitive(const urcl::vector6d_t& target, const double blend_radius = 0,
74  const std::chrono::duration<double> duration = std::chrono::milliseconds(0),
75  const double acceleration = 1.4, const double velocity = 1.04)
76  {
79  this->duration = duration;
80  this->acceleration = acceleration;
81  this->velocity = velocity;
82  this->blend_radius = blend_radius;
83  }
84 
86 };
87 
89 {
90  MoveLPrimitive(const urcl::Pose& target, const double blend_radius = 0,
91  const std::chrono::duration<double> duration = std::chrono::milliseconds(0),
92  const double acceleration = 1.4, const double velocity = 1.04)
93  {
95  target_pose = target;
96  this->duration = duration;
97  this->acceleration = acceleration;
98  this->velocity = velocity;
99  this->blend_radius = blend_radius;
100  }
101 
103 };
104 
106 {
107  MovePPrimitive(const urcl::Pose& target, const double blend_radius = 0, const double acceleration = 1.4,
108  const double velocity = 1.04)
109  {
111  target_pose = target;
112  this->acceleration = acceleration;
113  this->velocity = velocity;
114  this->blend_radius = blend_radius;
115  }
117 };
118 
120 {
121  MoveCPrimitive(const urcl::Pose& via_point, const urcl::Pose& target, const double blend_radius = 0,
122  const double acceleration = 1.4, const double velocity = 1.04, const int32_t mode = 0)
123  {
125  via_point_pose = via_point;
126  target_pose = target;
127  this->acceleration = acceleration;
128  this->velocity = velocity;
129  this->blend_radius = blend_radius;
130  this->mode = mode;
131  }
134  int32_t mode = 0;
135 };
136 
138 {
140  const std::optional<vector6d_t>& target_accelerations,
141  const std::chrono::duration<double> duration = std::chrono::milliseconds(0))
142  {
144  this->target_positions = target_positions;
145  this->target_velocities = target_velocities;
146  this->target_accelerations = target_accelerations;
147  this->duration = duration;
148  }
149 
151  {
152  if (target_accelerations.has_value())
153  {
155  }
156  else
157  {
159  }
160  }
163  std::optional<vector6d_t> target_accelerations;
164 };
165 } // namespace control
166 } // namespace urcl
167 #endif // UR_CLIENT_LIBRARY_MOTION_PRIMITIVES_H_INCLUDED
urcl::control::MotionPrimitive::velocity
double velocity
Definition: motion_primitives.h:67
urcl::control::MoveCPrimitive::via_point_pose
urcl::Pose via_point_pose
Definition: motion_primitives.h:132
urcl::control::MoveLPrimitive::MoveLPrimitive
MoveLPrimitive(const urcl::Pose &target, const double blend_radius=0, const std::chrono::duration< double > duration=std::chrono::milliseconds(0), const double acceleration=1.4, const double velocity=1.04)
Definition: motion_primitives.h:90
types.h
urcl::control::MoveCPrimitive::mode
int32_t mode
Definition: motion_primitives.h:134
urcl::control::MotionType::MOVEP
@ MOVEP
urcl
Definition: bin_parser.h:36
urcl::control::MovePPrimitive::MovePPrimitive
MovePPrimitive(const urcl::Pose &target, const double blend_radius=0, const double acceleration=1.4, const double velocity=1.04)
Definition: motion_primitives.h:107
urcl::control::MotionType::SPLINE
@ SPLINE
urcl::control::SplinePrimitive
Definition: motion_primitives.h:137
urcl::control::MoveLPrimitive
Definition: motion_primitives.h:88
urcl::control::SplinePrimitive::target_velocities
vector6d_t target_velocities
Definition: motion_primitives.h:162
urcl::control::SplinePrimitive::getSplineType
control::TrajectorySplineType getSplineType() const
Definition: motion_primitives.h:150
urcl::control::MotionType::MOVEL
@ MOVEL
urcl::control::MoveJPrimitive
Definition: motion_primitives.h:71
urcl::vector6d_t
std::array< double, 6 > vector6d_t
Definition: types.h:30
urcl::control::MoveCPrimitive
Definition: motion_primitives.h:119
urcl::control::SplinePrimitive::target_positions
vector6d_t target_positions
Definition: motion_primitives.h:161
urcl::control::MovePPrimitive::target_pose
urcl::Pose target_pose
Definition: motion_primitives.h:116
urcl::control::TrajectorySplineType
TrajectorySplineType
Definition: motion_primitives.h:56
urcl::control::TrajectorySplineType::SPLINE_CUBIC
@ SPLINE_CUBIC
urcl::control::MoveCPrimitive::MoveCPrimitive
MoveCPrimitive(const urcl::Pose &via_point, const urcl::Pose &target, const double blend_radius=0, const double acceleration=1.4, const double velocity=1.04, const int32_t mode=0)
Definition: motion_primitives.h:121
urcl::control::MoveCPrimitive::target_pose
urcl::Pose target_pose
Definition: motion_primitives.h:133
urcl::control::TrajectorySplineType::SPLINE_QUINTIC
@ SPLINE_QUINTIC
urcl::control::MotionPrimitive::acceleration
double acceleration
Definition: motion_primitives.h:66
urcl::control::MotionType::MOVEJ
@ MOVEJ
urcl::Pose
Definition: types.h:34
urcl::control::MotionPrimitive::type
MotionType type
Definition: motion_primitives.h:64
urcl::control::MotionPrimitive::duration
std::chrono::duration< double > duration
Definition: motion_primitives.h:65
urcl::control::MoveJPrimitive::MoveJPrimitive
MoveJPrimitive(const urcl::vector6d_t &target, const double blend_radius=0, const std::chrono::duration< double > duration=std::chrono::milliseconds(0), const double acceleration=1.4, const double velocity=1.04)
Definition: motion_primitives.h:73
urcl::control::MovePPrimitive
Definition: motion_primitives.h:105
urcl::control::MoveLPrimitive::target_pose
urcl::Pose target_pose
Definition: motion_primitives.h:102
urcl::control::SplinePrimitive::SplinePrimitive
SplinePrimitive(const urcl::vector6d_t &target_positions, const vector6d_t &target_velocities, const std::optional< vector6d_t > &target_accelerations, const std::chrono::duration< double > duration=std::chrono::milliseconds(0))
Definition: motion_primitives.h:139
urcl::control::MotionType
MotionType
Definition: motion_primitives.h:43
urcl::control::MotionType::MOVEC
@ MOVEC
urcl::control::MotionType::UNKNOWN
@ UNKNOWN
urcl::control::MotionPrimitive::blend_radius
double blend_radius
Definition: motion_primitives.h:68
urcl::control::MoveJPrimitive::target_joint_configuration
urcl::vector6d_t target_joint_configuration
Definition: motion_primitives.h:85
urcl::control::SplinePrimitive::target_accelerations
std::optional< vector6d_t > target_accelerations
Definition: motion_primitives.h:163
urcl::control::MotionPrimitive
Definition: motion_primitives.h:62


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Mon May 26 2025 02:35:58