cartesian_trajectory.cpp
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2021 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //-----------------------------------------------------------------------------
25 //-----------------------------------------------------------------------------
26 
29 
31 {
33 {
35 }
36 
37 CartesianTrajectory::CartesianTrajectory(const cartesian_control_msgs::CartesianTrajectory& ros_trajectory)
38 {
39  if (!init(ros_trajectory))
40  {
41  throw std::invalid_argument("Trajectory not valid");
42  };
43 }
44 
45 bool CartesianTrajectory::init(const cartesian_control_msgs::CartesianTrajectory& ros_trajectory)
46 {
47  trajectory_data_.clear();
48  bool sign_flipped = false;
49 
50  // Loop through the waypoints and build trajectory segments from each two
51  // neighboring pairs.
52  for (auto i = ros_trajectory.points.begin(); std::next(i) < ros_trajectory.points.end(); ++i)
53  {
54  // Waypoints' time from start must strictly increase
55  if (i->time_from_start.toSec() >= std::next(i)->time_from_start.toSec())
56  {
57  return false;
58  }
59 
60  CartesianState state = CartesianState(*i);
61  CartesianState next_state = CartesianState(*std::next(i));
62 
63  if (sign_flipped)
64  {
65  state.q = state.q.conjugate();
66  state.q.w() = state.q.w() * -1;
67  sign_flipped = false;
68  }
69 
70  // If the dot product is negative, we change the sign of the orientation to not travel the long way around
71  double dot_product = state.q.dot(next_state.q);
72  if (dot_product < 0.0)
73  {
74  next_state.q = next_state.q.conjugate();
75  next_state.q.w() = next_state.q.w() * -1;
76  sign_flipped = true;
77  }
78  CartesianTrajectorySegment s(i->time_from_start.toSec(), state, std::next(i)->time_from_start.toSec(), next_state);
79  trajectory_data_.push_back(s);
80  }
81  return true;
82 }
83 } // namespace ros_controllers_cartesian
ros_controllers_cartesian
Definition: cartesian_state.h:29
s
XmlRpcServer s
trajectory_interface::sample
Trajectory::const_iterator sample(const Trajectory &trajectory, const typename Trajectory::value_type::Time &time, typename Trajectory::value_type::State &state)
ros_controllers_cartesian::CartesianTrajectory::init
bool init(const cartesian_control_msgs::CartesianTrajectory &ros_trajectory)
Initialize from ROS message.
Definition: cartesian_trajectory.cpp:45
ros_controllers_cartesian::CartesianState::q
Eigen::Quaterniond q
rotation
Definition: cartesian_state.h:98
ros_controllers_cartesian::CartesianState
Cartesian state with pose, velocity and acceleration.
Definition: cartesian_state.h:38
trajectory_interface.h
cartesian_trajectory.h
ros_controllers_cartesian::CartesianTrajectory::sample
void sample(const CartesianTrajectorySegment::Time &time, CartesianState &state)
Sample a trajectory at a specified time.
Definition: cartesian_trajectory.cpp:32
ros_controllers_cartesian::CartesianTrajectorySegment
Cartesian segment between two trajectory waypoints.
Definition: cartesian_trajectory_segment.h:63
ros_controllers_cartesian::CartesianTrajectory::trajectory_data_
std::vector< CartesianTrajectorySegment > trajectory_data_
Definition: cartesian_trajectory.h:94
ros_controllers_cartesian::CartesianTrajectorySegment::Time
QuinticSplineSegment::Time Time
Relative time in seconds.
Definition: cartesian_trajectory_segment.h:69
ros_controllers_cartesian::CartesianTrajectory::CartesianTrajectory
CartesianTrajectory()=default


cartesian_trajectory_interpolation
Author(s):
autogenerated on Tue Oct 15 2024 02:09:14