hold_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 HOLD_TRAJECTORY_BUILDER_H
29 #define HOLD_TRAJECTORY_BUILDER_H
30 
31 #include <vector>
32 
34 
36 {
37 
42 template<class SegmentImpl, class HardwareInterface>
43 class HoldTrajectoryBuilder : public TrajectoryBuilder<SegmentImpl>
44 {
45 private:
47  using TrajectoryPerJoint = std::vector<Segment>;
48  using Trajectory = std::vector<TrajectoryPerJoint>;
49 
52 
53  using JointHandle = typename HardwareInterface::ResourceHandleType;
54 
55 public:
57  HoldTrajectoryBuilder(const std::vector<JointHandle>& joints);
58 
59 public:
63  bool buildTrajectory(Trajectory* hold_traj) override;
64 
65 private:
66  const std::vector<JointHandle>& joints_;
67 
68 private: //Pre-allocated memory for real time usage of build function
71 
72 };
73 
74 template<class SegmentImpl, class HardwareInterface>
76  : joints_(joints)
77 {
78 
79 }
80 
81 template<class SegmentImpl, class HardwareInterface>
83 {
85  {
86  return false;
87  }
88 
89  if(!TrajectoryBuilder<SegmentImpl>::isTrajectoryValid(hold_traj, joints_.size(), 1))
90  {
91  return false;
92  }
93 
94  const typename Segment::Time start_time {TrajectoryBuilder<SegmentImpl>::getStartTime().value()};
96  for (unsigned int joint_index = 0; joint_index < joints_.size(); ++joint_index)
97  {
98  hold_start_state_.position[0] = joints_[joint_index].getPosition();
99  hold_start_state_.velocity[0] = 0.0;
100  hold_start_state_.acceleration[0] = 0.0;
101 
102  Segment& segment {(*hold_traj)[joint_index].front()};
103  segment.init(start_time, hold_start_state_,
104  start_time, hold_start_state_);
105  segment.setGoalHandle(goal_handle);
106  }
107  return true;
108 }
109 
110 }
111 
112 #endif // HOLD_TRAJECTORY_BUILDER_H
joint_trajectory_controller::HoldTrajectoryBuilder::hold_end_state_
Segment::State hold_end_state_
Definition: hold_trajectory_builder.h:70
joint_trajectory_controller::HoldTrajectoryBuilder
Builder creating a trajectory "simply" holding (without motion) the specified position.
Definition: hold_trajectory_builder.h:43
joint_trajectory_controller::TrajectoryBuilder::createGoalHandlePtr
RealtimeGoalHandlePtr createGoalHandlePtr() const
Return the set goal handle or a default one, if no goal handle was set.
Definition: trajectory_builder.h:159
joint_trajectory_controller::HoldTrajectoryBuilder::joints_
const std::vector< JointHandle > & joints_
Definition: hold_trajectory_builder.h:66
boost::shared_ptr< RealtimeGoalHandle >
joint_trajectory_controller::TrajectoryBuilder::getStartTime
const boost::optional< typename Segment::Time > & getStartTime() const
Return the set start time.
Definition: trajectory_builder.h:146
joint_trajectory_controller::JointTrajectorySegment::Time
Segment::Time Time
Definition: joint_trajectory_segment.h:74
joint_trajectory_controller::HoldTrajectoryBuilder::HoldTrajectoryBuilder
HoldTrajectoryBuilder(const std::vector< JointHandle > &joints)
Definition: hold_trajectory_builder.h:75
joint_trajectory_controller::HoldTrajectoryBuilder::buildTrajectory
bool buildTrajectory(Trajectory *hold_traj) override
See base class.
Definition: hold_trajectory_builder.h:82
joint_trajectory_controller::HoldTrajectoryBuilder::JointHandle
typename HardwareInterface::ResourceHandleType JointHandle
Definition: hold_trajectory_builder.h:53
joint_trajectory_controller::JointTrajectorySegment::setGoalHandle
void setGoalHandle(RealtimeGoalHandlePtr rt_goal_handle)
Set the (realtime) goal handle associated to this segment.
Definition: joint_trajectory_segment.h:200
joint_trajectory_controller
Definition: hold_trajectory_builder.h:35
joint_trajectory_controller::JointTrajectorySegment::State
Definition: joint_trajectory_segment.h:79
joint_trajectory_controller::JointTrajectorySegment
Class representing a multi-dimensional quintic spline segment with a start and end time.
Definition: joint_trajectory_segment.h:70
joint_trajectory_controller::HoldTrajectoryBuilder::Trajectory
std::vector< TrajectoryPerJoint > Trajectory
Definition: hold_trajectory_builder.h:48
joint_trajectory_controller::HoldTrajectoryBuilder::hold_start_state_
Segment::State hold_start_state_
Definition: hold_trajectory_builder.h:69
realtime_tools::RealtimeServerGoalHandle
joint_trajectory_controller::TrajectoryBuilder
Base class for classes used to construct diffent trajectory types.
Definition: trajectory_builder.h:64
joint_trajectory_controller::HoldTrajectoryBuilder::TrajectoryPerJoint
std::vector< Segment > TrajectoryPerJoint
Definition: hold_trajectory_builder.h:47
trajectory_builder.h


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