00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * Copyright (c) 2010, Bosch LLC 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 /* 00036 * Author: Sachin Chitta and Matthew Piccoli (Willow Garage) 00037 * Sebastian Haug (Bosch LLC) 00038 */ 00039 00040 #include <ros/node_handle.h> 00041 #include <realtime_tools/realtime_publisher.h> 00042 #include <pr2_mechanism_controllers/BaseControllerState2.h> 00043 #include <robot_mechanism_controllers/joint_velocity_controller.h> 00044 #include <pr2_mechanism_controllers/base_kinematics.h> 00045 #include <geometry_msgs/Twist.h> 00046 #include <angles/angles.h> 00047 #include <boost/shared_ptr.hpp> 00048 #include <boost/scoped_ptr.hpp> 00049 #include <boost/thread/condition.hpp> 00050 #include <filters/transfer_function.h> 00051 00052 #include <safe_base_controller/TwistLimits.h> 00053 00054 namespace controller 00055 { 00059 class Pr2BaseController2Safe: public pr2_controller_interface::Controller 00060 { 00061 public: 00066 Pr2BaseController2Safe(); 00067 00072 ~Pr2BaseController2Safe(); 00073 00074 /* 00075 * \brief The starting method is called by the realtime thread just before 00076 * the first call to update. Overrides Controller.staring(). 00077 * @return Successful start 00078 */ 00079 void starting(); 00080 00081 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n); 00082 00083 /* 00084 * \brief callback function for setting the desired velocity using a topic 00085 * @param cmd_vel Velocity command of the base in m/s and rad/s 00086 */ 00087 void setCommand(const geometry_msgs::Twist &cmd_vel); 00088 00093 geometry_msgs::Twist getCommand(); 00094 00099 BaseKinematics base_kinematics_; 00100 00104 pthread_mutex_t pr2_base_controller_lock_; 00105 00110 void update(); 00111 00115 void setJointCommands(); 00116 00120 void setDesiredCasterSteer(); 00121 00122 private: 00123 00124 ros::NodeHandle node_; 00125 00126 ros::NodeHandle root_handle_; 00127 00128 ros::Subscriber cmd_sub_; 00129 00130 ros::Subscriber cmd_sub_deprecated_; 00131 00135 ros::Subscriber sub_cmd_limits; 00136 00140 bool paused_; 00141 00145 double timeout_; 00146 00150 double timeout_vel_limits_; 00151 00155 bool new_cmd_available_; 00156 00160 ros::Time last_time_; 00161 00165 ros::Time cmd_received_timestamp_; 00166 00171 geometry_msgs::Twist cmd_vel_t_; 00172 00176 geometry_msgs::Twist cmd_vel_; 00177 00181 geometry_msgs::Twist desired_vel_; 00182 00186 geometry_msgs::Twist max_vel_; 00187 00191 geometry_msgs::Twist max_accel_; 00192 00196 double max_translational_velocity_; 00197 00201 double max_rotational_velocity_; 00202 00206 double kp_caster_steer_; 00207 00211 double alpha_stall_; 00212 00216 std::vector<boost::shared_ptr<JointVelocityController> > wheel_controller_; 00217 00221 std::vector<boost::shared_ptr<JointVelocityController> > caster_controller_; 00222 00226 boost::scoped_ptr<realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState2> > state_publisher_; 00227 00231 void computeJointCommands(const double &dT); 00232 00236 void updateJointControllers(); 00237 00241 void computeDesiredCasterSteer(const double &dT); 00242 00246 void computeDesiredWheelSpeeds(const double &dT); 00247 00251 void setDesiredWheelSpeeds(); 00252 00256 geometry_msgs::Twist interpolateCommand(const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT); 00257 00261 void commandCallback(const geometry_msgs::TwistConstPtr& msg); 00262 00266 void cmdLimitsCB(const safe_base_controller::TwistLimits &cmd_limits); 00267 00271 double safe_max_x_; 00272 00276 double safe_min_x_; 00277 00281 double safe_max_y_; 00282 00286 double safe_min_y_; 00287 00291 double safe_max_z_; 00292 00296 double safe_min_z_; 00297 00301 ros::Time cmd_limits_timestamp_; 00302 00306 geometry_msgs::Twist base_vel_msg_; 00307 00311 double eps_; 00312 00316 double cmd_vel_rot_eps_; 00317 00321 double state_publish_time_, state_publish_rate_; 00322 00326 ros::Time last_publish_time_; 00327 00331 double cmd_vel_trans_eps_; 00332 00333 00337 void publishState(const ros::Time ¤t_time); 00338 00339 bool publish_state_; 00340 00344 std::vector<control_toolbox::Pid> caster_position_pid_; 00345 00346 filters::MultiChannelTransferFunctionFilter<double> caster_vel_filter_; 00347 00348 std::vector<double> filtered_velocity_; 00349 00350 filters::MultiChannelTransferFunctionFilter<double> wheel_vel_filter_; 00351 00352 std::vector<double> filtered_wheel_velocity_; 00353 00357 std::vector<control_toolbox::Pid> wheel_pid_controllers_; 00358 }; 00359 00360 }