trajectory_interface.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
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 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics S.L. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #pragma once
31 
32 
33 #include <algorithm>
34 #include <iterator>
35 #include <vector>
36 
37 // Things to generalize:
38 // - State specification: What values (pos, vel, acc, ...), and their dimension (4 for quats, 1 for scalars)
39 // - State might be different for derivatives: Quat == 4, ang vel == 3: Solve doing w=[w0, w1, w2, 0]
40 // - Sample state vs. sample pos and derivatives separately
41 // - Manage and find active segments of heretogeneous types
42 
43 // NOTES:
44 // - Segments in original implementation are an open interval on the start time. We are making them closed
45 // - If an action goal superceeds another and the new trajectory starts in the future, until that time no constraint
46 // enforcement will take place. Odd.
47 
48 namespace trajectory_interface
49 {
50 
51 namespace internal
52 {
53 
54 // NOTE: Implement as a lambda expression when C++11 becomes mainstream
55 template<class Time, class Segment>
56 inline bool isBeforeSegment(const Time& time, const Segment& segment)
57 {
58  return time < segment.startTime();
59 }
60 
61 } // namespace
62 
79 template<class TrajectoryIterator, class Time>
80 inline TrajectoryIterator findSegment(TrajectoryIterator first, TrajectoryIterator last, const Time& time)
81 {
82  typedef typename std::iterator_traits<TrajectoryIterator>::value_type Segment;
83  return (first == last || internal::isBeforeSegment(time, *first))
84  ? last // Optimization when time preceeds all segments, or when an empty range is passed
85  : --std::upper_bound(first, last, time, internal::isBeforeSegment<Time, Segment>); // Notice decrement operator
86 }
87 
98 template<class Trajectory, class Time>
99 inline typename Trajectory::const_iterator findSegment(const Trajectory& trajectory, const Time& time)
100 {
101  return findSegment(trajectory.begin(), trajectory.end(), time);
102 }
103 
111 template<class Trajectory, class Time>
112 inline typename Trajectory::iterator findSegment(Trajectory& trajectory, const Time& time)
113 {
114  return findSegment(trajectory.begin(), trajectory.end(), time);
115 }
116 
137 template<class Trajectory>
138 inline typename Trajectory::const_iterator sample(const Trajectory& trajectory,
139  const typename Trajectory::value_type::Time& time,
140  typename Trajectory::value_type::State& state)
141 {
142  typename Trajectory::const_iterator it = findSegment(trajectory, time);
143  if (it != trajectory.end())
144  {
145  it->sample(time, state); // Segment found at specified time
146  }
147  else if (!trajectory.empty())
148  {
149  trajectory.front().sample(time, state); // Specified time preceeds trajectory start time
150  }
151  return it;
152 }
153 
154 } // namespace
trajectory_interface::internal::isBeforeSegment
bool isBeforeSegment(const Time &time, const Segment &segment)
Definition: trajectory_interface.h:56
trajectory_interface
Definition: pos_vel_acc_state.h:36
trajectory_interface::sample
Trajectory::const_iterator sample(const Trajectory &trajectory, const typename Trajectory::value_type::Time &time, typename Trajectory::value_type::State &state)
Sample a trajectory at a specified time.
Definition: trajectory_interface.h:138
trajectory_interface::findSegment
TrajectoryIterator findSegment(TrajectoryIterator first, TrajectoryIterator last, const Time &time)
Find an iterator to the segment containing a specified time.
Definition: trajectory_interface.h:80


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Nov 3 2023 02:18:24