caster_controller.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*
00031  * Author: Stuart Glaser
00032 
00033  Example config:
00034 
00035  <controller type="CasterController" name="a_caster">
00036    <joints caster="caster_joint" wheel_l="wheel_left_joint" wheel_r="wheel_right_joint">
00037    <caster_pid p="5.0" i="0.0" d="0.0" iClamp="0.0" />
00038    <wheel_pid p="4.0" i="0.0" d="0.0" iClamp="0.0" />
00039  </controller>
00040 
00041  YAML config
00042 \verbatim
00043 caster_fl:
00044   type: CasterController
00045   caster_pid: {p: 6.0}
00046   wheel_pid: {p: 4.0}
00047   joints:
00048     caster: fl_caster_rotation_joint
00049     wheel_l: fl_caster_l_wheel_joint
00050     wheel_r: fl_caster_r_wheel_joint
00051 \endverbatim
00052 
00053  */
00054 
00055 #ifndef CASTER_CONTROLLER_H
00056 #define CASTER_CONTROLLER_H
00057 
00058 #include "ros/node_handle.h"
00059 
00060 #include "pr2_controller_interface/controller.h"
00061 #include "pr2_mechanism_model/robot.h"
00062 #include "control_toolbox/pid.h"
00063 #include "robot_mechanism_controllers/joint_velocity_controller.h"
00064 #include "std_msgs/Float64.h"
00065 #include <boost/thread/condition.hpp>
00066 
00067 namespace controller {
00068 
00069 class CasterController : public pr2_controller_interface::Controller
00070 {
00071 public:
00072   const static double WHEEL_RADIUS;
00073   const static double WHEEL_OFFSET;
00074 
00075   CasterController();
00076   ~CasterController();
00077 
00078   bool init(pr2_mechanism_model::RobotState *robot_state,
00079             const std::string &caster_joint,
00080             const std::string &wheel_l_joint, const std::string &wheel_r_joint,
00081             const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid);
00082   bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00083 
00084   void update();
00085 
00086   double steer_velocity_;
00087   double drive_velocity_;
00088 
00089   double getSteerPosition() { return caster_->position_; }
00090   double getSteerVelocity() { return caster_->velocity_; }
00091 
00092   pr2_mechanism_model::JointState *caster_;
00093 
00094 private:
00095   ros::NodeHandle node_;
00096   JointVelocityController caster_vel_, wheel_l_vel_, wheel_r_vel_;
00097   ros::Subscriber steer_cmd_;
00098   ros::Subscriber drive_cmd_;
00099 
00100   void setSteerCB(const std_msgs::Float64ConstPtr& msg);
00101   void setDriveCB(const std_msgs::Float64ConstPtr& msg);
00102 };
00103 
00104 }
00105 
00106 #endif


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Thu Aug 27 2015 14:22:52