point_head.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_POINT_HEAD_H
39 #define ROBOT_CONTROLLERS_POINT_HEAD_H
40 
41 #include <string>
42 #include <vector>
43 
44 #include <ros/ros.h>
48 #include <tf/transform_listener.h>
49 #include <control_msgs/PointHeadAction.h>
51 
54 
55 #include <kdl/tree.hpp>
56 
57 namespace robot_controllers
58 {
59 
61 {
63 
64 public:
66  virtual ~PointHeadController() {}
67 
75  virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
76 
82  virtual bool start();
83 
91  virtual bool stop(bool force);
92 
99  virtual bool reset();
100 
106  virtual void update(const ros::Time& now, const ros::Duration& dt);
107 
109  virtual std::string getType()
110  {
111  return "robot_controllers/PointHeadController";
112  }
113 
115  virtual std::vector<std::string> getCommandedNames();
116 
118  virtual std::vector<std::string> getClaimedNames();
119 
120 private:
121  void executeCb(const control_msgs::PointHeadGoalConstPtr& goal);
122 
125 
126  control_msgs::PointHeadResult result_;
128  boost::mutex sampler_mutex_;
129 
131 
133  /*
134  * In certain cases, we want to start a trajectory at our last sample,
135  * for instance if we were pre-empted (as is often the case with teleop)
136  * we need to use the velocity and position of the last sample as a
137  * starting point.
138  */
140  bool preempted_;
141 
142  std::string root_link_;
146 
149 };
150 
151 } // namespace robot_controllers
152 
153 #endif // ROBOT_CONTROLLERS_POINT_HEAD_H
Basis for a Trajectory Point.
Definition: trajectory.h:51
control_msgs::PointHeadResult result_
Definition: point_head.h:126
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
Definition: point_head.cpp:162
std::string root_link_
action was preempted (has nothing to do with preempt() above
Definition: point_head.h:142
actionlib::SimpleActionServer< control_msgs::PointHeadAction > head_server_t
Definition: point_head.h:62
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
Definition: point_head.cpp:132
boost::shared_ptr< TrajectorySampler > sampler_
Definition: point_head.h:127
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
Definition: point_head.cpp:290
void executeCb(const control_msgs::PointHeadGoalConstPtr &goal)
Definition: point_head.cpp:195
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
Definition: point_head.cpp:113
goal
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
Definition: point_head.cpp:49
boost::shared_ptr< head_server_t > server_
Definition: point_head.h:145
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
Definition: point_head.cpp:156
virtual std::string getType()
Get the type of this controller.
Definition: point_head.h:109
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
Definition: point_head.cpp:298


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