cartesian_pose_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 
69 #ifndef CARTESIAN_POSE_CONTROLLER_H
70 #define CARTESIAN_POSE_CONTROLLER_H
71 
72 #include <vector>
73 #include <boost/scoped_ptr.hpp>
74 
75 #include <ros/node_handle.h>
76 
77 #include <geometry_msgs/PoseStamped.h>
78 #include <geometry_msgs/Twist.h>
79 
80 #include <control_toolbox/pid.h>
81 #include <kdl/chainfksolver.hpp>
82 #include <kdl/chain.hpp>
83 #include <kdl/chainjnttojacsolver.hpp>
84 #include <kdl/frames.hpp>
89 #include <tf/message_filter.h>
90 #include <tf/transform_datatypes.h>
91 #include <tf/transform_listener.h>
92 
93 
94 namespace controller {
95 
97 {
98 public:
101 
103  void starting();
104  void update();
105 
106  void command(const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
107 
108  // input of the controller
109  KDL::Frame pose_desi_, pose_meas_;
110  KDL::Twist twist_ff_;
111 
112  // state output
113  KDL::Twist twist_error_;
114 
115 private:
116  KDL::Frame getPose();
117 
121 
122  // robot structure
125 
126  // pid controllers
127  std::vector<control_toolbox::Pid> pid_controller_;
128 
129  // kdl stuff for kinematics
130  KDL::Chain kdl_chain_;
131  boost::scoped_ptr<KDL::ChainFkSolverPos> jnt_to_pose_solver_;
132  boost::scoped_ptr<KDL::ChainJntToJacSolver> jac_solver_;
133  KDL::JntArray jnt_pos_;
134  KDL::JntArray jnt_eff_;
135  KDL::Jacobian jacobian_;
136 
137  // reatltime publisher
138  boost::scoped_ptr<realtime_tools::RealtimePublisher<geometry_msgs::Twist> > state_error_publisher_;
139  boost::scoped_ptr<realtime_tools::RealtimePublisher<geometry_msgs::PoseStamped> > state_pose_publisher_;
140  unsigned int loop_count_;
141 
144  boost::scoped_ptr<tf::MessageFilter<geometry_msgs::PoseStamped> > command_filter_;
145  //boost::scoped_ptr<tf::MessageNotifier<geometry_msgs::PoseStamped> > command_notifier_;
146 };
147 
148 } // namespace
149 
150 
151 #endif
controller::CartesianPoseController::command_filter_
boost::scoped_ptr< tf::MessageFilter< geometry_msgs::PoseStamped > > command_filter_
Definition: cartesian_pose_controller.h:144
realtime_publisher.h
node_handle.h
controller::CartesianPoseController::root_name_
std::string root_name_
Definition: cartesian_pose_controller.h:119
controller::CartesianPoseController::kdl_chain_
KDL::Chain kdl_chain_
Definition: cartesian_pose_controller.h:130
controller::CartesianPoseController::CartesianPoseController
CartesianPoseController()
Definition: cartesian_pose_controller.cpp:52
controller::CartesianPoseController::tf_
tf::TransformListener tf_
Definition: cartesian_pose_controller.h:142
controller::CartesianPoseController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: cartesian_pose_controller.cpp:62
controller::CartesianPoseController::sub_command_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_command_
Definition: cartesian_pose_controller.h:143
controller::CartesianPoseController::twist_error_
KDL::Twist twist_error_
Definition: cartesian_pose_controller.h:113
pr2_mechanism_model::Chain
controller::CartesianPoseController::update
void update()
Definition: cartesian_pose_controller.cpp:138
controller::CartesianPoseController::controller_name_
std::string controller_name_
Definition: cartesian_pose_controller.h:119
controller::CartesianPoseController::starting
void starting()
Definition: cartesian_pose_controller.cpp:122
controller::CartesianPoseController::robot_state_
pr2_mechanism_model::RobotState * robot_state_
Definition: cartesian_pose_controller.h:123
controller::CartesianPoseController::chain_
pr2_mechanism_model::Chain chain_
Definition: cartesian_pose_controller.h:124
controller::CartesianPoseController::~CartesianPoseController
~CartesianPoseController()
Definition: cartesian_pose_controller.cpp:56
controller::CartesianPoseController::jnt_pos_
KDL::JntArray jnt_pos_
Definition: cartesian_pose_controller.h:133
controller::CartesianPoseController::jnt_to_pose_solver_
boost::scoped_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_
Definition: cartesian_pose_controller.h:131
controller::CartesianPoseController::state_pose_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::PoseStamped > > state_pose_publisher_
Definition: cartesian_pose_controller.h:139
controller::CartesianPoseController::jac_solver_
boost::scoped_ptr< KDL::ChainJntToJacSolver > jac_solver_
Definition: cartesian_pose_controller.h:132
controller::CartesianPoseController::pid_controller_
std::vector< control_toolbox::Pid > pid_controller_
Definition: cartesian_pose_controller.h:127
message_filters::Subscriber< geometry_msgs::PoseStamped >
controller::CartesianPoseController::twist_ff_
KDL::Twist twist_ff_
Definition: cartesian_pose_controller.h:110
controller::CartesianPoseController::loop_count_
unsigned int loop_count_
Definition: cartesian_pose_controller.h:140
controller.h
controller
message_filter.h
pr2_mechanism_model::RobotState
subscriber.h
controller::CartesianPoseController::jnt_eff_
KDL::JntArray jnt_eff_
Definition: cartesian_pose_controller.h:134
controller::CartesianPoseController::state_error_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > state_error_publisher_
Definition: cartesian_pose_controller.h:138
controller::CartesianPoseController::jacobian_
KDL::Jacobian jacobian_
Definition: cartesian_pose_controller.h:135
controller::CartesianPoseController
Definition: cartesian_pose_controller.h:96
pr2_controller_interface::Controller
transform_listener.h
transform_datatypes.h
ros::Time
chain.h
controller::CartesianPoseController::pose_meas_
KDL::Frame pose_meas_
Definition: cartesian_pose_controller.h:109
controller::CartesianPoseController::pose_desi_
KDL::Frame pose_desi_
Definition: cartesian_pose_controller.h:109
tf::TransformListener
pid.h
controller::CartesianPoseController::last_time_
ros::Time last_time_
Definition: cartesian_pose_controller.h:120
controller::CartesianPoseController::command
void command(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: cartesian_pose_controller.cpp:205
ros::NodeHandle
controller::CartesianPoseController::node_
ros::NodeHandle node_
Definition: cartesian_pose_controller.h:118
controller::CartesianPoseController::getPose
KDL::Frame getPose()
Definition: cartesian_pose_controller.cpp:193


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:22