cartesian_twist.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, Hanjun Song
40  */
41 
42 #ifndef ROBOT_CONTROLLERS_CARTESIAN_TWIST_H
43 #define ROBOT_CONTROLLERS_CARTESIAN_TWIST_H
44 
45 #include <string>
46 #include <vector>
47 #include <boost/shared_ptr.hpp>
48 
49 #include <ros/ros.h>
53 
54 #include <geometry_msgs/PoseStamped.h>
55 #include <geometry_msgs/TwistStamped.h>
56 
57 #include <kdl/chain.hpp>
58 #include <kdl/chainiksolvervel_wdls.hpp>
59 #include <kdl/chainfksolver.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 
67 
68 namespace robot_controllers
69 {
70 
72 {
73 public:
76 
84  virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
85 
91  virtual bool start();
92 
100  virtual bool stop(bool force);
101 
108  virtual bool reset();
109 
115  virtual void update(const ros::Time& now, const ros::Duration& dt);
116 
118  virtual std::string getType()
119  {
120  return "robot_controllers/CartesianTwistController";
121  }
122 
124  virtual std::vector<std::string> getCommandedNames();
125 
127  virtual std::vector<std::string> getClaimedNames();
128 
130  void command(const geometry_msgs::TwistStamped::ConstPtr& goal);
131 
132 private:
134 
137 
138  bool enabled_;
139 
146 
149 
150  std::vector<JointHandlePtr> joints_;
151 
152  boost::mutex mutex_;
154  std::string twist_command_frame_;
157 };
158 
159 } // namespace robot_controllers
160 
161 #endif // ROBOT_CONTROLLERS_CARTESIAN_TWIST_H
boost::shared_ptr< KDL::ChainIkSolverVel_wdls > solver_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
void command(const geometry_msgs::TwistStamped::ConstPtr &goal)
Controller command.
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > fksolver_
virtual std::string getType()
Get the type of this controller.
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
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...
goal
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
std::vector< JointHandlePtr > joints_


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