$search
00001 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2009, Willow Garage, Inc. 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 #ifndef TRIGGER_CONTROLLER_H 00036 #define TRIGGER_CONTROLLER_H 00037 00038 #include <ros/node_handle.h> 00039 #include <pr2_controller_interface/controller.h> 00040 #include <pr2_mechanism_model/robot.h> 00041 #include <ethercat_trigger_controllers/SetWaveform.h> 00042 #include <realtime_tools/realtime_publisher.h> 00043 #include <roslib/Header.h> 00044 #include <boost/scoped_ptr.hpp> 00045 00052 namespace controller 00053 { 00054 typedef ethercat_trigger_controllers::SetWaveform::Request trigger_configuration; 00055 00056 class TriggerControllerNode; 00057 00058 class TriggerController : public pr2_controller_interface::Controller 00059 { 00060 public: 00061 TriggerController(); 00062 00063 ~TriggerController(); 00064 00065 void update(); 00066 00067 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n); 00068 00082 static double getTick(double t, trigger_configuration const &config) 00083 { 00084 return t * config.rep_rate - config.phase; 00085 } 00086 00101 static double getTick(const ros::Time &t, trigger_configuration const &config) 00102 { 00103 return getTick(t.toSec(), config); 00104 } 00105 00120 static double getTickStartTimeSecFromPhase(double tick, trigger_configuration const &config) 00121 { 00122 return (floor(tick) + config.phase) / config.rep_rate; 00123 } 00124 00139 static ros::Time getTickStartTimeFromPhase(double tick, trigger_configuration const &config) 00140 { 00141 return ros::Time(getTickStartTimeSecFromPhase(tick, config)); 00142 } 00143 00158 static ros::Time getTickStartTime(ros::Time time, trigger_configuration const &config) 00159 { 00160 return ros::Time(getTickStartTimeSec(time.toSec(), config)); 00161 } 00162 00177 static double getTickStartTimeSec(double time, trigger_configuration const &config) 00178 { 00179 return getTickStartTimeSecFromPhase(getTick(time, config), config); 00180 } 00181 00194 static ros::Duration getTickDuration(trigger_configuration &config) 00195 { 00196 return ros::Duration(getTickDurationSec(config)); 00197 } 00198 00211 static double getTickDurationSec(trigger_configuration &config) 00212 { 00213 if (!config.running) 00214 return 0; 00215 else if (config.pulsed) 00216 return 1e-3; // @todo the update rate should be in an include file somewhere. 00217 else 00218 return config.duty_cycle / config.rep_rate; 00219 } 00220 00221 private: 00222 double getTick(); 00223 00224 bool setWaveformSrv(trigger_configuration &req, 00225 ethercat_trigger_controllers::SetWaveform::Response &resp); 00226 00227 pr2_mechanism_model::RobotState * robot_; 00228 pr2_hardware_interface::DigitalOutCommand *digital_out_command_; 00229 00230 double prev_tick_; 00231 00232 ros::ServiceServer set_waveform_handle_; 00233 ros::NodeHandle node_handle_; 00234 00235 boost::scoped_ptr< 00236 realtime_tools::RealtimePublisher< 00237 roslib::Header> > rising_edge_pub_, falling_edge_pub_; 00238 bool last_out_; 00239 00240 // Configuration of controller. 00241 trigger_configuration config_; 00242 std::string actuator_name_; 00243 }; 00244 00245 }; 00246 00247 #endif 00248