joint_spline_trajectory_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
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  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
37 #ifndef JOINT_TRAJECTORY_CONTROLLER_H__
38 #define JOINT_TRAJECTORY_CONTROLLER_H__
39 
40 #include <vector>
41 
42 #include <boost/scoped_ptr.hpp>
43 #include <boost/thread/recursive_mutex.hpp>
44 #include <boost/thread/condition.hpp>
45 #include <ros/node_handle.h>
46 #include <control_toolbox/pid.h>
50 
51 #include "trajectory_msgs/JointTrajectory.h"
52 //#include "robot_mechanism_controllers/Trajectory.h"
53 #include "pr2_controllers_msgs/QueryTrajectoryState.h"
54 #include "pr2_controllers_msgs/JointTrajectoryControllerState.h"
55 
56 namespace controller {
57 
59 {
60 public:
61 
64 
66 
67  void starting();
68  void update();
69 
70 private:
74  std::vector<pr2_mechanism_model::JointState*> joints_;
75  std::vector<control_toolbox::Pid> pids_;
76 
78 
79  void commandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
81 
82  bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req,
83  pr2_controllers_msgs::QueryTrajectoryState::Response &resp);
85 
86  boost::scoped_ptr<
88  pr2_controllers_msgs::JointTrajectoryControllerState> > controller_state_publisher_;
89 
90 
91  // ------ Mechanisms for passing the trajectory into realtime
92 
93  // coef[0] + coef[1]*t + ... + coef[5]*t^5
94  struct Spline
95  {
96  std::vector<double> coef;
97 
98  Spline() : coef(6, 0.0) {}
99  };
100 
101  struct Segment
102  {
103  double start_time;
104  double duration;
105  std::vector<Spline> splines;
106  };
107  typedef std::vector<Segment> SpecifiedTrajectory;
108 
111 
112  // Holds the trajectory that we are currently following. The mutex
113  // guarding current_trajectory_ is locked from within realtime, so
114  // it may only be locked for a bounded duration.
115  //boost::shared_ptr<const SpecifiedTrajectory> current_trajectory_;
116  //boost::recursive_mutex current_trajectory_lock_RT_;
117 
118  std::vector<double> q, qd, qdd; // Preallocated in init
119 
120  // Samples, but handling time bounds. When the time is past the end
121  // of the spline duration, the position is the last valid position,
122  // and the derivatives are all 0.
123  static void sampleSplineWithTimeBounds(const std::vector<double>& coefficients, double duration, double time,
124  double& position, double& velocity, double& acceleration);
125 };
126 
127 }
128 
129 #endif
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
static void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
std::vector< pr2_mechanism_model::JointState * > joints_
bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req, pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
void commandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Mon Jun 10 2019 14:26:26