cartesian_pose.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  * Copyright (c) 2008, Willow Garage, Inc.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Unbounded Robotics nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /*
38  * Derived a bit from pr2_controllers/cartesian_pose_controller.cpp
39  * Author: Michael Ferguson, Wim Meeussen
40  */
41 
42 #ifndef ROBOT_CONTROLLERS_CARTESIAN_POSE_H
43 #define ROBOT_CONTROLLERS_CARTESIAN_POSE_H
44 
45 #include <string>
46 #include <vector>
47 #include <boost/shared_ptr.hpp>
48 
49 #include <ros/ros.h>
50 #include <robot_controllers/pid.h>
54 
55 #include <geometry_msgs/PoseStamped.h>
56 #include <geometry_msgs/Twist.h>
57 
58 #include <kdl/chain.hpp>
59 #include <kdl/chainjnttojacsolver.hpp>
60 #include <kdl/chainfksolverpos_recursive.hpp>
61 #include <kdl/frames.hpp>
62 
63 #include <tf/transform_datatypes.h>
64 #include <tf/transform_listener.h>
65 
66 namespace robot_controllers
67 {
68 
70 {
71 public:
74 
82  virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
83 
89  virtual bool start();
90 
98  virtual bool stop(bool force);
99 
106  virtual bool reset();
107 
113  virtual void update(const ros::Time& now, const ros::Duration& dt);
114 
116  virtual std::string getType()
117  {
118  return "robot_controllers/CartesianPoseController";
119  }
120 
122  virtual std::vector<std::string> getCommandedNames();
123 
125  virtual std::vector<std::string> getClaimedNames();
126 
128  void command(const geometry_msgs::PoseStamped::ConstPtr& goal);
129 
130 private:
132 
135 
136  bool enabled_;
137  std::string root_link_;
139 
142 
144 
151 
154 
156  std::vector<JointHandlePtr> joints_;
157  std::vector<robot_controllers::PID> pid_;
158 };
159 
160 } // namespace robot_controllers
161 
162 #endif // ROBOT_CONTROLLERS_CARTESIAN_POSE_H
std::vector< JointHandlePtr > joints_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual std::string getType()
Get the type of this controller.
void command(const geometry_msgs::PoseStamped::ConstPtr &goal)
Controller command.
boost::shared_ptr< KDL::ChainJntToJacSolver > jac_solver_
virtual bool start()
Attempt to start 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 bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
goal
std::vector< robot_controllers::PID > pid_
boost::shared_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.


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