follow_joint_trajectory.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Fetch Robotics Inc.
5  * Copyright (c) 2013, Unbounded Robotics Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Unbounded Robotics nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 // Author: Michael Ferguson
37 
38 #ifndef ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H
39 #define ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H
40 
41 #include <string>
42 #include <vector>
43 #include <boost/shared_ptr.hpp>
44 #include <boost/thread.hpp>
45 
46 #include <ros/ros.h>
50 #include <control_msgs/FollowJointTrajectoryAction.h>
52 
53 #include <angles/angles.h>
56 
57 namespace robot_controllers
58 {
59 
66 {
68 
69 public:
72 
80  virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
81 
87  virtual bool start();
88 
96  virtual bool stop(bool force);
97 
104  virtual bool reset();
105 
111  virtual void update(const ros::Time& now, const ros::Duration& dt);
112 
114  virtual std::string getType()
115  {
116  return "robot_controllers/FollowJointTrajectoryController";
117  }
118 
120  virtual std::vector<std::string> getCommandedNames();
121 
123  virtual std::vector<std::string> getClaimedNames();
124 
125 private:
127  void executeCb(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal);
128 
130  TrajectoryPoint getPointFromCurrent(bool incl_vel, bool incl_acc, bool zero_vel);
131 
134 
135  std::vector<JointHandlePtr> joints_;
136  std::vector<std::string> joint_names_;
137  std::vector<bool> continuous_;
139 
141  boost::mutex sampler_mutex_;
142 
144 
147 
149  /*
150  * In certain cases, we want to start a trajectory at our last sample,
151  * for instance if we were pre-empted (as is often the case with teleop)
152  * we need to use the velocity and position of the last sample as a
153  * starting point.
154  */
156  bool preempted_;
157  bool has_path_tolerance_;
160 
164 
165  control_msgs::FollowJointTrajectoryFeedback feedback_;
167 };
168 
169 } // namespace robot_controllers
170 
171 #endif // ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H_
Basis for a Trajectory Point.
Definition: trajectory.h:51
control_msgs::FollowJointTrajectoryFeedback feedback_
This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) rob...
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
virtual std::string getType()
Get the type of this controller.
void executeCb(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
Callback for goal.
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > server_t
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
goal
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
TrajectoryPoint getPointFromCurrent(bool incl_vel, bool incl_acc, bool zero_vel)
Get a trajectory point from the current position/velocity/acceleration.
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39