stop_trajectory_builder.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 // Copyright (c) 2008, Willow Garage, Inc.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of PAL Robotics S.L. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 #ifndef STOP_TRAJECTORY_BUILDER_H
29 #define STOP_TRAJECTORY_BUILDER_H
30 
31 #include <vector>
32 
34 
36 {
37 
41 template<class SegmentImpl>
42 class StopTrajectoryBuilder : public TrajectoryBuilder<SegmentImpl>
43 {
44 private:
46  using TrajectoryPerJoint = std::vector<Segment>;
47  using Trajectory = std::vector<TrajectoryPerJoint>;
48 
51 
52 public:
60  StopTrajectoryBuilder(const typename Segment::Time& stop_traj_duration,
61  const typename Segment::State& hold_state);
62 
63 public:
77  bool buildTrajectory(Trajectory* hold_traj) override;
78 
79 private:
82  const typename Segment::State& hold_state_;
83 
84 private: //Pre-allocated memory for real time usage of build function
87 };
88 
89 template<class SegmentImpl>
91  const typename Segment::State& hold_state)
92  : stop_traj_duration_(stop_traj_duration)
93  , hold_state_(hold_state)
94 {
95 }
96 
97 template<class SegmentImpl>
99 {
100  const unsigned int number_of_joints = hold_state_.position.size();
101 
103  {
104  return false;
105  }
106 
107  if(!TrajectoryBuilder<SegmentImpl>::isTrajectoryValid(hold_traj, number_of_joints, 1))
108  {
109  return false;
110  }
111 
112  const typename Segment::Time start_time {TrajectoryBuilder<SegmentImpl>::getStartTime().value()};
114  const typename Segment::Time end_time {start_time + stop_traj_duration_};
115  const typename Segment::Time end_time_2x {start_time + 2.0 * stop_traj_duration_};
116  for (unsigned int joint_index = 0; joint_index < number_of_joints; ++joint_index)
117  {
118  hold_start_state_.position[0] = hold_state_.position[joint_index];
119  hold_start_state_.velocity[0] = hold_state_.velocity[joint_index];
120  hold_start_state_.acceleration[0] = 0.0;
121 
122  hold_end_state_.position[0] = hold_state_.position[joint_index];
123  hold_end_state_.velocity[0] = -hold_state_.velocity[joint_index];
124  hold_end_state_.acceleration[0] = 0.0;
125 
126  Segment& segment {(*hold_traj)[joint_index].front()};
127  segment.init(start_time, hold_start_state_,
128  end_time_2x, hold_end_state_);
129  // Sample segment at its midpoint, that should have zero velocity
130  segment.sample(end_time, hold_end_state_);
131  // Now create segment that goes from current state to one with zero end velocity
132  segment.init(start_time, hold_start_state_,
133  end_time, hold_end_state_);
134 
135  segment.setGoalHandle(goal_handle);
136  }
137 
138  return true;
139 }
140 
141 
142 } // namespace joint_trajectory_controller
143 
144 #endif // STOP_TRAJECTORY_BUILDER_H
Builder creating a trajectory stopping the robot.
const Segment::State & hold_state_
Stores a reference to the state where the stop motion shall start.
void setGoalHandle(RealtimeGoalHandlePtr rt_goal_handle)
Set the (realtime) goal handle associated to this segment.
StopTrajectoryBuilder(const typename Segment::Time &stop_traj_duration, const typename Segment::State &hold_state)
Class representing a multi-dimensional quintic spline segment with a start and end time...
Base class for classes used to construct diffent trajectory types.
bool buildTrajectory(Trajectory *hold_traj) override
Creates a trajectory which reaches the settle position in a fixed time.
RealtimeGoalHandlePtr createGoalHandlePtr() const
Return the set goal handle or a default one, if no goal handle was set.
const boost::optional< typename Segment::Time > & getStartTime() const
Return the set start time.


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Feb 3 2023 03:19:15